Public Member Functions | Static Public Member Functions | Protected Member Functions | List of all members
dynamixel::PacketHandler Class Referenceabstract

The class that inherits Protocol1PacketHandler class or Protocol2PacketHandler class. More...

#include <packet_handler.h>

Inheritance diagram for dynamixel::PacketHandler:
Inheritance graph
[legend]

Public Member Functions

virtual int action (PortHandler *port, uint8_t id)=0
 The function that makes Dynamixels run as written in the Dynamixel register The function makes an instruction packet with INST_ACTION, transmits the packet with PacketHandler::txRxPacket(). To use this function, Dynamixel register should be set by PacketHandler::regWriteTxOnly() or PacketHandler::regWriteTxRx() More...
 
virtual int broadcastPing (PortHandler *port, std::vector< uint8_t > &id_list)=0
 (Available only in Protocol 2.0) The function that pings all connected Dynamixel More...
 
virtual int bulkReadTx (PortHandler *port, uint8_t *param, uint16_t param_length)=0
 The function that transmits INST_BULK_READ instruction packet The function makes an instruction packet with INST_BULK_READ, transmits the packet with PacketHandler::txPacket(). More...
 
virtual int bulkWriteTxOnly (PortHandler *port, uint8_t *param, uint16_t param_length)=0
 The function that transmits INST_BULK_WRITE instruction packet The function makes an instruction packet with INST_BULK_WRITE, transmits the packet with PacketHandler::txRxPacket(). More...
 
virtual int clearMultiTurn (PortHandler *port, uint8_t id, uint8_t *error=0)=0
 The function that reset multi-turn revolution information of Dynamixel The function makes an instruction packet with INST_CLEAR, transmits the packet with PacketHandler::txRxPacket(). Applied Products : MX with Protocol 2.0 (Firmware v42 or above), Dynamixel X-series (Firmware v42 or above). More...
 
virtual int factoryReset (PortHandler *port, uint8_t id, uint8_t option=0, uint8_t *error=0)=0
 The function that makes Dynamixel reset as it was produced in the factory The function makes an instruction packet with INST_FACTORY_RESET, transmits the packet with PacketHandler::txRxPacket(). Be careful of the use. More...
 
virtual float getProtocolVersion ()=0
 The function that returns Protocol version. More...
 
virtual const char * getRxPacketError (uint8_t error)=0
 The function that gets description of hardware error. More...
 
virtual const char * getTxRxResult (int result)=0
 The function that gets description of communication result. More...
 
virtual int ping (PortHandler *port, uint8_t id, uint8_t *error=0)=0
 The function that pings Dynamixel but doesn't take its model number The function calls PacketHandler::ping() which gets Dynamixel model number, but doesn't carry the model number. More...
 
virtual int ping (PortHandler *port, uint8_t id, uint16_t *model_number, uint8_t *error=0)=0
 The function that pings Dynamixel and takes its model number The function makes an instruction packet with INST_PING, transmits the packet with PacketHandler::txRxPacket(), and call PacketHandler::readTxRx to read model_number in the rx buffer. It breaks out when it tries to transmit to BROADCAST_ID. More...
 
virtual int read1ByteRx (PortHandler *port, uint8_t id, uint8_t *data, uint8_t *error=0)=0
 The function that calls PacketHandler::readRx() function and reads 1 byte data on the packet The function calls PacketHandler::readRx() function, gets 1 byte data from the packet. More...
 
virtual int read1ByteTx (PortHandler *port, uint8_t id, uint16_t address)=0
 The function that calls PacketHandler::readTx() function for reading 1 byte data The function calls PacketHandler::readTx() function for reading 1 byte data. More...
 
virtual int read1ByteTxRx (PortHandler *port, uint8_t id, uint16_t address, uint8_t *data, uint8_t *error=0)=0
 The function that calls PacketHandler::readTxRx() function for reading 1 byte data The function calls PacketHandler::readTxRx(), gets 1 byte data from the packet. More...
 
virtual int read2ByteRx (PortHandler *port, uint8_t id, uint16_t *data, uint8_t *error=0)=0
 The function that calls PacketHandler::readRx() function and reads 2 byte data on the packet The function calls PacketHandler::readRx() function, gets 2 byte data from the packet. More...
 
virtual int read2ByteTx (PortHandler *port, uint8_t id, uint16_t address)=0
 The function that calls PacketHandler::readTx() function for reading 2 byte data The function calls PacketHandler::readTx() function for reading 2 byte data. More...
 
virtual int read2ByteTxRx (PortHandler *port, uint8_t id, uint16_t address, uint16_t *data, uint8_t *error=0)=0
 The function that calls PacketHandler::readTxRx() function for reading 2 byte data The function calls PacketHandler::readTxRx(), gets 2 byte data from the packet. More...
 
virtual int read4ByteRx (PortHandler *port, uint8_t id, uint32_t *data, uint8_t *error=0)=0
 The function that calls PacketHandler::readRx() function and reads 4 byte data on the packet The function calls PacketHandler::readRx() function, gets 4 byte data from the packet. More...
 
virtual int read4ByteTx (PortHandler *port, uint8_t id, uint16_t address)=0
 The function that calls PacketHandler::readTx() function for reading 4 byte data The function calls PacketHandler::readTx() function for reading 4 byte data. More...
 
virtual int read4ByteTxRx (PortHandler *port, uint8_t id, uint16_t address, uint32_t *data, uint8_t *error=0)=0
 The function that calls PacketHandler::readTxRx() function for reading 4 byte data The function calls PacketHandler::readTxRx(), gets 4 byte data from the packet. More...
 
virtual int readRx (PortHandler *port, uint8_t id, uint16_t length, uint8_t *data, uint8_t *error=0)=0
 The function that receives the packet and reads the data in the packet The function receives the packet which might be come by previous INST_READ instruction packet transmission, gets the data from the packet. More...
 
virtual int readTx (PortHandler *port, uint8_t id, uint16_t address, uint16_t length)=0
 The function that transmits INST_READ instruction packet The function makes an instruction packet with INST_READ, transmits the packet with PacketHandler::txPacket(). It breaks out when it tries to transmit to BROADCAST_ID. More...
 
virtual int readTxRx (PortHandler *port, uint8_t id, uint16_t address, uint16_t length, uint8_t *data, uint8_t *error=0)=0
 The function that transmits INST_READ instruction packet, and read data from received packet The function makes an instruction packet with INST_READ, transmits and receives the packet with PacketHandler::txRxPacket(), gets the data from the packet. It breaks out when it tries to transmit to BROADCAST_ID. More...
 
virtual int reboot (PortHandler *port, uint8_t id, uint8_t *error=0)=0
 The function that makes Dynamixel reboot The function makes an instruction packet with INST_REBOOT, transmits the packet with PacketHandler::txRxPacket(), then Dynamixel reboots. During reboot, its LED will blink. More...
 
virtual int regWriteTxOnly (PortHandler *port, uint8_t id, uint16_t address, uint16_t length, uint8_t *data)=0
 The function that transmits INST_REG_WRITE instruction packet with the data for writing on the Dynamixel register The function makes an instruction packet with INST_REG_WRITE and the data for writing on the Dynamixel register, transmits the packet with PacketHandler::txPacket(). The data written in the register will act when INST_ACTION instruction packet is transmitted to the Dynamixel. More...
 
virtual int regWriteTxRx (PortHandler *port, uint8_t id, uint16_t address, uint16_t length, uint8_t *data, uint8_t *error=0)=0
 The function that transmits INST_REG_WRITE instruction packet with the data for writing on the Dynamixel register, and receives the packet The function makes an instruction packet with INST_REG_WRITE and the data for writing on the Dynamixel register, transmits and receives the packet with PacketHandler::txRxPacket(), gets the error from the packet. The data written in the register will act when INST_ACTION instruction packet is transmitted to the Dynamixel. More...
 
virtual int rxPacket (PortHandler *port, uint8_t *rxpacket)=0
 The function that receives packet (rxpacket) during designated time via PortHandler port The function repeatedly tries to receive rxpacket by PortHandler::readPort() function. It breaks out when PortHandler::isPacketTimeout() shows the timeout, when rxpacket seemed as corrupted, or when nothing received. More...
 
virtual int syncReadTx (PortHandler *port, uint16_t start_address, uint16_t data_length, uint8_t *param, uint16_t param_length)=0
 The function that transmits INST_SYNC_READ instruction packet The function makes an instruction packet with INST_SYNC_READ, transmits the packet with PacketHandler::txPacket(). More...
 
virtual int syncWriteTxOnly (PortHandler *port, uint16_t start_address, uint16_t data_length, uint8_t *param, uint16_t param_length)=0
 The function that transmits INST_SYNC_WRITE instruction packet The function makes an instruction packet with INST_SYNC_WRITE, transmits the packet with PacketHandler::txRxPacket(). More...
 
virtual int txPacket (PortHandler *port, uint8_t *txpacket)=0
 The function that transmits the instruction packet txpacket via PortHandler port. The function clears the port buffer by PortHandler::clearPort() function, then transmits txpacket by PortHandler::writePort() function. The function activates only when the port is not busy and when the packet is already written on the port buffer. More...
 
virtual int txRxPacket (PortHandler *port, uint8_t *txpacket, uint8_t *rxpacket, uint8_t *error=0)=0
 The function that transmits packet (txpacket) and receives packet (rxpacket) during designated time via PortHandler port The function calls PacketHandler::txPacket(), and calls PacketHandler::rxPacket() if it succeeds PacketHandler::txPacket(). It breaks out when it fails PacketHandler::txPacket(), when txpacket is called by PacketHandler::broadcastPing() / PacketHandler::syncWriteTxOnly() / PacketHandler::regWriteTxOnly / PacketHandler::action. More...
 
virtual int write1ByteTxOnly (PortHandler *port, uint8_t id, uint16_t address, uint8_t data)=0
 The function that calls PacketHandler::writeTxOnly() for writing 1 byte data The function calls PacketHandler::writeTxOnly() for writing 1 byte data. More...
 
virtual int write1ByteTxRx (PortHandler *port, uint8_t id, uint16_t address, uint8_t data, uint8_t *error=0)=0
 The function that calls PacketHandler::writeTxRx() for writing 1 byte data and receives the packet The function calls PacketHandler::writeTxRx() for writing 1 byte data and receves the packet, gets the error from the packet. More...
 
virtual int write2ByteTxOnly (PortHandler *port, uint8_t id, uint16_t address, uint16_t data)=0
 The function that calls PacketHandler::writeTxOnly() for writing 2 byte data The function calls PacketHandler::writeTxOnly() for writing 2 byte data. More...
 
virtual int write2ByteTxRx (PortHandler *port, uint8_t id, uint16_t address, uint16_t data, uint8_t *error=0)=0
 The function that calls PacketHandler::writeTxRx() for writing 2 byte data and receives the packet The function calls PacketHandler::writeTxRx() for writing 2 byte data and receves the packet, gets the error from the packet. More...
 
virtual int write4ByteTxOnly (PortHandler *port, uint8_t id, uint16_t address, uint32_t data)=0
 The function that calls PacketHandler::writeTxOnly() for writing 4 byte data The function calls PacketHandler::writeTxOnly() for writing 4 byte data. More...
 
virtual int write4ByteTxRx (PortHandler *port, uint8_t id, uint16_t address, uint32_t data, uint8_t *error=0)=0
 The function that calls PacketHandler::writeTxRx() for writing 4 byte data and receives the packet The function calls PacketHandler::writeTxRx() for writing 4 byte data and receves the packet, gets the error from the packet. More...
 
virtual int writeTxOnly (PortHandler *port, uint8_t id, uint16_t address, uint16_t length, uint8_t *data)=0
 The function that transmits INST_WRITE instruction packet with the data for write The function makes an instruction packet with INST_WRITE and the data for write, transmits the packet with PacketHandler::txPacket(). More...
 
virtual int writeTxRx (PortHandler *port, uint8_t id, uint16_t address, uint16_t length, uint8_t *data, uint8_t *error=0)=0
 The function that transmits INST_WRITE instruction packet with the data for write, and receives the packet The function makes an instruction packet with INST_WRITE and the data for write, transmits and receives the packet with PacketHandler::txRxPacket(), gets the error from the packet. More...
 
virtual ~PacketHandler ()
 

Static Public Member Functions

static PacketHandlergetPacketHandler (float protocol_version=2.0)
 The function that returns PacketHandler instance. More...
 

Protected Member Functions

 PacketHandler ()
 

Detailed Description

The class that inherits Protocol1PacketHandler class or Protocol2PacketHandler class.

Definition at line 82 of file packet_handler.h.

Constructor & Destructor Documentation

dynamixel::PacketHandler::PacketHandler ( )
inlineprotected

Definition at line 85 of file packet_handler.h.

virtual dynamixel::PacketHandler::~PacketHandler ( )
inlinevirtual

Definition at line 94 of file packet_handler.h.

Member Function Documentation

virtual int dynamixel::PacketHandler::action ( PortHandler port,
uint8_t  id 
)
pure virtual

The function that makes Dynamixels run as written in the Dynamixel register The function makes an instruction packet with INST_ACTION, transmits the packet with PacketHandler::txRxPacket(). To use this function, Dynamixel register should be set by PacketHandler::regWriteTxOnly() or PacketHandler::regWriteTxRx()

Parameters
portPortHandler instance
idDynamixel ID
Returns
communication results which come from PacketHandler::txRxPacket()

Implemented in dynamixel::Protocol2PacketHandler, and dynamixel::Protocol1PacketHandler.

virtual int dynamixel::PacketHandler::broadcastPing ( PortHandler port,
std::vector< uint8_t > &  id_list 
)
pure virtual

(Available only in Protocol 2.0) The function that pings all connected Dynamixel

Parameters
portPortHandler instance
id_listID list of Dynamixels which are found by broadcast ping
Returns
COMM_NOT_AVAILABLE

Implemented in dynamixel::Protocol2PacketHandler, and dynamixel::Protocol1PacketHandler.

virtual int dynamixel::PacketHandler::bulkReadTx ( PortHandler port,
uint8_t *  param,
uint16_t  param_length 
)
pure virtual

The function that transmits INST_BULK_READ instruction packet The function makes an instruction packet with INST_BULK_READ, transmits the packet with PacketHandler::txPacket().

Parameters
portPortHandler instance
paramParameter for Bulk Read
param_lengthLength of the data for Bulk Read
Returns
communication results which come from PacketHandler::txPacket()

Implemented in dynamixel::Protocol2PacketHandler, and dynamixel::Protocol1PacketHandler.

virtual int dynamixel::PacketHandler::bulkWriteTxOnly ( PortHandler port,
uint8_t *  param,
uint16_t  param_length 
)
pure virtual

The function that transmits INST_BULK_WRITE instruction packet The function makes an instruction packet with INST_BULK_WRITE, transmits the packet with PacketHandler::txRxPacket().

Parameters
portPortHandler instance
paramParameter for Bulk Write
param_lengthLength of the data for Bulk Write
Returns
communication results which come from PacketHandler::txRxPacket()

Implemented in dynamixel::Protocol2PacketHandler, and dynamixel::Protocol1PacketHandler.

virtual int dynamixel::PacketHandler::clearMultiTurn ( PortHandler port,
uint8_t  id,
uint8_t *  error = 0 
)
pure virtual

The function that reset multi-turn revolution information of Dynamixel The function makes an instruction packet with INST_CLEAR, transmits the packet with PacketHandler::txRxPacket(). Applied Products : MX with Protocol 2.0 (Firmware v42 or above), Dynamixel X-series (Firmware v42 or above).

Parameters
portPortHandler instance
idDynamixel ID
errorDynamixel hardware error
Returns
communication results which come from PacketHandler::txRxPacket()

Implemented in dynamixel::Protocol2PacketHandler, and dynamixel::Protocol1PacketHandler.

virtual int dynamixel::PacketHandler::factoryReset ( PortHandler port,
uint8_t  id,
uint8_t  option = 0,
uint8_t *  error = 0 
)
pure virtual

The function that makes Dynamixel reset as it was produced in the factory The function makes an instruction packet with INST_FACTORY_RESET, transmits the packet with PacketHandler::txRxPacket(). Be careful of the use.

Parameters
portPortHandler instance
idDynamixel ID
optionReset option
errorDynamixel hardware error
Returns
communication results which come from PacketHandler::txRxPacket()

Implemented in dynamixel::Protocol2PacketHandler, and dynamixel::Protocol1PacketHandler.

PacketHandler * PacketHandler::getPacketHandler ( float  protocol_version = 2.0)
static

The function that returns PacketHandler instance.

Returns
PacketHandler instance

Definition at line 40 of file packet_handler.cpp.

virtual float dynamixel::PacketHandler::getProtocolVersion ( )
pure virtual

The function that returns Protocol version.

Returns
protocol version

Implemented in dynamixel::Protocol2PacketHandler, and dynamixel::Protocol1PacketHandler.

virtual const char* dynamixel::PacketHandler::getRxPacketError ( uint8_t  error)
pure virtual

The function that gets description of hardware error.

Parameters
errorDynamixel hardware error which might be gotten by the tx rx functions
Returns
description of hardware error in const char* (string)

Implemented in dynamixel::Protocol2PacketHandler, and dynamixel::Protocol1PacketHandler.

virtual const char* dynamixel::PacketHandler::getTxRxResult ( int  result)
pure virtual

The function that gets description of communication result.

Parameters
resultCommunication result which might be gotten by the tx rx functions
Returns
description of communication result in const char* (string)

Implemented in dynamixel::Protocol2PacketHandler, and dynamixel::Protocol1PacketHandler.

virtual int dynamixel::PacketHandler::ping ( PortHandler port,
uint8_t  id,
uint8_t *  error = 0 
)
pure virtual

The function that pings Dynamixel but doesn't take its model number The function calls PacketHandler::ping() which gets Dynamixel model number, but doesn't carry the model number.

Parameters
portPortHandler instance
idDynamixel ID
errorDynamixel hardware error
Returns
communication results which come from PacketHandler::ping()

Implemented in dynamixel::Protocol2PacketHandler, and dynamixel::Protocol1PacketHandler.

virtual int dynamixel::PacketHandler::ping ( PortHandler port,
uint8_t  id,
uint16_t *  model_number,
uint8_t *  error = 0 
)
pure virtual

The function that pings Dynamixel and takes its model number The function makes an instruction packet with INST_PING, transmits the packet with PacketHandler::txRxPacket(), and call PacketHandler::readTxRx to read model_number in the rx buffer. It breaks out when it tries to transmit to BROADCAST_ID.

Parameters
portPortHandler instance
idDynamixel ID
errorDynamixel hardware error
Returns
COMM_NOT_AVAILABLE
when it tries to transmit to BROADCAST_ID
COMM_SUCCESS
when it succeeds to ping Dynamixel and get model_number from it
or the other communication results which come from PacketHandler::txRxPacket() and PacketHandler::readTxRx()

Implemented in dynamixel::Protocol2PacketHandler, and dynamixel::Protocol1PacketHandler.

virtual int dynamixel::PacketHandler::read1ByteRx ( PortHandler port,
uint8_t  id,
uint8_t *  data,
uint8_t *  error = 0 
)
pure virtual

The function that calls PacketHandler::readRx() function and reads 1 byte data on the packet The function calls PacketHandler::readRx() function, gets 1 byte data from the packet.

Parameters
portPortHandler instance
dataData extracted from the packet
errorDynamixel hardware error
Returns
communication results which come from PacketHandler::readRx()

Implemented in dynamixel::Protocol2PacketHandler, and dynamixel::Protocol1PacketHandler.

virtual int dynamixel::PacketHandler::read1ByteTx ( PortHandler port,
uint8_t  id,
uint16_t  address 
)
pure virtual

The function that calls PacketHandler::readTx() function for reading 1 byte data The function calls PacketHandler::readTx() function for reading 1 byte data.

Parameters
portPortHandler instance
idDynamixel ID
addressAddress of the data for read
Returns
communication results which come from PacketHandler::readTx()

Implemented in dynamixel::Protocol2PacketHandler, and dynamixel::Protocol1PacketHandler.

virtual int dynamixel::PacketHandler::read1ByteTxRx ( PortHandler port,
uint8_t  id,
uint16_t  address,
uint8_t *  data,
uint8_t *  error = 0 
)
pure virtual

The function that calls PacketHandler::readTxRx() function for reading 1 byte data The function calls PacketHandler::readTxRx(), gets 1 byte data from the packet.

Parameters
portPortHandler instance
idDynamixel ID
addressAddress of the data for read
lengthLength of the data for read
dataData extracted from the packet
errorDynamixel hardware error
Returns
communication results which come from PacketHandler::txRxPacket()

Implemented in dynamixel::Protocol2PacketHandler, and dynamixel::Protocol1PacketHandler.

virtual int dynamixel::PacketHandler::read2ByteRx ( PortHandler port,
uint8_t  id,
uint16_t *  data,
uint8_t *  error = 0 
)
pure virtual

The function that calls PacketHandler::readRx() function and reads 2 byte data on the packet The function calls PacketHandler::readRx() function, gets 2 byte data from the packet.

Parameters
portPortHandler instance
dataData extracted from the packet
errorDynamixel hardware error
Returns
communication results which come from PacketHandler::readRx()

Implemented in dynamixel::Protocol2PacketHandler, and dynamixel::Protocol1PacketHandler.

virtual int dynamixel::PacketHandler::read2ByteTx ( PortHandler port,
uint8_t  id,
uint16_t  address 
)
pure virtual

The function that calls PacketHandler::readTx() function for reading 2 byte data The function calls PacketHandler::readTx() function for reading 2 byte data.

Parameters
portPortHandler instance
idDynamixel ID
addressAddress of the data for read
Returns
communication results which come from PacketHandler::readTx()

Implemented in dynamixel::Protocol2PacketHandler, and dynamixel::Protocol1PacketHandler.

virtual int dynamixel::PacketHandler::read2ByteTxRx ( PortHandler port,
uint8_t  id,
uint16_t  address,
uint16_t *  data,
uint8_t *  error = 0 
)
pure virtual

The function that calls PacketHandler::readTxRx() function for reading 2 byte data The function calls PacketHandler::readTxRx(), gets 2 byte data from the packet.

Parameters
portPortHandler instance
idDynamixel ID
addressAddress of the data for read
lengthLength of the data for read
dataData extracted from the packet
errorDynamixel hardware error
Returns
communication results which come from PacketHandler::txRxPacket()

Implemented in dynamixel::Protocol2PacketHandler, and dynamixel::Protocol1PacketHandler.

virtual int dynamixel::PacketHandler::read4ByteRx ( PortHandler port,
uint8_t  id,
uint32_t *  data,
uint8_t *  error = 0 
)
pure virtual

The function that calls PacketHandler::readRx() function and reads 4 byte data on the packet The function calls PacketHandler::readRx() function, gets 4 byte data from the packet.

Parameters
portPortHandler instance
dataData extracted from the packet
errorDynamixel hardware error
Returns
communication results which come from PacketHandler::readRx()

Implemented in dynamixel::Protocol2PacketHandler, and dynamixel::Protocol1PacketHandler.

virtual int dynamixel::PacketHandler::read4ByteTx ( PortHandler port,
uint8_t  id,
uint16_t  address 
)
pure virtual

The function that calls PacketHandler::readTx() function for reading 4 byte data The function calls PacketHandler::readTx() function for reading 4 byte data.

Parameters
portPortHandler instance
idDynamixel ID
addressAddress of the data for read
Returns
communication results which come from PacketHandler::readTx()

Implemented in dynamixel::Protocol2PacketHandler, and dynamixel::Protocol1PacketHandler.

virtual int dynamixel::PacketHandler::read4ByteTxRx ( PortHandler port,
uint8_t  id,
uint16_t  address,
uint32_t *  data,
uint8_t *  error = 0 
)
pure virtual

The function that calls PacketHandler::readTxRx() function for reading 4 byte data The function calls PacketHandler::readTxRx(), gets 4 byte data from the packet.

Parameters
portPortHandler instance
idDynamixel ID
addressAddress of the data for read
lengthLength of the data for read
dataData extracted from the packet
errorDynamixel hardware error
Returns
communication results which come from PacketHandler::txRxPacket()

Implemented in dynamixel::Protocol2PacketHandler, and dynamixel::Protocol1PacketHandler.

virtual int dynamixel::PacketHandler::readRx ( PortHandler port,
uint8_t  id,
uint16_t  length,
uint8_t *  data,
uint8_t *  error = 0 
)
pure virtual

The function that receives the packet and reads the data in the packet The function receives the packet which might be come by previous INST_READ instruction packet transmission, gets the data from the packet.

Parameters
portPortHandler instance
lengthLength of the data for read
dataData extracted from the packet
errorDynamixel hardware error
Returns
communication results which come from PacketHandler::rxPacket()

Implemented in dynamixel::Protocol2PacketHandler, and dynamixel::Protocol1PacketHandler.

virtual int dynamixel::PacketHandler::readTx ( PortHandler port,
uint8_t  id,
uint16_t  address,
uint16_t  length 
)
pure virtual

The function that transmits INST_READ instruction packet The function makes an instruction packet with INST_READ, transmits the packet with PacketHandler::txPacket(). It breaks out when it tries to transmit to BROADCAST_ID.

Parameters
portPortHandler instance
idDynamixel ID
addressAddress of the data for read
lengthLength of the data for read
Returns
COMM_NOT_AVAILABLE
when it tries to transmit to BROADCAST_ID
or the other communication results which come from PacketHandler::txPacket()

Implemented in dynamixel::Protocol2PacketHandler, and dynamixel::Protocol1PacketHandler.

virtual int dynamixel::PacketHandler::readTxRx ( PortHandler port,
uint8_t  id,
uint16_t  address,
uint16_t  length,
uint8_t *  data,
uint8_t *  error = 0 
)
pure virtual

The function that transmits INST_READ instruction packet, and read data from received packet The function makes an instruction packet with INST_READ, transmits and receives the packet with PacketHandler::txRxPacket(), gets the data from the packet. It breaks out when it tries to transmit to BROADCAST_ID.

Parameters
portPortHandler instance
idDynamixel ID
addressAddress of the data for read
lengthLength of the data for read
dataData extracted from the packet
errorDynamixel hardware error
Returns
COMM_NOT_AVAILABLE
when it tries to transmit to BROADCAST_ID
or the other communication results which come from PacketHandler::txRxPacket()

Implemented in dynamixel::Protocol2PacketHandler, and dynamixel::Protocol1PacketHandler.

virtual int dynamixel::PacketHandler::reboot ( PortHandler port,
uint8_t  id,
uint8_t *  error = 0 
)
pure virtual

The function that makes Dynamixel reboot The function makes an instruction packet with INST_REBOOT, transmits the packet with PacketHandler::txRxPacket(), then Dynamixel reboots. During reboot, its LED will blink.

Parameters
portPortHandler instance
idDynamixel ID
errorDynamixel hardware error
Returns
COMM_NOT_AVAILABLE

Implemented in dynamixel::Protocol2PacketHandler, and dynamixel::Protocol1PacketHandler.

virtual int dynamixel::PacketHandler::regWriteTxOnly ( PortHandler port,
uint8_t  id,
uint16_t  address,
uint16_t  length,
uint8_t *  data 
)
pure virtual

The function that transmits INST_REG_WRITE instruction packet with the data for writing on the Dynamixel register The function makes an instruction packet with INST_REG_WRITE and the data for writing on the Dynamixel register, transmits the packet with PacketHandler::txPacket(). The data written in the register will act when INST_ACTION instruction packet is transmitted to the Dynamixel.

Parameters
portPortHandler instance
idDynamixel ID
addressAddress of the data for write
lengthLength of the data for write
dataData for write
Returns
communication results which come from PacketHandler::txPacket()

Implemented in dynamixel::Protocol2PacketHandler, and dynamixel::Protocol1PacketHandler.

virtual int dynamixel::PacketHandler::regWriteTxRx ( PortHandler port,
uint8_t  id,
uint16_t  address,
uint16_t  length,
uint8_t *  data,
uint8_t *  error = 0 
)
pure virtual

The function that transmits INST_REG_WRITE instruction packet with the data for writing on the Dynamixel register, and receives the packet The function makes an instruction packet with INST_REG_WRITE and the data for writing on the Dynamixel register, transmits and receives the packet with PacketHandler::txRxPacket(), gets the error from the packet. The data written in the register will act when INST_ACTION instruction packet is transmitted to the Dynamixel.

Parameters
portPortHandler instance
idDynamixel ID
addressAddress of the data for write
lengthLength of the data for write
dataData for write
errorDynamixel hardware error
Returns
communication results which come from PacketHandler::txRxPacket()

Implemented in dynamixel::Protocol2PacketHandler, and dynamixel::Protocol1PacketHandler.

virtual int dynamixel::PacketHandler::rxPacket ( PortHandler port,
uint8_t *  rxpacket 
)
pure virtual

The function that receives packet (rxpacket) during designated time via PortHandler port The function repeatedly tries to receive rxpacket by PortHandler::readPort() function. It breaks out when PortHandler::isPacketTimeout() shows the timeout, when rxpacket seemed as corrupted, or when nothing received.

Parameters
portPortHandler instance
rxpacketreceived packet
Returns
COMM_RX_CORRUPT
when it received the packet but it couldn't find header in the packet
when it found header in the packet but the id, length or error value is out of range
when it received the packet but it is shorted than expected
COMM_RX_TIMEOUT
when there is no rxpacket received until PortHandler::isPacketTimeout() shows the timeout
COMM_SUCCESS
when rxpacket passes checksum test
or COMM_RX_FAIL

Implemented in dynamixel::Protocol2PacketHandler, and dynamixel::Protocol1PacketHandler.

virtual int dynamixel::PacketHandler::syncReadTx ( PortHandler port,
uint16_t  start_address,
uint16_t  data_length,
uint8_t *  param,
uint16_t  param_length 
)
pure virtual

The function that transmits INST_SYNC_READ instruction packet The function makes an instruction packet with INST_SYNC_READ, transmits the packet with PacketHandler::txPacket().

Parameters
portPortHandler instance
start_addressAddress of the data for Sync Read
data_lengthLength of the data for Sync Read
paramParameter for Sync Read
param_lengthLength of the data for Sync Read
Returns
communication results which come from PacketHandler::txPacket()

Implemented in dynamixel::Protocol2PacketHandler, and dynamixel::Protocol1PacketHandler.

virtual int dynamixel::PacketHandler::syncWriteTxOnly ( PortHandler port,
uint16_t  start_address,
uint16_t  data_length,
uint8_t *  param,
uint16_t  param_length 
)
pure virtual

The function that transmits INST_SYNC_WRITE instruction packet The function makes an instruction packet with INST_SYNC_WRITE, transmits the packet with PacketHandler::txRxPacket().

Parameters
portPortHandler instance
start_addressAddress of the data for Sync Write
data_lengthLength of the data for Sync Write
paramParameter for Sync Write
param_lengthLength of the data for Sync Write
Returns
communication results which come from PacketHandler::txRxPacket()

Implemented in dynamixel::Protocol2PacketHandler, and dynamixel::Protocol1PacketHandler.

virtual int dynamixel::PacketHandler::txPacket ( PortHandler port,
uint8_t *  txpacket 
)
pure virtual

The function that transmits the instruction packet txpacket via PortHandler port. The function clears the port buffer by PortHandler::clearPort() function, then transmits txpacket by PortHandler::writePort() function. The function activates only when the port is not busy and when the packet is already written on the port buffer.

Parameters
portPortHandler instance
txpacketpacket for transmission
Returns
COMM_PORT_BUSY
when the port is already in use
COMM_TX_ERROR
when txpacket is out of range described by TXPACKET_MAX_LEN
COMM_TX_FAIL
when written packet is shorter than expected
or COMM_SUCCESS

Implemented in dynamixel::Protocol2PacketHandler, and dynamixel::Protocol1PacketHandler.

virtual int dynamixel::PacketHandler::txRxPacket ( PortHandler port,
uint8_t *  txpacket,
uint8_t *  rxpacket,
uint8_t *  error = 0 
)
pure virtual

The function that transmits packet (txpacket) and receives packet (rxpacket) during designated time via PortHandler port The function calls PacketHandler::txPacket(), and calls PacketHandler::rxPacket() if it succeeds PacketHandler::txPacket(). It breaks out when it fails PacketHandler::txPacket(), when txpacket is called by PacketHandler::broadcastPing() / PacketHandler::syncWriteTxOnly() / PacketHandler::regWriteTxOnly / PacketHandler::action.

Parameters
portPortHandler instance
txpacketpacket for transmission
rxpacketreceived packet
Returns
COMM_SUCCESS
when it succeeds PacketHandler::txPacket() and PacketHandler::rxPacket()
or the other communication results which come from PacketHandler::txPacket() and PacketHandler::rxPacket()

Implemented in dynamixel::Protocol2PacketHandler, and dynamixel::Protocol1PacketHandler.

virtual int dynamixel::PacketHandler::write1ByteTxOnly ( PortHandler port,
uint8_t  id,
uint16_t  address,
uint8_t  data 
)
pure virtual

The function that calls PacketHandler::writeTxOnly() for writing 1 byte data The function calls PacketHandler::writeTxOnly() for writing 1 byte data.

Parameters
portPortHandler instance
idDynamixel ID
addressAddress of the data for write
dataData for write
Returns
communication results which come from PacketHandler::writeTxOnly()

Implemented in dynamixel::Protocol2PacketHandler, and dynamixel::Protocol1PacketHandler.

virtual int dynamixel::PacketHandler::write1ByteTxRx ( PortHandler port,
uint8_t  id,
uint16_t  address,
uint8_t  data,
uint8_t *  error = 0 
)
pure virtual

The function that calls PacketHandler::writeTxRx() for writing 1 byte data and receives the packet The function calls PacketHandler::writeTxRx() for writing 1 byte data and receves the packet, gets the error from the packet.

Parameters
portPortHandler instance
idDynamixel ID
addressAddress of the data for write
dataData for write
errorDynamixel hardware error
Returns
communication results which come from PacketHandler::writeTxRx()

Implemented in dynamixel::Protocol2PacketHandler, and dynamixel::Protocol1PacketHandler.

virtual int dynamixel::PacketHandler::write2ByteTxOnly ( PortHandler port,
uint8_t  id,
uint16_t  address,
uint16_t  data 
)
pure virtual

The function that calls PacketHandler::writeTxOnly() for writing 2 byte data The function calls PacketHandler::writeTxOnly() for writing 2 byte data.

Parameters
portPortHandler instance
idDynamixel ID
addressAddress of the data for write
dataData for write
Returns
communication results which come from PacketHandler::writeTxOnly()

Implemented in dynamixel::Protocol2PacketHandler, and dynamixel::Protocol1PacketHandler.

virtual int dynamixel::PacketHandler::write2ByteTxRx ( PortHandler port,
uint8_t  id,
uint16_t  address,
uint16_t  data,
uint8_t *  error = 0 
)
pure virtual

The function that calls PacketHandler::writeTxRx() for writing 2 byte data and receives the packet The function calls PacketHandler::writeTxRx() for writing 2 byte data and receves the packet, gets the error from the packet.

Parameters
portPortHandler instance
idDynamixel ID
addressAddress of the data for write
dataData for write
errorDynamixel hardware error
Returns
communication results which come from PacketHandler::writeTxRx()

Implemented in dynamixel::Protocol2PacketHandler, and dynamixel::Protocol1PacketHandler.

virtual int dynamixel::PacketHandler::write4ByteTxOnly ( PortHandler port,
uint8_t  id,
uint16_t  address,
uint32_t  data 
)
pure virtual

The function that calls PacketHandler::writeTxOnly() for writing 4 byte data The function calls PacketHandler::writeTxOnly() for writing 4 byte data.

Parameters
portPortHandler instance
idDynamixel ID
addressAddress of the data for write
dataData for write
Returns
communication results which come from PacketHandler::writeTxOnly()

Implemented in dynamixel::Protocol2PacketHandler, and dynamixel::Protocol1PacketHandler.

virtual int dynamixel::PacketHandler::write4ByteTxRx ( PortHandler port,
uint8_t  id,
uint16_t  address,
uint32_t  data,
uint8_t *  error = 0 
)
pure virtual

The function that calls PacketHandler::writeTxRx() for writing 4 byte data and receives the packet The function calls PacketHandler::writeTxRx() for writing 4 byte data and receves the packet, gets the error from the packet.

Parameters
portPortHandler instance
idDynamixel ID
addressAddress of the data for write
dataData for write
errorDynamixel hardware error
Returns
communication results which come from PacketHandler::writeTxRx()

Implemented in dynamixel::Protocol2PacketHandler, and dynamixel::Protocol1PacketHandler.

virtual int dynamixel::PacketHandler::writeTxOnly ( PortHandler port,
uint8_t  id,
uint16_t  address,
uint16_t  length,
uint8_t *  data 
)
pure virtual

The function that transmits INST_WRITE instruction packet with the data for write The function makes an instruction packet with INST_WRITE and the data for write, transmits the packet with PacketHandler::txPacket().

Parameters
portPortHandler instance
idDynamixel ID
addressAddress of the data for write
lengthLength of the data for write
dataData for write
Returns
communication results which come from PacketHandler::txPacket()

Implemented in dynamixel::Protocol2PacketHandler, and dynamixel::Protocol1PacketHandler.

virtual int dynamixel::PacketHandler::writeTxRx ( PortHandler port,
uint8_t  id,
uint16_t  address,
uint16_t  length,
uint8_t *  data,
uint8_t *  error = 0 
)
pure virtual

The function that transmits INST_WRITE instruction packet with the data for write, and receives the packet The function makes an instruction packet with INST_WRITE and the data for write, transmits and receives the packet with PacketHandler::txRxPacket(), gets the error from the packet.

Parameters
portPortHandler instance
idDynamixel ID
addressAddress of the data for write
lengthLength of the data for write
dataData for write
errorDynamixel hardware error
Returns
communication results which come from PacketHandler::txRxPacket()

Implemented in dynamixel::Protocol2PacketHandler, and dynamixel::Protocol1PacketHandler.


The documentation for this class was generated from the following files:


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