The class that inherits Protocol1PacketHandler class or Protocol2PacketHandler class. More...
#include <packet_handler.h>
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 PacketHandler * | getPacketHandler (float protocol_version=2.0) |
The function that returns PacketHandler instance. More... | |
Protected Member Functions | |
PacketHandler () | |
The class that inherits Protocol1PacketHandler class or Protocol2PacketHandler class.
Definition at line 82 of file packet_handler.h.
|
inlineprotected |
Definition at line 85 of file packet_handler.h.
|
inlinevirtual |
Definition at line 94 of file packet_handler.h.
|
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()
port | PortHandler instance |
id | Dynamixel ID |
Implemented in dynamixel::Protocol2PacketHandler, and dynamixel::Protocol1PacketHandler.
|
pure virtual |
(Available only in Protocol 2.0) The function that pings all connected Dynamixel
port | PortHandler instance |
id_list | ID list of Dynamixels which are found by broadcast ping |
Implemented in dynamixel::Protocol2PacketHandler, and dynamixel::Protocol1PacketHandler.
|
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().
port | PortHandler instance |
param | Parameter for Bulk Read |
param_length | Length of the data for Bulk Read |
Implemented in dynamixel::Protocol2PacketHandler, and dynamixel::Protocol1PacketHandler.
|
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().
port | PortHandler instance |
param | Parameter for Bulk Write |
param_length | Length of the data for Bulk Write |
Implemented in dynamixel::Protocol2PacketHandler, and dynamixel::Protocol1PacketHandler.
|
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).
port | PortHandler instance |
id | Dynamixel ID |
error | Dynamixel hardware error |
Implemented in dynamixel::Protocol2PacketHandler, and dynamixel::Protocol1PacketHandler.
|
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.
port | PortHandler instance |
id | Dynamixel ID |
option | Reset option |
error | Dynamixel hardware error |
Implemented in dynamixel::Protocol2PacketHandler, and dynamixel::Protocol1PacketHandler.
|
static |
The function that returns PacketHandler instance.
Definition at line 40 of file packet_handler.cpp.
|
pure virtual |
The function that returns Protocol version.
Implemented in dynamixel::Protocol2PacketHandler, and dynamixel::Protocol1PacketHandler.
|
pure virtual |
The function that gets description of hardware error.
error | Dynamixel hardware error which might be gotten by the tx rx functions |
Implemented in dynamixel::Protocol2PacketHandler, and dynamixel::Protocol1PacketHandler.
|
pure virtual |
The function that gets description of communication result.
result | Communication result which might be gotten by the tx rx functions |
Implemented in dynamixel::Protocol2PacketHandler, and dynamixel::Protocol1PacketHandler.
|
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.
port | PortHandler instance |
id | Dynamixel ID |
error | Dynamixel hardware error |
Implemented in dynamixel::Protocol2PacketHandler, and dynamixel::Protocol1PacketHandler.
|
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.
port | PortHandler instance |
id | Dynamixel ID |
error | Dynamixel hardware error |
Implemented in dynamixel::Protocol2PacketHandler, and dynamixel::Protocol1PacketHandler.
|
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.
port | PortHandler instance |
data | Data extracted from the packet |
error | Dynamixel hardware error |
Implemented in dynamixel::Protocol2PacketHandler, and dynamixel::Protocol1PacketHandler.
|
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.
port | PortHandler instance |
id | Dynamixel ID |
address | Address of the data for read |
Implemented in dynamixel::Protocol2PacketHandler, and dynamixel::Protocol1PacketHandler.
|
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.
port | PortHandler instance |
id | Dynamixel ID |
address | Address of the data for read |
length | Length of the data for read |
data | Data extracted from the packet |
error | Dynamixel hardware error |
Implemented in dynamixel::Protocol2PacketHandler, and dynamixel::Protocol1PacketHandler.
|
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.
port | PortHandler instance |
data | Data extracted from the packet |
error | Dynamixel hardware error |
Implemented in dynamixel::Protocol2PacketHandler, and dynamixel::Protocol1PacketHandler.
|
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.
port | PortHandler instance |
id | Dynamixel ID |
address | Address of the data for read |
Implemented in dynamixel::Protocol2PacketHandler, and dynamixel::Protocol1PacketHandler.
|
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.
port | PortHandler instance |
id | Dynamixel ID |
address | Address of the data for read |
length | Length of the data for read |
data | Data extracted from the packet |
error | Dynamixel hardware error |
Implemented in dynamixel::Protocol2PacketHandler, and dynamixel::Protocol1PacketHandler.
|
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.
port | PortHandler instance |
data | Data extracted from the packet |
error | Dynamixel hardware error |
Implemented in dynamixel::Protocol2PacketHandler, and dynamixel::Protocol1PacketHandler.
|
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.
port | PortHandler instance |
id | Dynamixel ID |
address | Address of the data for read |
Implemented in dynamixel::Protocol2PacketHandler, and dynamixel::Protocol1PacketHandler.
|
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.
port | PortHandler instance |
id | Dynamixel ID |
address | Address of the data for read |
length | Length of the data for read |
data | Data extracted from the packet |
error | Dynamixel hardware error |
Implemented in dynamixel::Protocol2PacketHandler, and dynamixel::Protocol1PacketHandler.
|
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.
port | PortHandler instance |
length | Length of the data for read |
data | Data extracted from the packet |
error | Dynamixel hardware error |
Implemented in dynamixel::Protocol2PacketHandler, and dynamixel::Protocol1PacketHandler.
|
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.
port | PortHandler instance |
id | Dynamixel ID |
address | Address of the data for read |
length | Length of the data for read |
Implemented in dynamixel::Protocol2PacketHandler, and dynamixel::Protocol1PacketHandler.
|
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.
port | PortHandler instance |
id | Dynamixel ID |
address | Address of the data for read |
length | Length of the data for read |
data | Data extracted from the packet |
error | Dynamixel hardware error |
Implemented in dynamixel::Protocol2PacketHandler, and dynamixel::Protocol1PacketHandler.
|
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.
port | PortHandler instance |
id | Dynamixel ID |
error | Dynamixel hardware error |
Implemented in dynamixel::Protocol2PacketHandler, and dynamixel::Protocol1PacketHandler.
|
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.
port | PortHandler instance |
id | Dynamixel ID |
address | Address of the data for write |
length | Length of the data for write |
data | Data for write |
Implemented in dynamixel::Protocol2PacketHandler, and dynamixel::Protocol1PacketHandler.
|
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.
port | PortHandler instance |
id | Dynamixel ID |
address | Address of the data for write |
length | Length of the data for write |
data | Data for write |
error | Dynamixel hardware error |
Implemented in dynamixel::Protocol2PacketHandler, and dynamixel::Protocol1PacketHandler.
|
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.
port | PortHandler instance |
rxpacket | received packet |
Implemented in dynamixel::Protocol2PacketHandler, and dynamixel::Protocol1PacketHandler.
|
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().
port | PortHandler instance |
start_address | Address of the data for Sync Read |
data_length | Length of the data for Sync Read |
param | Parameter for Sync Read |
param_length | Length of the data for Sync Read |
Implemented in dynamixel::Protocol2PacketHandler, and dynamixel::Protocol1PacketHandler.
|
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().
port | PortHandler instance |
start_address | Address of the data for Sync Write |
data_length | Length of the data for Sync Write |
param | Parameter for Sync Write |
param_length | Length of the data for Sync Write |
Implemented in dynamixel::Protocol2PacketHandler, and dynamixel::Protocol1PacketHandler.
|
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.
port | PortHandler instance |
txpacket | packet for transmission |
Implemented in dynamixel::Protocol2PacketHandler, and dynamixel::Protocol1PacketHandler.
|
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.
port | PortHandler instance |
txpacket | packet for transmission |
rxpacket | received packet |
Implemented in dynamixel::Protocol2PacketHandler, and dynamixel::Protocol1PacketHandler.
|
pure virtual |
The function that calls PacketHandler::writeTxOnly() for writing 1 byte data The function calls PacketHandler::writeTxOnly() for writing 1 byte data.
port | PortHandler instance |
id | Dynamixel ID |
address | Address of the data for write |
data | Data for write |
Implemented in dynamixel::Protocol2PacketHandler, and dynamixel::Protocol1PacketHandler.
|
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.
port | PortHandler instance |
id | Dynamixel ID |
address | Address of the data for write |
data | Data for write |
error | Dynamixel hardware error |
Implemented in dynamixel::Protocol2PacketHandler, and dynamixel::Protocol1PacketHandler.
|
pure virtual |
The function that calls PacketHandler::writeTxOnly() for writing 2 byte data The function calls PacketHandler::writeTxOnly() for writing 2 byte data.
port | PortHandler instance |
id | Dynamixel ID |
address | Address of the data for write |
data | Data for write |
Implemented in dynamixel::Protocol2PacketHandler, and dynamixel::Protocol1PacketHandler.
|
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.
port | PortHandler instance |
id | Dynamixel ID |
address | Address of the data for write |
data | Data for write |
error | Dynamixel hardware error |
Implemented in dynamixel::Protocol2PacketHandler, and dynamixel::Protocol1PacketHandler.
|
pure virtual |
The function that calls PacketHandler::writeTxOnly() for writing 4 byte data The function calls PacketHandler::writeTxOnly() for writing 4 byte data.
port | PortHandler instance |
id | Dynamixel ID |
address | Address of the data for write |
data | Data for write |
Implemented in dynamixel::Protocol2PacketHandler, and dynamixel::Protocol1PacketHandler.
|
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.
port | PortHandler instance |
id | Dynamixel ID |
address | Address of the data for write |
data | Data for write |
error | Dynamixel hardware error |
Implemented in dynamixel::Protocol2PacketHandler, and dynamixel::Protocol1PacketHandler.
|
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().
port | PortHandler instance |
id | Dynamixel ID |
address | Address of the data for write |
length | Length of the data for write |
data | Data for write |
Implemented in dynamixel::Protocol2PacketHandler, and dynamixel::Protocol1PacketHandler.
|
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.
port | PortHandler instance |
id | Dynamixel ID |
address | Address of the data for write |
length | Length of the data for write |
data | Data for write |
error | Dynamixel hardware error |
Implemented in dynamixel::Protocol2PacketHandler, and dynamixel::Protocol1PacketHandler.