Public Member Functions | Static Public Member Functions | Private Member Functions | Static Private Attributes | List of all members
dynamixel::Protocol2PacketHandler Class Reference

The class for control Dynamixel by using Protocol2.0. More...

#include <protocol2_packet_handler.h>

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

Public Member Functions

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

Static Public Member Functions

static Protocol2PacketHandlergetInstance ()
 The function that returns Protocol2PacketHandler instance. More...
 
- Static Public Member Functions inherited from dynamixel::PacketHandler
static PacketHandlergetPacketHandler (float protocol_version=2.0)
 The function that returns PacketHandler instance. More...
 

Private Member Functions

void addStuffing (uint8_t *packet)
 
 Protocol2PacketHandler ()
 
void removeStuffing (uint8_t *packet)
 
uint16_t updateCRC (uint16_t crc_accum, uint8_t *data_blk_ptr, uint16_t data_blk_size)
 

Static Private Attributes

static Protocol2PacketHandlerunique_instance_ = new Protocol2PacketHandler()
 

Additional Inherited Members

- Protected Member Functions inherited from dynamixel::PacketHandler
 PacketHandler ()
 

Detailed Description

The class for control Dynamixel by using Protocol2.0.

Definition at line 34 of file protocol2_packet_handler.h.

Constructor & Destructor Documentation

Protocol2PacketHandler::Protocol2PacketHandler ( )
private

Definition at line 67 of file protocol2_packet_handler.cpp.

virtual dynamixel::Protocol2PacketHandler::~Protocol2PacketHandler ( )
inlinevirtual

Definition at line 52 of file protocol2_packet_handler.h.

Member Function Documentation

int Protocol2PacketHandler::action ( PortHandler port,
uint8_t  id 
)
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 Protocol2PacketHandler::txRxPacket(). To use this function, Dynamixel register should be set by Protocol2PacketHandler::regWriteTxOnly() or Protocol2PacketHandler::regWriteTxRx()

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

Implements dynamixel::PacketHandler.

Definition at line 593 of file protocol2_packet_handler.cpp.

void Protocol2PacketHandler::addStuffing ( uint8_t *  packet)
private

Definition at line 194 of file protocol2_packet_handler.cpp.

int Protocol2PacketHandler::broadcastPing ( PortHandler port,
std::vector< uint8_t > &  id_list 
)
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

Implements dynamixel::PacketHandler.

Definition at line 496 of file protocol2_packet_handler.cpp.

int Protocol2PacketHandler::bulkReadTx ( PortHandler port,
uint8_t *  param,
uint16_t  param_length 
)
virtual

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

Parameters
portPortHandler instance
paramParameter for Bulk Read {ID1, ADDR_L1, ADDR_H1, LEN_L1, LEN_H1, ID2, ADDR_L2, ADDR_H2, LEN_L2, LEN_H2, ...}
param_lengthLength of the data for Bulk Read
Returns
communication results which come from Protocol2PacketHandler::txPacket()

Implements dynamixel::PacketHandler.

Definition at line 1021 of file protocol2_packet_handler.cpp.

int Protocol2PacketHandler::bulkWriteTxOnly ( PortHandler port,
uint8_t *  param,
uint16_t  param_length 
)
virtual

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

Parameters
portPortHandler instance
paramParameter for Bulk Write {ID1, START_ADDR_L, START_ADDR_H, DATA_LEN_L, DATA_LEN_H, DATA0, DATA1, ..., DATAn, ID2, START_ADDR_L, START_ADDR_H, DATA_LEN_L, DATA_LEN_H, DATA0, DATA1, ..., DATAn}
param_lengthLength of the data for Bulk Write
Returns
communication results which come from Protocol2PacketHandler::txRxPacket()

Implements dynamixel::PacketHandler.

Definition at line 1054 of file protocol2_packet_handler.cpp.

int Protocol2PacketHandler::clearMultiTurn ( PortHandler port,
uint8_t  id,
uint8_t *  error = 0 
)
virtual

The function that reset multi-turn revolution information of Dynamixel The function makes an instruction packet with INST_CLEAR, transmits the packet with Protocol2PacketHandler::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 Protocol2PacketHandler::txRxPacket()

Implements dynamixel::PacketHandler.

Definition at line 618 of file protocol2_packet_handler.cpp.

int Protocol2PacketHandler::factoryReset ( PortHandler port,
uint8_t  id,
uint8_t  option,
uint8_t *  error = 0 
)
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 Protocol2PacketHandler::txRxPacket(). Be careful of the use.

Parameters
portPortHandler instance
idDynamixel ID
optionReset option (0xFF for reset all values / 0x01 for reset all values except ID / 0x02 for reset all values except ID and Baudrate)
errorDynamixel hardware error
Returns
communication results which come from Protocol2PacketHandler::txRxPacket()

Implements dynamixel::PacketHandler.

Definition at line 636 of file protocol2_packet_handler.cpp.

static Protocol2PacketHandler* dynamixel::Protocol2PacketHandler::getInstance ( )
inlinestatic

The function that returns Protocol2PacketHandler instance.

Returns
Protocol2PacketHandler instance

Definition at line 50 of file protocol2_packet_handler.h.

float dynamixel::Protocol2PacketHandler::getProtocolVersion ( )
inlinevirtual

The function that returns Protocol version used in Protocol2PacketHandler (2.0)

Returns
2.0

Implements dynamixel::PacketHandler.

Definition at line 58 of file protocol2_packet_handler.h.

const char * Protocol2PacketHandler::getRxPacketError ( uint8_t  error)
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)

Implements dynamixel::PacketHandler.

Definition at line 105 of file protocol2_packet_handler.cpp.

const char * Protocol2PacketHandler::getTxRxResult ( int  result)
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)

Implements dynamixel::PacketHandler.

Definition at line 69 of file protocol2_packet_handler.cpp.

int Protocol2PacketHandler::ping ( PortHandler port,
uint8_t  id,
uint8_t *  error = 0 
)
virtual

The function that pings Dynamixel but doesn't take its model number The function calls Protocol2PacketHandler::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 Protocol2PacketHandler::ping()

Implements dynamixel::PacketHandler.

Definition at line 469 of file protocol2_packet_handler.cpp.

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

The function that pings Dynamixel and takes its model number The function makes an instruction packet with INST_PING, transmits the packet with Protocol2PacketHandler::txRxPacket(), and call Protocol2PacketHandler::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 Protocol2PacketHandler::txRxPacket() and Protocol2PacketHandler::readTxRx()

Implements dynamixel::PacketHandler.

Definition at line 474 of file protocol2_packet_handler.cpp.

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

The function that calls Protocol2PacketHandler::readRx() function and reads 1 byte data on the packet The function calls Protocol2PacketHandler::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 Protocol2PacketHandler::readRx()

Implements dynamixel::PacketHandler.

Definition at line 755 of file protocol2_packet_handler.cpp.

int Protocol2PacketHandler::read1ByteTx ( PortHandler port,
uint8_t  id,
uint16_t  address 
)
virtual

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

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

Implements dynamixel::PacketHandler.

Definition at line 751 of file protocol2_packet_handler.cpp.

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

The function that calls Protocol2PacketHandler::readTxRx() function for reading 1 byte data The function calls Protocol2PacketHandler::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 Protocol2PacketHandler::txRxPacket()

Implements dynamixel::PacketHandler.

Definition at line 763 of file protocol2_packet_handler.cpp.

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

The function that calls Protocol2PacketHandler::readRx() function and reads 2 byte data on the packet The function calls Protocol2PacketHandler::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 Protocol2PacketHandler::readRx()

Implements dynamixel::PacketHandler.

Definition at line 776 of file protocol2_packet_handler.cpp.

int Protocol2PacketHandler::read2ByteTx ( PortHandler port,
uint8_t  id,
uint16_t  address 
)
virtual

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

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

Implements dynamixel::PacketHandler.

Definition at line 772 of file protocol2_packet_handler.cpp.

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

The function that calls Protocol2PacketHandler::readTxRx() function for reading 2 byte data The function calls Protocol2PacketHandler::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 Protocol2PacketHandler::txRxPacket()

Implements dynamixel::PacketHandler.

Definition at line 784 of file protocol2_packet_handler.cpp.

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

The function that calls Protocol2PacketHandler::readRx() function and reads 4 byte data on the packet The function calls Protocol2PacketHandler::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 Protocol2PacketHandler::readRx()

Implements dynamixel::PacketHandler.

Definition at line 797 of file protocol2_packet_handler.cpp.

int Protocol2PacketHandler::read4ByteTx ( PortHandler port,
uint8_t  id,
uint16_t  address 
)
virtual

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

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

Implements dynamixel::PacketHandler.

Definition at line 793 of file protocol2_packet_handler.cpp.

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

The function that calls Protocol2PacketHandler::readTxRx() function for reading 4 byte data The function calls Protocol2PacketHandler::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 Protocol2PacketHandler::txRxPacket()

Implements dynamixel::PacketHandler.

Definition at line 805 of file protocol2_packet_handler.cpp.

int Protocol2PacketHandler::readRx ( PortHandler port,
uint8_t  id,
uint16_t  length,
uint8_t *  data,
uint8_t *  error = 0 
)
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 Protocol2PacketHandler::rxPacket()

Implements dynamixel::PacketHandler.

Definition at line 677 of file protocol2_packet_handler.cpp.

int Protocol2PacketHandler::readTx ( PortHandler port,
uint8_t  id,
uint16_t  address,
uint16_t  length 
)
virtual

The function that transmits INST_READ instruction packet The function makes an instruction packet with INST_READ, transmits the packet with Protocol2PacketHandler::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 Protocol2PacketHandler::txPacket()

Implements dynamixel::PacketHandler.

Definition at line 650 of file protocol2_packet_handler.cpp.

int Protocol2PacketHandler::readTxRx ( PortHandler port,
uint8_t  id,
uint16_t  address,
uint16_t  length,
uint8_t *  data,
uint8_t *  error = 0 
)
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 Protocol2PacketHandler::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 Protocol2PacketHandler::txRxPacket()

Implements dynamixel::PacketHandler.

Definition at line 707 of file protocol2_packet_handler.cpp.

int Protocol2PacketHandler::reboot ( PortHandler port,
uint8_t  id,
uint8_t *  error = 0 
)
virtual

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

Parameters
portPortHandler instance
idDynamixel ID
errorDynamixel hardware error
Returns
COMM_NOT_AVAILABLE

Implements dynamixel::PacketHandler.

Definition at line 605 of file protocol2_packet_handler.cpp.

int Protocol2PacketHandler::regWriteTxOnly ( PortHandler port,
uint8_t  id,
uint16_t  address,
uint16_t  length,
uint8_t *  data 
)
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 Protocol2PacketHandler::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 Protocol2PacketHandler::txPacket()

Implements dynamixel::PacketHandler.

Definition at line 904 of file protocol2_packet_handler.cpp.

int Protocol2PacketHandler::regWriteTxRx ( PortHandler port,
uint8_t  id,
uint16_t  address,
uint16_t  length,
uint8_t *  data,
uint8_t *  error = 0 
)
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 Protocol2PacketHandler::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 Protocol2PacketHandler::txRxPacket()

Implements dynamixel::PacketHandler.

Definition at line 932 of file protocol2_packet_handler.cpp.

void Protocol2PacketHandler::removeStuffing ( uint8_t *  packet)
private

Definition at line 240 of file protocol2_packet_handler.cpp.

int Protocol2PacketHandler::rxPacket ( PortHandler port,
uint8_t *  rxpacket 
)
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

Implements dynamixel::PacketHandler.

Definition at line 307 of file protocol2_packet_handler.cpp.

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

The function that transmits INST_SYNC_READ instruction packet The function makes an instruction packet with INST_SYNC_READ, transmits the packet with Protocol2PacketHandler::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 Protocol2PacketHandler::txPacket()

Implements dynamixel::PacketHandler.

Definition at line 960 of file protocol2_packet_handler.cpp.

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

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

Parameters
portPortHandler instance
start_addressAddress of the data for Sync Write
data_lengthLength of the data for Sync Write
paramParameter for Sync Write {ID1, DATA0, DATA1, ..., DATAn, ID2, DATA0, DATA1, ..., DATAn, ID3, DATA0, DATA1, ..., DATAn}
param_lengthLength of the data for Sync Write
Returns
communication results which come from Protocol2PacketHandler::txRxPacket()

Implements dynamixel::PacketHandler.

Definition at line 991 of file protocol2_packet_handler.cpp.

int Protocol2PacketHandler::txPacket ( PortHandler port,
uint8_t *  txpacket 
)
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

Implements dynamixel::PacketHandler.

Definition at line 263 of file protocol2_packet_handler.cpp.

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

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

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

Implements dynamixel::PacketHandler.

Definition at line 423 of file protocol2_packet_handler.cpp.

unsigned short Protocol2PacketHandler::updateCRC ( uint16_t  crc_accum,
uint8_t *  data_blk_ptr,
uint16_t  data_blk_size 
)
private

Definition at line 143 of file protocol2_packet_handler.cpp.

int Protocol2PacketHandler::write1ByteTxOnly ( PortHandler port,
uint8_t  id,
uint16_t  address,
uint8_t  data 
)
virtual

The function that calls Protocol2PacketHandler::writeTxOnly() for writing 1 byte data The function calls Protocol2PacketHandler::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 Protocol2PacketHandler::writeTxOnly()

Implements dynamixel::PacketHandler.

Definition at line 871 of file protocol2_packet_handler.cpp.

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

The function that calls Protocol2PacketHandler::writeTxRx() for writing 1 byte data and receives the packet The function calls Protocol2PacketHandler::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 Protocol2PacketHandler::writeTxRx()

Implements dynamixel::PacketHandler.

Definition at line 876 of file protocol2_packet_handler.cpp.

int Protocol2PacketHandler::write2ByteTxOnly ( PortHandler port,
uint8_t  id,
uint16_t  address,
uint16_t  data 
)
virtual

The function that calls Protocol2PacketHandler::writeTxOnly() for writing 2 byte data The function calls Protocol2PacketHandler::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 Protocol2PacketHandler::writeTxOnly()

Implements dynamixel::PacketHandler.

Definition at line 882 of file protocol2_packet_handler.cpp.

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

The function that calls Protocol2PacketHandler::writeTxRx() for writing 2 byte data and receives the packet The function calls Protocol2PacketHandler::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 Protocol2PacketHandler::writeTxRx()

Implements dynamixel::PacketHandler.

Definition at line 887 of file protocol2_packet_handler.cpp.

int Protocol2PacketHandler::write4ByteTxOnly ( PortHandler port,
uint8_t  id,
uint16_t  address,
uint32_t  data 
)
virtual

The function that calls Protocol2PacketHandler::writeTxOnly() for writing 4 byte data The function calls Protocol2PacketHandler::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 Protocol2PacketHandler::writeTxOnly()

Implements dynamixel::PacketHandler.

Definition at line 893 of file protocol2_packet_handler.cpp.

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

The function that calls Protocol2PacketHandler::writeTxRx() for writing 4 byte data and receives the packet The function calls Protocol2PacketHandler::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 Protocol2PacketHandler::writeTxRx()

Implements dynamixel::PacketHandler.

Definition at line 898 of file protocol2_packet_handler.cpp.

int Protocol2PacketHandler::writeTxOnly ( PortHandler port,
uint8_t  id,
uint16_t  address,
uint16_t  length,
uint8_t *  data 
)
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 Protocol2PacketHandler::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 Protocol2PacketHandler::txPacket()

Implements dynamixel::PacketHandler.

Definition at line 815 of file protocol2_packet_handler.cpp.

int Protocol2PacketHandler::writeTxRx ( PortHandler port,
uint8_t  id,
uint16_t  address,
uint16_t  length,
uint8_t *  data,
uint8_t *  error = 0 
)
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 Protocol2PacketHandler::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 Protocol2PacketHandler::txRxPacket()

Implements dynamixel::PacketHandler.

Definition at line 843 of file protocol2_packet_handler.cpp.

Member Data Documentation

Protocol2PacketHandler * Protocol2PacketHandler::unique_instance_ = new Protocol2PacketHandler()
staticprivate

Definition at line 37 of file protocol2_packet_handler.h.


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