22 #ifndef DYNAMIXEL_SDK_INCLUDE_DYNAMIXEL_SDK_PROTOCOL1PACKETHANDLER_H_
23 #define DYNAMIXEL_SDK_INCLUDE_DYNAMIXEL_SDK_PROTOCOL1PACKETHANDLER_H_
61 const char *getTxRxResult (
int result);
68 const char *getRxPacketError (uint8_t error);
85 int txPacket (
PortHandler *port, uint8_t *txpacket);
106 int rxPacket (
PortHandler *port, uint8_t *rxpacket);
122 int txRxPacket (
PortHandler *port, uint8_t *txpacket, uint8_t *rxpacket, uint8_t *error = 0);
133 int ping (
PortHandler *port, uint8_t
id, uint8_t *error = 0);
151 int ping (
PortHandler *port, uint8_t
id, uint16_t *model_number, uint8_t *error = 0);
159 int broadcastPing (
PortHandler *port, std::vector<uint8_t> &id_list);
179 int reboot (
PortHandler *port, uint8_t
id, uint8_t *error = 0);
188 int clearMultiTurn (
PortHandler *port, uint8_t
id, uint8_t *error = 0);
201 int factoryReset (
PortHandler *port, uint8_t
id, uint8_t option, uint8_t *error = 0);
217 int readTx (
PortHandler *port, uint8_t
id, uint16_t address, uint16_t length);
229 int readRx (
PortHandler *port, uint8_t
id, uint16_t length, uint8_t *data, uint8_t *error = 0);
248 int readTxRx (
PortHandler *port, uint8_t
id, uint16_t address, uint16_t length, uint8_t *data, uint8_t *error = 0);
258 int read1ByteTx (
PortHandler *port, uint8_t
id, uint16_t address);
269 int read1ByteRx (
PortHandler *port, uint8_t
id, uint8_t *data, uint8_t *error = 0);
283 int read1ByteTxRx (
PortHandler *port, uint8_t
id, uint16_t address, uint8_t *data, uint8_t *error = 0);
293 int read2ByteTx (
PortHandler *port, uint8_t
id, uint16_t address);
304 int read2ByteRx (
PortHandler *port, uint8_t
id, uint16_t *data, uint8_t *error = 0);
318 int read2ByteTxRx (
PortHandler *port, uint8_t
id, uint16_t address, uint16_t *data, uint8_t *error = 0);
328 int read4ByteTx (
PortHandler *port, uint8_t
id, uint16_t address);
339 int read4ByteRx (
PortHandler *port, uint8_t
id, uint32_t *data, uint8_t *error = 0);
353 int read4ByteTxRx (
PortHandler *port, uint8_t
id, uint16_t address, uint32_t *data, uint8_t *error = 0);
366 int writeTxOnly (
PortHandler *port, uint8_t
id, uint16_t address, uint16_t length, uint8_t *data);
381 int writeTxRx (
PortHandler *port, uint8_t
id, uint16_t address, uint16_t length, uint8_t *data, uint8_t *error = 0);
392 int write1ByteTxOnly(
PortHandler *port, uint8_t
id, uint16_t address, uint8_t data);
405 int write1ByteTxRx (
PortHandler *port, uint8_t
id, uint16_t address, uint8_t data, uint8_t *error = 0);
416 int write2ByteTxOnly(
PortHandler *port, uint8_t
id, uint16_t address, uint16_t data);
429 int write2ByteTxRx (
PortHandler *port, uint8_t
id, uint16_t address, uint16_t data, uint8_t *error = 0);
440 int write4ByteTxOnly(
PortHandler *port, uint8_t
id, uint16_t address, uint32_t data);
453 int write4ByteTxRx (
PortHandler *port, uint8_t
id, uint16_t address, uint32_t data, uint8_t *error = 0);
467 int regWriteTxOnly (
PortHandler *port, uint8_t
id, uint16_t address, uint16_t length, uint8_t *data);
483 int regWriteTxRx (
PortHandler *port, uint8_t
id, uint16_t address, uint16_t length, uint8_t *data, uint8_t *error = 0);
494 int syncReadTx (
PortHandler *port, uint16_t start_address, uint16_t data_length, uint8_t *param, uint16_t param_length);
509 int syncWriteTxOnly (
PortHandler *port, uint16_t start_address, uint16_t data_length, uint8_t *param, uint16_t param_length);
520 int bulkReadTx (
PortHandler *port, uint8_t *param, uint16_t param_length);
531 int bulkWriteTxOnly (
PortHandler *port, uint8_t *param, uint16_t param_length);