Skip to main content

cpp_packethandler

CPP PacketHandler

  • Description

Base class for packet construction.

  • Members

    None

  • Methods

MethodsDescription
getPacketHandlerGets PacketHandler from either of Protocols
~PacketHandlerNone
getProtocolVersionGets Protocol version
printTxRxResultShows communication result
printRxPacketErrorShows hardware error
txPacketTransmits the packet
rxPacketReceives the packet
txRxPacketTransmits and receives the packet
pingPing DYNAMIXEL
broadcastPingPing all connected DYNAMIXEL's
actionCommands ‘Run’ the Regwritten
regWriteWrites the packets and wait for the ‘Action’ command
rebootReboots DYNAMIXEL
factoryResetResets all DYNAMIXEL settings
readTxTransmits N byte read instruction packet
readRxReceives N byte read status packet
readTxRxTransmits and receives N byte packet
read1ByteTxTransmits 1 byte read instruction packet
read1ByteRxReceives 1 byte read status packet
read1ByteTxRxTransmits and receives 1 byte packet
read2ByteTxTransmits 2 byte read instruction packet
read2ByteRxReceives 2 byte read status packet
read2ByteTxRxTransmits and receives 2 byte packet
read4ByteTxTransmits 4 byte read instruction packet
read4ByteRxReceives 4 byte read status packet
read4ByteTxRxTransmits and receives 4 byte packet
writeTxOnlyTransmits N byte write instruction packet
writeTxRxTransmits and receives N byte packet
write1ByteTxOnlyTransmits 1 byte write instruction packet
write1ByteTxRxTransmits and receives 1 byte packet
write2ByteTxOnlyTransmits 2 byte write instruction packet
write2ByteTxRxTransmits and receives 2 byte packet
write4ByteTxOnlyTransmits 4 byte write instruction packet
write4ByteTxRxTransmits and receives 4 byte packet
regWriteTxOnlyTransmits register write instruction packet
regWriteTxRxTransmits and receives register write packet
syncReadTxTransmits N byte sync read Instruction packet
syncWriteTxOnlyTransmits N byte sync write Instruction packet
bulkReadTxTransmits N byte bulk read Instruction packet
bulkWriteTxOnlyTransmits N byte bulk write Instruction packet
  • Enumerator
EnumeratorDescription
DXL_MAKEWORD(a, b)Makes value from a and b to word type
DXL_MAKEDWORD(a, b)Makes value from a and b to dword type
DXL_LOWORD(l)Gets lower word type value from l
DXL_HIWORD(l)Gets higher word type value from l
DXL_LOBYTE(w)Gets lower byte type value from w
DXL_HIBYTE(w)Gets higher byte type value from w
BROADCAST_ID:= 0xFE Broadcast ID
MAX_ID:= 0xFC Maximum ID value
INST_PING:= 1 Instruction value of Ping
INST_READ:= 2 Instruction value of Read
INST_WRITE:= 3 Instruction value of Write
INST_REG_WRITE:= 4 Instruction value of Register Write
INST_ACTION:= 5 Instruction value of Action
INST_FACTORY_RESET:= 6 Instruction value of Factory Reset
INST_SYNC_WRITE:= 131 Instruction value of Sync Write
INST_BULK_READ:= 146 Instruction value of Bulk Read
INST_REBOOT:= 8 Instruction value of Reboot
INST_STATUS:= 85 Instruction value of Status
INST_SYNC_READ:= 130 Instruction value of Sync Read
INST_BULK_WRITE:= 147 Instruction value of Bulk Write
COMM_SUCCESS:= 0 Status of Communication Success
COMM_PORT_BUSY:= -1000 Status of Port in use
COMM_TX_FAIL:= -1001 Status of Transmit packet failed
COMM_RX_FAIL:= -1002 Status of Receive packet failed
COMM_TX_ERROR:= -2000 Status of Transmit packet error
COMM_RX_WAITING:= -3000 Status of Receive packet waiting
COMM_RX_TIMEOUT:= -3001 Status of Receive packet timeout
COMM_RX_CORRUPT:= -3002 Status of Receive packet corrupt
COMM_NOT_AVAILABLE:= -9000 Status of Unavailable in protocol 1.0

Method References

Protocol1 Packet Handler

Protocol2 Packet Handler

CPP Protocol1PacketHandler

  • Description

    Child class for packet construction using Protocol 1.0.

  • Members

    None

  • Methods

MethodsDescription
getInstanceGets instance of this class
~Protocol1PacketHandlerNone
getProtocolVersionGets Protocol version
printTxRxResultShows communication result
printRxPacketErrorShows hardware error
txPacketTransmits the packet
rxPacketReceives the packet
txRxPacketTransmits and receives the packet
pingPing DYNAMIXEL
broadcastPingNot available in Protocol 1.0
actionCommands ‘Run’ the Regwritten
regWriteWrites the packets and wait for the ‘Action’ command
rebootNot available in Protocol 1.0
factoryResetResets all DYNAMIXEL settings
readTxTransmits N byte read instruction packet
readRxReceives N byte read status packet
readTxRxTransmits and receives N byte packet
read1ByteTxTransmits 1 byte read instruction packet
read1ByteRxReceives 1 byte read status packet
read1ByteTxRxTransmits and receives 1 byte packet
read2ByteTxTransmits 2 byte read instruction packet
read2ByteRxReceives 2 byte read status packet
read2ByteTxRxTransmits and receives 2 byte packet
read4ByteTxNot available in Protocol 1.0
read4ByteRxNot available in Protocol 1.0
read4ByteTxRxNot available in Protocol 1.0
writeTxOnlyTransmits N byte write instruction packet
writeTxRxTransmits and receives N byte packet
write1ByteTxOnlyTransmits 1 byte write instruction packet
write1ByteTxRxTransmits and receives 1 byte packet
write2ByteTxOnlyTransmits 2 byte write instruction packet
write2ByteTxRxTransmits and receives 2 byte packet
write4ByteTxOnlyNot available in Protocol 1.0
write4ByteTxRxNot available in Protocol 1.0
regWriteTxOnlyTransmits register write instruction packet
regWriteTxRxTransmits and receives register write packet
syncReadTxNot available in Protocol 1.0
syncWriteTxOnlyTransmits N byte sync write Instruction packet
bulkReadTxTransmits N byte bulk read Instruction packet
bulkWriteTxOnlyNot available in Protocol 1.0
  • Enumerator

    None

Method References

getProtocolVersion
  • Syntax
float getProtocolVersion()
  • Parameters

    None

  • Detailed Description

    This function returns the protocol version set in the PacketHandler as a float value.

printTxRxResult
  • Syntax
void printTxRxResult(int result)
  • Parameters
ParametersDescription
resultCommunication result
  • Detailed Description

    This function prints out on the console window what communication result value means.

printRxPacketError
  • Syntax
void printRxPacketError(uint8_t error)
  • Parameters
ParametersDescription
errorHardware error
  • Detailed Description

    This function prints out on the console window what hardware error value means.

txPacket
  • Syntax
int txPacket(PortHandler *port, UINT8_T *txpacket)
  • Parameters
ParametersDescription
portPortHandler instance
txpacketpacket for transmission
  • Detailed Description

    This function transmits the packet. The function clears the port by clearPort() function at first, and passes the txpacket to the writePort() function. The function activates while the port is not busy, and when the packet is written on the port buffer.

rxPacket
  • Syntax
int rxPacket(PortHandler *port, UINT8_T *rxpacket)
  • Parameters
ParametersDescription
portPortHandler instance
rxpacketpacket for reception
  • Detailed Description

    This function repeatedly tries to receive packets by readPort() function until whole packets that it waits to get have arrived, or the packet wait time limit is over. After, it returns communication status value.

txRxPacket
  • Syntax
int txRxPacket(PortHandler *port, UINT8_T *txpacket, UINT8_T *rxpacket, UINT8_T *error = 0)
  • Parameters
ParametersDescription
portPortHandler instance
txpacketpacket for transmission
rxpacketpacket for reception
errorDYNAMIXEL error
  • Detailed Description

    This function transmits and receives packets by txPacket() and rxPacket() functions. When txPacket() function succeeds to communicate, it will continue to rxPacket() and finishes the process if the packet succeeds to be received. In case of using the group handler functions for write, such as SyncWrite, and BulkWrite, they don’t use rxPacket(), so the function finishes its operation immediately after the txPacket(). Before the rxPacket(), it sets packet timeout if the packet instruction is INST_READ.

ping
  • Syntax
int ping (PortHandler *port, UINT8_T id, UINT8_T *error = 0)
int ping (PortHandler *port, UINT8_T id, UINT16_T *model_number, UINT8_T *error = 0)
  • Parameters
ParametersDescription
portPortHandler instance
idDYNAMIXEL ID
errorDYNAMIXEL error
  • Detailed Description

    This function constructs the transmission packet with INST_PING instruction, and txRxPacket(). Then, the function tries to get the model number of the DYNAMIXEL by ReadTxRx() function. When it succeeds to receive the packet, it makes the model number value by using DXL_MAKEWORD() to put two byte-type data together. Finally, it returns communication status value.

broadcastPing
  • Syntax
int broadcastPing(PortHandler *port, std::vector<UINT8_T> &id_list)
  • Parameters
ParametersDescription
portPortHandler instance
id_listDYNAMIXEL ID list
  • Detailed Description

    This function is not available with the DYNAMIXEL Protocol 1.0. It returns COMM_NOT_AVAILABLE status.

action
  • Syntax
int action(PortHandler *port, UINT8_T id)
  • Parameters
ParametersDescription
portPortHandler instance
idDYNAMIXEL ID
  • Detailed Description

    This function constructs the transmission packet with INST_ACTION instruction, and txRxPacket(). Before using this function, the orders for the DYNAMIXEL's should be already written in the register in DYNAMIXEL by RegWrite function. Finally, it returns communication status value.

reboot
  • Syntax
int reboot(PortHandler *port, UINT8_T id, UINT8_T *error)
  • Parameters
ParametersDescription
portPortHandler instance
idDYNAMIXEL ID
errorDYNAMIXEL error
  • Detailed Description

    This function is not available with the DYNAMIXEL Protocol 1.0. It returns COMM_NOT_AVAILABLE status.

factoryReset
  • Syntax
int factoryReset(PortHandler *port, UINT8_T id, UINT8_T option, UINT8_T *error)
  • Parameters
ParametersDescription
portPortHandler instance
idDYNAMIXEL ID
optionReset option
errorDYNAMIXEL error
  • Detailed Description

    This function constructs the transmission packet with INST_FACTORY_RESET instruction, and txRxPacket(). This resets all DYNAMIXEL settings to the factory default settings. The option is not available in DYNAMIXEL Protocol 1.0. Finally, it returns communication status.

readTx
  • Syntax
int readTx(PortHandler *port, UINT8_T id, UINT16_T address, UINT16_T length)
  • Parameters
ParametersDescription
portPortHandler instance
idDYNAMIXEL ID
addressAddress on the control table of DYNAMIXEL
lengthPacket length
  • Detailed Description

    This function constructs the transmission packet with INST_READ instruction, and txPacket(). Then the function calls setPacketTimeout() function when txPacket() succeeds. This function is not available for controlling more than one DYNAMIXEL. Finally, it returns communication status.

readRx
  • Syntax
int readRx(PortHandler *port, UINT16_T length, UINT8_T *data, UINT8_T *error)
  • Parameters
ParametersDescription
portPortHandler instance
lengthPacket length
dataPacket data
errorDYNAMIXEL error
  • Detailed Description

    This function calls rxPacket() function and gets the reception packet if the communication succeeds. Finally, it returns communication status value.

readTxRx
  • Syntax
int readTxRx(PortHandler *port, UINT8_T id, UINT16_T address, UINT16_T length, UINT8_T *data, UINT8_T *error)
  • Parameters
ParametersDescription
portPortHandler instance
idDYNAMIXEL ID
addressAddress on the control table of DYNAMIXEL
lengthPacket length
dataPacket data
errorDYNAMIXEL error
  • Detailed Description

    This function calls readTx() function and readRx() function. readRx() function will be called when readTx() succeeds. Finally, it returns communication status value.

read1ByteTx
  • Syntax
int read1ByteTx(PortHandler *port, UINT8_T id, UINT16_T address)
  • Parameters
ParametersDescription
portPortHandler instance
idDYNAMIXEL ID
addressAddress on the control table of DYNAMIXEL
  • Detailed Description

    This function calls readTx() function for 1 Byte packet transmission. Finally, it returns communication status.

read1ByteRx
  • Syntax
int read1ByteRx(PortHandler *port, UINT8_T *data, UINT8_T *error)
  • Parameters
ParametersDescription
portPortHandler instance
dataPacket data
errorDYNAMIXEL error
  • Detailed Description

    This function calls readRx() function for 1 Byte packet reception. Finally, it returns communication status.

read1ByteTxRx
  • Syntax
int read1ByteTxRx(PortHandler *port, UINT8_T id,UINT16_T address, UINT8_T *data, UINT8_T *error)
  • Parameters
ParametersDescription
portPortHandler instance
idDYNAMIXEL ID
addressAddress on the control table of DYNAMIXEL
dataPacket data
errorDYNAMIXEL error
  • Detailed Description

    This function calls read1ByteTx() function and read1ByteRx() function for 1 Byte packet transmission and reception. read1ByteRx() function will be called when read1ByteTx() succeeds. Finally, it returns communication status.

read2ByteTx
  • Syntax
int read2ByteTx(PortHandler *port, UINT8_T id, UINT16_T address)
  • Parameters
ParametersDescription
portPortHandler instance
idDYNAMIXEL ID
addressAddress on the control table of DYNAMIXEL
  • Detailed Description

    This function calls readTx() function for 2 Byte packet transmission. Finally, it returns communication status.

read2ByteRx
  • Syntax
int read2ByteRx(PortHandler *port, UINT16_T *data, UINT8_T *error)
  • Parameters
ParametersDescription
portPortHandler instance
dataPacket data
errorDYNAMIXEL error
  • Detailed Description

    This function calls readRx() function for 2 Byte packet reception. Finally, it returns communication status.

read2ByteTxRx
  • Syntax
int read2ByteTxRx(PortHandler *port, UINT8_T id,UINT16_T address, UIN16_T *data, UINT8_T *error)
  • Parameters
ParametersDescription
portPortHandler instance
idDYNAMIXEL ID
addressAddress on the control table of DYNAMIXEL
dataPacket data
errorDYNAMIXEL error
  • Detailed Description

    This function calls read2ByteTx() function and read2ByteRx() function for 2 Byte packet transmission and reception. read2ByteRx() function will be called when read2ByteTx() succeeds. Finally, it returns communication status.

read4ByteTx
  • Syntax
int read4ByteTx(PortHandler *port, UINT8_T id, UINT16_T address)
  • Parameters
ParametersDescription
portPortHandler instance
idDYNAMIXEL ID
addressAddress on the control table of DYNAMIXEL
  • Detailed Description

    This function is not available with the DYNAMIXEL Protocol 1.0. It returns COMM_NOT_AVAILABLE status.

read4ByteRx
  • Syntax
int read4ByteRx(PortHandler *port, UINT32_T *data, UINT8_T *error)
  • Parameters
ParametersDescription
portPortHandler instance
dataPacket data
errorDYNAMIXEL error
  • Detailed Description

    This function is not available with the DYNAMIXEL Protocol 1.0. It returns COMM_NOT_AVAILABLE status.

read4ByteTxRx
  • Syntax
int read4ByteTxRx(PortHandler *port, UIN8_T id, UINT16_T address, UINT32_T *data, UINT8_T *error)
  • Parameters
ParametersDescription
portPortHandler instance
idDYNAMIXEL ID
addressAddress on the control table of DYNAMIXEL
dataData for write
errorDYNAMIXEL error
  • Detailed Description

    This function is not available with the DYNAMIXEL Protocol 1.0. It returns COMM_NOT_AVAILABLE status.

writeTxOnly
  • Syntax
int writeTxOnly(PortHandler *port, UINT8_T id, UINT16_T address, UINT16_T length, UINT8_T *data)
  • Parameters
ParametersDescription
portPortHandler instance
idDYNAMIXEL ID
addressAddress on the control table of DYNAMIXEL
lengthPacket length
dataData for write
  • Detailed Description

    This function constructs the transmission packet with INST_WRITE instruction, and txPacket(). Finally, it returns communication status.

writeTxRx
  • Syntax
int writeTxRx(PortHandler *port, UINT8_T id, UINT16_T address, UINT16_T length, UINT8_T *data, UINT8_T *error)
  • Parameters
ParametersDescription
portPortHandler instance
idDYNAMIXEL ID
addressAddress on the control table of DYNAMIXEL
lengthPacket length
dataData for write
errorDYNAMIXEL error
  • Detailed Description

    This function constructs the transmission packet with INST_WRITE instruction, and txRxPacket(). Finally, it returns communication status.

write1ByteTxOnly
  • Syntax
int write1ByteTxOnly(PortHandler *port, UINT8_T id, UINT16_T address, UINT8_T data)
  • Parameters
ParametersDescription
portPortHandler instance
idDYNAMIXEL ID
addressAddress on the control table of DYNAMIXEL
dataData for write
  • Detailed Description

    This function calls writeTxOnly() function for 1 Byte packet. Finally, it returns communication status.

write1ByteTxRx
  • Syntax
int write1ByteTxRx(PortHandler *port, UINT8_T id, UINT16_T address, UINT8_T data, UINT8_T *error)
  • Parameters
ParametersDescription
portPortHandler instance
idDYNAMIXEL ID
addressAddress on the control table of DYNAMIXEL
dataData for write
errorDYNAMIXEL error
  • Detailed Description

    This function calls writeTxRx() function for 1 Byte packet transmission and reception. Finally, it returns communication status.

write2ByteTxOnly
  • Syntax
int write2ByteTxOnly(PortHandler *port, UINT8_T id, UINT16_T address, UINT16_T data)
  • Parameters
ParametersDescription
portPortHandler instance
idDYNAMIXEL ID
addressAddress on the control table of DYNAMIXEL
dataData for write
  • Detailed Description

    This function calls writeTxOnly() function for 2 Byte packet. Finally, it returns communication status.

write2ByteTxRx
  • Syntax
int write2ByteTxRx(PortHandler *port, UINT8_T id, UINT16_T address, UINT16_T data, UINT8_T *error)
  • Parameters
ParametersDescription
portPortHandler instance
idDYNAMIXEL ID
addressAddress on the control table of DYNAMIXEL
dataData for write
errorDYNAMIXEL error
  • Detailed Description

    This function calls writeTxRx() function for 2Byte packet transmission and reception. Finally, it returns communication status.

write4ByteTxOnly
  • Syntax
int write1ByteTxOnly(PortHandler *port, UINT8_T id, UINT16_T address, UINT32_T data)
  • Parameters
ParametersDescription
portPortHandler instance
idDYNAMIXEL ID
addressAddress on the control table of DYNAMIXEL
dataData for write
  • Detailed Description

    This function is not available with the DYNAMIXEL Protocol 1.0. It returns COMM_NOT_AVAILABLE status.

write4ByteTxRx
  • Syntax
int write4ByteTxRx(PortHandler *port, UINT8_T id, UINT16_T address, UINT32_T data, UINT8_T *error)
  • Parameters
ParametersDescription
portPortHandler instance
idDYNAMIXEL ID
addressAddress on the control table of DYNAMIXEL
dataData for write
errorDYNAMIXEL error
  • Detailed Description

    This function is not available with the DYNAMIXEL Protocol 1.0. It returns COMM_NOT_AVAILABLE status.

regWriteTxOnly
  • Syntax
int RegWriteTxOnly(PortHandler *port, UINT8_T id, UINT16_T address, UINT16_T length, UINT8_T *data)
  • Parameters
ParametersDescription
portPortHandler instance
idDYNAMIXEL ID
addressAddress on the control table of DYNAMIXEL
lengthPacket length
dataData for write
  • Detailed Description

    This function constructs the transmission packet with INST_REG_WRITE instruction, and txPacket(). Finally, it returns communication status.

regWriteTxRx
  • Syntax
int RegWriteTxRx(PortHandler *port, UINT8_T id, UINT16_T address, UINT16_T length, UINT8_T *data, UINT8_T *error)
  • Parameters
ParametersDescription
portPortHandler instance
idDYNAMIXEL ID
addressAddress on the control table of DYNAMIXEL
lengthPacket length
dataData for write
errorDYNAMIXEL error
  • Detailed Description

    This function constructs the transmission packet with INST_REG_WRITE instruction, and txRxPacket(). Finally, it returns communication status.

syncReadTx
  • Syntax
int syndReadTx(PortHandler *port, UINT16_T address, UINT16_T data_length, UINT8_T *param, UINT16_T param_length)
  • Parameters
ParametersDescription
portPortHandler instance
addressAddress on the control table of DYNAMIXEL
data_lengthData length
paramParameters
param_lengthParameter length
  • Detailed Description

    This function is not available with the DYNAMIXEL Protocol 1.0. It returns COMM_NOT_AVAILABLE status.

syncWriteTxOnly
  • Syntax
int syncWriteTxOnly(PortHandler *port, UINT16_T start_address, UINT16_T data_length, UINT8_T *data, UINT16_T param_length)
  • Parameters
ParametersDescription
portPortHandler instance
idDYNAMIXEL ID
addressAddress on the control table of DYNAMIXEL
data_lengthData length
dataData for write
param_lengthParameter length
  • Detailed Description

    This function constructs the transmission packet with INST_SYNC_WRITE instruction, and txRxPacket(). Finally, it returns communication status.

bulkReadTx
  • Syntax
int bulkReadTx(PortHandler *port, UINT8_T *param, UINT16_T param_length)
  • Parameters
ParametersDescription
portPortHandler instance
paramParameters
param_lengthParameter length
  • Detailed Description

    This function constructs the transmission packet with INST_BULK_READ instruction, and txPacket(). Then the function calls setPacketTimeout() function when txPacket() succeeds. Finally, it returns communication status.

bulkWriteTxOnly
  • Syntax
int bulkWriteTxOnly(PortHandler *port, UINT8_T *param, UINT16_T param_length)
  • Parameters
ParametersDescription
portPortHandler instance
paramParameters
param_lengthParameter length
  • Detailed Description

    This function is not available with the DYNAMIXEL Protocol 1.0. It returns COMM_NOT_AVAILABLE status.

CPP Protocol2PacketHandler

  • Description

Child class for packet construction using Protocol 2.0.

  • Members

None

  • Methods
MethodsDescription
getInstanceGets instance of this class
~Protocol2PacketHandlerNone
getProtocolVersionGets Protocol version
printTxRxResultShows communication result
printRxPacketErrorShows hardware error
txPacketTransmits the packet
rxPacketReceives the packet
txRxPacketTransmits and receives the packet
pingPing DYNAMIXEL
broadcastPingPing all connected DYNAMIXEL's
actionCommands ‘Run’ the Regwritten
regWriteWrites the packets and wait for the ‘Action’ command
rebootReboots DYNAMIXEL
factoryResetResets all DYNAMIXEL settings
readTxTransmits N byte read instruction packet
readRxReceives N byte read status packet
readTxRxTransmits and receives N byte packet
read1ByteTxTransmits 1 byte read instruction packet
read1ByteRxReceives 1 byte read status packet
read1ByteTxRxTransmits and receives 1 byte packet
read2ByteTxTransmits 2 byte read instruction packet
read2ByteRxReceives 2 byte read status packet
read2ByteTxRxTransmits and receives 2 byte packet
read4ByteTxTransmits 4 byte read instruction packet
read4ByteRxReceives 4 byte read status packet
read4ByteTxRxTransmits and receives 4 byte packet
writeTxOnlyTransmits N byte write instruction packet
writeTxRxTransmits and receives N byte packet
write1ByteTxOnlyTransmits 1 byte write instruction packet
write1ByteTxRxTransmits and receives 1 byte packet
write2ByteTxOnlyTransmits 2 byte write instruction packet
write2ByteTxRxTransmits and receives 2 byte packet
write4ByteTxOnlyTransmits 4 byte write instruction packet
write4ByteTxRxTransmits and receives 4 byte packet
regWriteTxOnlyTransmits register write instruction packet
regWriteTxRxTransmits and receives register write packet
syncReadTxTransmits N byte sync read Instruction packet
syncWriteTxOnlyTransmits N byte sync write Instruction packet
bulkReadTxTransmits N byte bulk read Instruction packet
bulkWriteTxOnlyTransmits N byte bulk write Instruction packet
  • Enumerator

None

Method References

getProtocolVersion
  • Syntax
float getProtocolVersion()
  • Parameters

    None

  • Detailed Description

    This function returns the protocol version set in the PacketHandler as a float value.

printTxRxResult
  • Syntax
void printTxRxResult(int result)
  • Parameters
ParametersDescription
resultCommunication result
  • Detailed Description

    This function prints out on the console window what communication result value means.

printRxPacketError
  • Syntax
void printRxPacketError(uint8_t error)
  • Parameters
ParametersDescription
errorHardware error
  • Detailed Description

    This function prints out on the console window what hardware error value means.

txPacket
  • Syntax
int txPacket(PortHandler *port, UINT8_T *txpacket)
  • Parameters
ParametersDescription
portPortHandler instance
txpacketpacket for transmission
  • Detailed Description

    This function transmits the packet. The function clears the port by clearPort() function at first, and passes the txpacket to the writePort() function. The function activates while the port is not busy, and when the packet is written on the port buffer.

rxPacket
  • Syntax
int rxPacket(PortHandler *port, UINT8_T *rxpacket)
  • Parameters
ParametersDescription
portPortHandler instance
rxpacketpacket for reception
  • Detailed Description

    This function repeatedly tries to receive packets by readPort() function until whole packets that it waits to get have arrived, or the packet wait time limit is over. After, it returns communication status value.

txRxPacket
  • Syntax
int txRxPacket(PortHandler *port, UINT8_T *txpacket, UINT8_T *rxpacket, UINT8_T *error = 0)
  • Parameters
ParametersDescription
portPortHandler instance
txpacketpacket for transmission
rxpacketpacket for reception
errorDYNAMIXEL error
  • Detailed Description

    This function transmits and receives packets by txPacket() and rxPacket() functions. When txPacket() function succeeds to communicate, it will continue to rxPacket() and finishes the process if the packet succeeds to be received. In case of using the group handler functions for write, such as SyncWrite, and BulkWrite, they don’t use rxPacket(), so the function finishes its operation immediately after the txPacket(). Before the rxPacket(), it sets packet timeout if the packet instruction is INST_READ.

ping
  • Syntax
int ping (PortHandler *port, UINT8_T id, UINT8_T *error = 0)
int ping (PortHandler *port, UINT8_T id, UINT16_T *model_number, UINT8_T *error = 0)
  • Parameters
ParametersDescription
portPortHandler instance
idDYNAMIXEL ID
errorDYNAMIXEL error
  • Detailed Description

    This function constructs the transmission packet with INST_PING instruction, and txRxPacket(). Then, the function tries to get the model number of the DYNAMIXEL by readTxRx() function. When it succeeds to receive the packet, it makes the model number value by using DXL_MAKEWORD() to put two byte-type data together. Finally, it returns communication status value.

broadcastPing
  • Syntax
int broadcastPing(PortHandler *port, std::vector<UINT8_T> &id_list)
  • Parameters
ParametersDescription
portPortHandler instance
id_listDYNAMIXEL ID list
  • Detailed Description

    This function finds all connected dynamixels and store the their id lists.

action
  • Syntax
int action(PortHandler *port, UINT8_T id)
  • Parameters
ParametersDescription
portPortHandler instance
idDYNAMIXEL ID
  • Detailed Description

    This function constructs the transmission packet with INST_ACTION instruction, and txRxPacket(). Before using this function, the orders for the DYNAMIXEL's should be already written in the register in DYNAMIXEL by RegWrite function. Finally, it returns communication status value.

reboot
  • Syntax
int reboot(PortHandler *port, UINT8_T id, UINT8_T *error)
  • Parameters
ParametersDescription
portPortHandler instance
idDYNAMIXEL ID
errorDYNAMIXEL error
  • Detailed Description

    This function constructs the transmission packet with INST_REBOOT instruction, and txRxPacket(). Finally, it returns commnunication status.

factoryReset
  • Syntax
int factoryReset(PortHandler *port, UINT8_T id, UINT8_T option, UINT8_T *error)
  • Parameters
ParametersDescription
portPortHandler instance
idDYNAMIXEL ID
optionReset option
errorDYNAMIXEL error
  • Detailed Description

    This function constructs the transmission packet with INST_FACTORY_RESET instruction, and txRxPacket(). This resets all DYNAMIXEL settings to the factory default settings. The option is not available in DYNAMIXEL Protocol 1.0. Finally, it returns communication status.

readTx
  • Syntax
int readTx(PortHandler *port, UINT8_T id, UINT16_T address, UINT16_T length)
  • Parameters
ParametersDescription
portPortHandler instance
idDYNAMIXEL ID
addressAddress on the control table of DYNAMIXEL
lengthPacket length
  • Detailed Description

    This function constructs the transmission packet with INST_READ instruction, and txPacket(). Then the function calls setPacketTimeout() function when txPacket() succeeds. This function is not available for controlling more than one DYNAMIXEL. Finally, it returns communication status.

readRx
  • Syntax
int readRx(PortHandler *port, UINT16_T length, UINT8_T *data, UINT8_T *error)
  • Parameters
ParametersDescription
portPortHandler instance
lengthPacket length
dataPacket data
errorDYNAMIXEL error
  • Detailed Description

    This function calls rxPacket() function and gets the reception packet if the communication succeeds. Finally, it returns communication status value.

readTxRx
  • Syntax
int readTxRx(PortHandler *port, UINT8_T id, UINT16_T address, UINT16_T length, UINT8_T *data, UINT8_T *error)
  • Parameters
ParametersDescription
portPortHandler instance
idDYNAMIXEL ID
addressAddress on the control table of DYNAMIXEL
lengthPacket length
dataPacket data
errorDYNAMIXEL error
  • Detailed Description

    This function calls readTx() function and readRx() function. readRx() function will be called when readTx() succeeds. Finally, it returns communication status value.

read1ByteTx
  • Syntax
int read1ByteTx(PortHandler *port, UINT8_T id, UINT16_T address)
  • Parameters
ParametersDescription
portPortHandler instance
idDYNAMIXEL ID
addressAddress on the control table of DYNAMIXEL
  • Detailed Description

    This function calls readTx() function for 1 Byte packet transmission. Finally, it returns communication status.

read1ByteRx
  • Syntax
int read1ByteRx(PortHandler *port, UINT8_T *data, UINT8_T *error)
  • Parameters
ParametersDescription
portPortHandler instance
dataPacket data
errorDYNAMIXEL error
  • Detailed Description

    This function calls readRx() function for 1 Byte packet reception. Finally, it returns communication status.

read1ByteTxRx
  • Syntax
int read1ByteTxRx(PortHandler *port, UINT8_T id,UINT16_T address, UINT8_T *data, UINT8_T *error)
  • Parameters
ParametersDescription
portPortHandler instance
idDYNAMIXEL ID
addressAddress on the control table of DYNAMIXEL
dataPacket data
errorDYNAMIXEL error
  • Detailed Description

    This function calls read1ByteTx() function and read1ByteRx() function for 1 Byte packet transmission and reception. read1ByteRx() function will be called when read1ByteTx() succeeds. Finally, it returns communication status.

openPort
  • Syntax
int read2ByteTx(PortHandler *port, UINT8_T id, UINT16_T address)
  • Parameters
ParametersDescription
portPortHandler instance
idDYNAMIXEL ID
addressAddress on the control table of DYNAMIXEL
  • Detailed Description

    This function calls readTx() function for 2 Byte packet transmission. Finally, it returns communication status.

read2ByteRx
  • Syntax
int read2ByteRx(PortHandler *port, UINT16_T *data, UINT8_T *error)
  • Parameters
ParametersDescription
portPortHandler instance
dataPacket data
errorDYNAMIXEL error
  • Detailed Description

    This function calls readRx() function for 2 Byte packet reception. Finally, it returns communication status.

read2ByteTxRx
  • Syntax
int read2ByteTxRx(PortHandler *port, UINT8_T id,UINT16_T address, UIN16_T *data, UINT8_T *error)
  • Parameters
ParametersDescription
portPortHandler instance
idDYNAMIXEL ID
addressAddress on the control table of DYNAMIXEL
dataPacket data
errorDYNAMIXEL error
  • Detailed Description

    This function calls read2ByteTx() function and read2ByteRx() function for 2 Byte packet transmission and reception. read2ByteRx() function will be called when read2ByteTx() succeeds. Finally, it returns communication status.

read4ByteTx
  • Syntax
int read4ByteTx(PortHandler *port, UINT8_T id, UINT16_T address)
  • Parameters
ParametersDescription
portPortHandler instance
idDYNAMIXEL ID
addressAddress on the control table of DYNAMIXEL
  • Detailed Description

    This function calls readTx() function for 4 Byte packet transmission. Finally, it returns communication status.

read4ByteRx
  • Syntax
int read4ByteRx(PortHandler *port, UINT32_T *data, UINT8_T *error)
  • Parameters
ParametersDescription
portPortHandler instance
dataPacket data
errorDYNAMIXEL error
  • Detailed Description

    This function calls readRx() function for 4 Byte packet reception. Finally, it returns communication status.

read4ByteTxRx
  • Syntax
int read4ByteTxRx(PortHandler *port, UIN8_T id, UINT16_T address, UINT32_T *data, UINT8_T *error)
  • Parameters
ParametersDescription
portPortHandler instance
idDYNAMIXEL ID
addressAddress on the control table of DYNAMIXEL
dataData for write
errorDYNAMIXEL error
  • Detailed Description

    This function calls read4ByteTx() function and read4ByteRx() function for 4 Byte packet transmission and reception. read4ByteRx() function will be called when read4ByteTx() succeeds. Finally, it returns communication status.

writeTxOnly
  • Syntax
int writeTxOnly(PortHandler *port, UINT8_T id, UINT16_T address, UINT16_T length, UINT8_T *data)
  • Parameters
ParametersDescription
portPortHandler instance
idDYNAMIXEL ID
addressAddress on the control table of DYNAMIXEL
lengthPacket length
dataData for write
  • Detailed Description

    This function constructs the transmission packet with INST_WRITE instruction, and txPacket(). Finally, it returns communication status.

writeTxRx
  • Syntax
int writeTxRx(PortHandler *port, UINT8_T id, UINT16_T address, UINT16_T length, UINT8_T *data, UINT8_T *error)
  • Parameters
ParametersDescription
portPortHandler instance
idDYNAMIXEL ID
addressAddress on the control table of DYNAMIXEL
lengthPacket length
dataData for write
errorDYNAMIXEL error
  • Detailed Description

    This function constructs the transmission packet with INST_WRITE instruction, and txRxPacket(). Finally, it returns communication status.

write1ByteTxOnly
  • Syntax
int write1ByteTxOnly(PortHandler *port, UINT8_T id, UINT16_T address, UINT8_T data)
  • Parameters
ParametersDescription
portPortHandler instance
idDYNAMIXEL ID
addressAddress on the control table of DYNAMIXEL
dataData for write
  • Detailed Description

    This function calls writeTxOnly() function for 1 Byte packet. Finally, it returns communication status.

write1ByteTxRx
  • Syntax
int write1ByteTxRx(PortHandler *port, UINT8_T id, UINT16_T address, UINT8_T data, UINT8_T *error)
  • Parameters
ParametersDescription
portPortHandler instance
idDYNAMIXEL ID
addressAddress on the control table of DYNAMIXEL
dataData for write
errorDYNAMIXEL error
  • Detailed Description

    This function calls writeTxRx() function for 1 Byte packet transmission and reception. Finally, it returns communication status.

write2ByteTxOnly
  • Syntax
int write2ByteTxOnly(PortHandler *port, UINT8_T id, UINT16_T address, UINT16_T data)
  • Parameters
ParametersDescription
portPortHandler instance
idDYNAMIXEL ID
addressAddress on the control table of DYNAMIXEL
dataData for write
  • Detailed Description

    This function calls writeTxOnly() function for 2 Byte packet. Finally, it returns communication status.

write2ByteTxRx
  • Syntax
int write2ByteTxRx(PortHandler *port, UINT8_T id, UINT16_T address, UINT16_T data, UINT8_T *error)
  • Parameters
ParametersDescription
portPortHandler instance
idDYNAMIXEL ID
addressAddress on the control table of DYNAMIXEL
dataData for write
errorDYNAMIXEL error
  • Detailed Description

    This function calls writeTxRx() function for 2 Byte packet transmission and reception. Finally, it returns communication status.

write4ByteTxOnly
  • Syntax
int write1ByteTxOnly(PortHandler *port, UINT8_T id, UINT16_T address, UINT32_T data)
  • Parameters
ParametersDescription
portPortHandler instance
idDYNAMIXEL ID
addressAddress on the control table of DYNAMIXEL
dataData for write
  • Detailed Description

    This function calls writeTxOnly() function for 4 Byte packet. Finally, it returns communication status.

write4ByteTxRx
  • Syntax
int write4ByteTxRx(PortHandler *port, UINT8_T id, UINT16_T address, UINT32_T data, UINT8_T *error)
  • Parameters
ParametersDescription
portPortHandler instance
idDYNAMIXEL ID
addressAddress on the control table of DYNAMIXEL
dataData for write
errorDYNAMIXEL error
  • Detailed Description

    This function calls writeTxRx() function for 4 Byte packet transmission and reception. Finally, it returns communication status.

regWriteTxOnly
  • Syntax
int regWriteTxOnly(PortHandler *port, UINT8_T id, UINT16_T address, UINT16_T length, UINT8_T *data)
  • Parameters
ParametersDescription
portPortHandler instance
idDYNAMIXEL ID
addressAddress on the control table of DYNAMIXEL
lengthPacket length
dataData for write
  • Detailed Description

    This function constructs the transmission packet with INST_REG_WRITE instruction, and txPacket(). Finally, it returns communication status.

regWriteTxRx
  • Syntax
int regWriteTxRx(PortHandler *port, UINT8_T id, UINT16_T address, UINT16_T length, UINT8_T *data, UINT8_T *error)
  • Parameters
ParametersDescription
portPortHandler instance
idDYNAMIXEL ID
addressAddress on the control table of DYNAMIXEL
lengthPacket length
dataData for write
errorDYNAMIXEL error
  • Detailed Description

    This function constructs the transmission packet with INST_REG_WRITE instruction, and txRxPacket(). Finally, it returns communication status.

syncReadTx
  • Syntax
int syndReadTx(PortHandler *port, UINT16_T address, UINT16_T data_length, UINT8_T *param, UINT16_T param_length)
  • Parameters
ParametersDescription
portPortHandler instance
addressAddress on the control table of DYNAMIXEL
data_lengthData length
paramParameters
param_lengthParameter length
  • Detailed Description

    This function constructs the transmission packet with INST_SYNC_READ instruction, and txPacket(). Then the function calls setPacketTimeout() function when txPacket() succeeds. Finally, it returns communication status.

syncWriteTxOnly
  • Syntax
int syncWriteTxOnly(PortHandler *port, UINT16_T start_address, UINT16_T data_length, UINT8_T *data, UINT16_T param_length)
  • Parameters
ParametersDescription
portPortHandler instance
idDYNAMIXEL ID
addressAddress on the control table of DYNAMIXEL
data_lengthData length
dataData for write
param_lengthParameter length
  • Detailed Description

    This function constructs the transmission packet with INST_SYNC_WRITE instruction, and txRxPacket(). Finally, it returns communication status.

bulkReadTx
  • Syntax
int bulkReadTx(PortHandler *port, UINT8_T *param, UINT16_T param_length)
  • Parameters
ParametersDescription
portPortHandler instance
paramParameters
param_lengthParameter length
  • Detailed Description

    This function constructs the transmission packet with INST_BULK_READ instruction, and txPacket(). Then the function calls setPacketTimeout() function when txPacket() succeeds. Finally, it returns communication status.

bulkWriteTxOnly
  • Syntax
int bulkWriteTxOnly(PortHandler *port, UINT8_T *param, UINT16_T param_length)
  • Parameters
ParametersDescription
portPortHandler instance
paramParameters
param_lengthParameter length
  • Detailed Description

    This function constructs the transmission packet with INST_BULK_WRITE instruction, and txRxPacket(). Finally, it returns communication status.