protocol2_packet_handler.h
Go to the documentation of this file.
1 /*******************************************************************************
2 * Copyright 2017 ROBOTIS CO., LTD.
3 *
4 * Licensed under the Apache License, Version 2.0 (the "License");
5 * you may not use this file except in compliance with the License.
6 * You may obtain a copy of the License at
7 *
8 * http://www.apache.org/licenses/LICENSE-2.0
9 *
10 * Unless required by applicable law or agreed to in writing, software
11 * distributed under the License is distributed on an "AS IS" BASIS,
12 * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
13 * See the License for the specific language governing permissions and
14 * limitations under the License.
15 *******************************************************************************/
16 
21 
22 #ifndef DYNAMIXEL_SDK_INCLUDE_DYNAMIXEL_SDK_PROTOCOL2PACKETHANDLER_H_
23 #define DYNAMIXEL_SDK_INCLUDE_DYNAMIXEL_SDK_PROTOCOL2PACKETHANDLER_H_
24 
25 
26 #include "packet_handler.h"
27 
28 namespace dynamixel
29 {
30 
34 class WINDECLSPEC Protocol2PacketHandler : public PacketHandler
35 {
36  private:
38 
40 
41  uint16_t updateCRC(uint16_t crc_accum, uint8_t *data_blk_ptr, uint16_t data_blk_size);
42  void addStuffing(uint8_t *packet);
43  void removeStuffing(uint8_t *packet);
44 
45  public:
50  static Protocol2PacketHandler *getInstance() { return unique_instance_; }
51 
53 
58  float getProtocolVersion() { return 2.0; }
59 
65  const char *getTxRxResult (int result);
66 
72  const char *getRxPacketError (uint8_t error);
73 
89  int txPacket (PortHandler *port, uint8_t *txpacket);
90 
110  int rxPacket (PortHandler *port, uint8_t *rxpacket);
111 
126  int txRxPacket (PortHandler *port, uint8_t *txpacket, uint8_t *rxpacket, uint8_t *error = 0);
127 
137  int ping (PortHandler *port, uint8_t id, uint8_t *error = 0);
138 
155  int ping (PortHandler *port, uint8_t id, uint16_t *model_number, uint8_t *error = 0);
156 
163  int broadcastPing (PortHandler *port, std::vector<uint8_t> &id_list);
164 
174  int action (PortHandler *port, uint8_t id);
175 
187  int reboot (PortHandler *port, uint8_t id, uint8_t *error = 0);
188 
200  int clearMultiTurn (PortHandler *port, uint8_t id, uint8_t *error = 0);
201 
213  int factoryReset (PortHandler *port, uint8_t id, uint8_t option, uint8_t *error = 0);
214 
229  int readTx (PortHandler *port, uint8_t id, uint16_t address, uint16_t length);
230 
241  int readRx (PortHandler *port, uint8_t id, uint16_t length, uint8_t *data, uint8_t *error = 0);
242 
260  int readTxRx (PortHandler *port, uint8_t id, uint16_t address, uint16_t length, uint8_t *data, uint8_t *error = 0);
261 
270  int read1ByteTx (PortHandler *port, uint8_t id, uint16_t address);
271 
281  int read1ByteRx (PortHandler *port, uint8_t id, uint8_t *data, uint8_t *error = 0);
282 
295  int read1ByteTxRx (PortHandler *port, uint8_t id, uint16_t address, uint8_t *data, uint8_t *error = 0);
296 
305  int read2ByteTx (PortHandler *port, uint8_t id, uint16_t address);
306 
316  int read2ByteRx (PortHandler *port, uint8_t id, uint16_t *data, uint8_t *error = 0);
317 
330  int read2ByteTxRx (PortHandler *port, uint8_t id, uint16_t address, uint16_t *data, uint8_t *error = 0);
331 
340  int read4ByteTx (PortHandler *port, uint8_t id, uint16_t address);
341 
351  int read4ByteRx (PortHandler *port, uint8_t id, uint32_t *data, uint8_t *error = 0);
352 
365  int read4ByteTxRx (PortHandler *port, uint8_t id, uint16_t address, uint32_t *data, uint8_t *error = 0);
366 
378  int writeTxOnly (PortHandler *port, uint8_t id, uint16_t address, uint16_t length, uint8_t *data);
379 
393  int writeTxRx (PortHandler *port, uint8_t id, uint16_t address, uint16_t length, uint8_t *data, uint8_t *error = 0);
394 
404  int write1ByteTxOnly(PortHandler *port, uint8_t id, uint16_t address, uint8_t data);
405 
417  int write1ByteTxRx (PortHandler *port, uint8_t id, uint16_t address, uint8_t data, uint8_t *error = 0);
418 
428  int write2ByteTxOnly(PortHandler *port, uint8_t id, uint16_t address, uint16_t data);
429 
441  int write2ByteTxRx (PortHandler *port, uint8_t id, uint16_t address, uint16_t data, uint8_t *error = 0);
442 
452  int write4ByteTxOnly(PortHandler *port, uint8_t id, uint16_t address, uint32_t data);
453 
465  int write4ByteTxRx (PortHandler *port, uint8_t id, uint16_t address, uint32_t data, uint8_t *error = 0);
466 
479  int regWriteTxOnly (PortHandler *port, uint8_t id, uint16_t address, uint16_t length, uint8_t *data);
480 
495  int regWriteTxRx (PortHandler *port, uint8_t id, uint16_t address, uint16_t length, uint8_t *data, uint8_t *error = 0);
496 
497 
509  int syncReadTx (PortHandler *port, uint16_t start_address, uint16_t data_length, uint8_t *param, uint16_t param_length);
510  // SyncReadRx -> GroupSyncRead class
511  // SyncReadTxRx -> GroupSyncRead class
512 
524  int syncWriteTxOnly (PortHandler *port, uint16_t start_address, uint16_t data_length, uint8_t *param, uint16_t param_length);
525 
535  int bulkReadTx (PortHandler *port, uint8_t *param, uint16_t param_length);
536  // BulkReadRx -> GroupBulkRead class
537  // BulkReadTxRx -> GroupBulkRead class
538 
548  int bulkWriteTxOnly (PortHandler *port, uint8_t *param, uint16_t param_length);
549 };
550 
551 }
552 
553 
554 #endif /* DYNAMIXEL_SDK_INCLUDE_DYNAMIXEL_SDK_PROTOCOL2PACKETHANDLER_H_ */
static Protocol2PacketHandler * unique_instance_
bool param(const std::string &param_name, T &param_val, const T &default_val)
The class that inherits Protocol1PacketHandler class or Protocol2PacketHandler class.
The class for port control that inherits PortHandlerLinux, PortHandlerWindows, PortHandlerMac, or PortHandlerArduino.
Definition: port_handler.h:56
The class for control Dynamixel by using Protocol2.0.
float getProtocolVersion()
The function that returns Protocol version used in Protocol2PacketHandler (2.0)
static Protocol2PacketHandler * getInstance()
The function that returns Protocol2PacketHandler instance.


dynamixel_sdk
Author(s): Gilbert , Zerom , Darby Lim , Leon
autogenerated on Fri Apr 16 2021 02:25:55