22 #ifndef DYNAMIXEL_SDK_INCLUDE_DYNAMIXEL_SDK_PROTOCOL2PACKETHANDLER_H_
23 #define DYNAMIXEL_SDK_INCLUDE_DYNAMIXEL_SDK_PROTOCOL2PACKETHANDLER_H_
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);
65 const char *getTxRxResult (
int result);
72 const char *getRxPacketError (uint8_t error);
89 int txPacket (
PortHandler *port, uint8_t *txpacket);
110 int rxPacket (
PortHandler *port, uint8_t *rxpacket);
126 int txRxPacket (
PortHandler *port, uint8_t *txpacket, uint8_t *rxpacket, uint8_t *error = 0);
137 int ping (
PortHandler *port, uint8_t
id, uint8_t *error = 0);
155 int ping (
PortHandler *port, uint8_t
id, uint16_t *model_number, uint8_t *error = 0);
163 int broadcastPing (
PortHandler *port, std::vector<uint8_t> &id_list);
187 int reboot (
PortHandler *port, uint8_t
id, uint8_t *error = 0);
200 int clearMultiTurn (
PortHandler *port, uint8_t
id, uint8_t *error = 0);
213 int factoryReset (
PortHandler *port, uint8_t
id, uint8_t option, uint8_t *error = 0);
229 int readTx (
PortHandler *port, uint8_t
id, uint16_t address, uint16_t length);
241 int readRx (
PortHandler *port, uint8_t
id, uint16_t length, uint8_t *data, uint8_t *error = 0);
260 int readTxRx (
PortHandler *port, uint8_t
id, uint16_t address, uint16_t length, uint8_t *data, uint8_t *error = 0);
270 int read1ByteTx (
PortHandler *port, uint8_t
id, uint16_t address);
281 int read1ByteRx (
PortHandler *port, uint8_t
id, uint8_t *data, uint8_t *error = 0);
295 int read1ByteTxRx (
PortHandler *port, uint8_t
id, uint16_t address, uint8_t *data, uint8_t *error = 0);
305 int read2ByteTx (
PortHandler *port, uint8_t
id, uint16_t address);
316 int read2ByteRx (
PortHandler *port, uint8_t
id, uint16_t *data, uint8_t *error = 0);
330 int read2ByteTxRx (
PortHandler *port, uint8_t
id, uint16_t address, uint16_t *data, uint8_t *error = 0);
340 int read4ByteTx (
PortHandler *port, uint8_t
id, uint16_t address);
351 int read4ByteRx (
PortHandler *port, uint8_t
id, uint32_t *data, uint8_t *error = 0);
365 int read4ByteTxRx (
PortHandler *port, uint8_t
id, uint16_t address, uint32_t *data, uint8_t *error = 0);
378 int writeTxOnly (
PortHandler *port, uint8_t
id, uint16_t address, uint16_t length, uint8_t *data);
393 int writeTxRx (
PortHandler *port, uint8_t
id, uint16_t address, uint16_t length, uint8_t *data, uint8_t *error = 0);
404 int write1ByteTxOnly(
PortHandler *port, uint8_t
id, uint16_t address, uint8_t data);
417 int write1ByteTxRx (
PortHandler *port, uint8_t
id, uint16_t address, uint8_t data, uint8_t *error = 0);
428 int write2ByteTxOnly(
PortHandler *port, uint8_t
id, uint16_t address, uint16_t data);
441 int write2ByteTxRx (
PortHandler *port, uint8_t
id, uint16_t address, uint16_t data, uint8_t *error = 0);
452 int write4ByteTxOnly(
PortHandler *port, uint8_t
id, uint16_t address, uint32_t data);
465 int write4ByteTxRx (
PortHandler *port, uint8_t
id, uint16_t address, uint32_t data, uint8_t *error = 0);
479 int regWriteTxOnly (
PortHandler *port, uint8_t
id, uint16_t address, uint16_t length, uint8_t *data);
495 int regWriteTxRx (
PortHandler *port, uint8_t
id, uint16_t address, uint16_t length, uint8_t *data, uint8_t *error = 0);
509 int syncReadTx (
PortHandler *port, uint16_t start_address, uint16_t data_length, uint8_t *param, uint16_t param_length);
524 int syncWriteTxOnly (
PortHandler *port, uint16_t start_address, uint16_t data_length, uint8_t *param, uint16_t param_length);
535 int bulkReadTx (
PortHandler *port, uint8_t *param, uint16_t param_length);
548 int bulkWriteTxOnly (
PortHandler *port, uint8_t *param, uint16_t param_length);