The class for control Dynamixel by using Protocol1.0. More...
#include <protocol1_packet_handler.h>
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 Protocol1PacketHandler::txRxPacket(). To use this function, Dynamixel register should be set by Protocol1PacketHandler::regWriteTxOnly() or Protocol1PacketHandler::regWriteTxRx() | |
int | broadcastPing (PortHandler *port, std::vector< uint8_t > &id_list) |
(Available only in Protocol 2.0) The function that pings all connected Dynamixel | |
int | bulkReadTx (PortHandler *port, uint8_t *param, uint16_t param_length) |
(Available only on Dynamixel MX / X series) The function that transmits Bulk Read instruction packet The function makes an instruction packet with INST_BULK_READ, transmits the packet with Protocol1PacketHandler::txPacket(). | |
int | bulkWriteTxOnly (PortHandler *port, uint8_t *param, uint16_t param_length) |
(Available only in Protocol 2.0) The function that transmits Bulk Write instruction packet | |
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 Protocol1PacketHandler::txRxPacket(). Be careful of the use. | |
float | getProtocolVersion () |
The function that returns Protocol version used in Protocol1PacketHandler (1.0) | |
const char * | getRxPacketError (uint8_t error) |
The function that gets description of hardware error. | |
const char * | getTxRxResult (int result) |
The function that gets description of communication result. | |
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 Protocol1PacketHandler::ping() which gets Dynamixel model number, but doesn't carry the model number. | |
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 Protocol1PacketHandler::txRxPacket(), and call Protocol1PacketHandler::readTxRx to read model_number in the rx buffer. It breaks out when it tries to transmit to BROADCAST_ID. | |
int | read1ByteRx (PortHandler *port, uint8_t id, uint8_t *data, uint8_t *error=0) |
The function that calls Protocol1PacketHandler::readRx() function and reads 1 byte data on the packet The function calls Protocol1PacketHandler::readRx() function, gets 1 byte data from the packet. | |
int | read1ByteTx (PortHandler *port, uint8_t id, uint16_t address) |
The function that calls Protocol1PacketHandler::readTx() function for reading 1 byte data The function calls Protocol1PacketHandler::readTx() function for reading 1 byte data. | |
int | read1ByteTxRx (PortHandler *port, uint8_t id, uint16_t address, uint8_t *data, uint8_t *error=0) |
The function that calls Protocol1PacketHandler::readTxRx() function for reading 1 byte data The function calls Protocol1PacketHandler::readTxRx(), gets 1 byte data from the packet. | |
int | read2ByteRx (PortHandler *port, uint8_t id, uint16_t *data, uint8_t *error=0) |
The function that calls Protocol1PacketHandler::readRx() function and reads 2 byte data on the packet The function calls Protocol1PacketHandler::readRx() function, gets 2 byte data from the packet. | |
int | read2ByteTx (PortHandler *port, uint8_t id, uint16_t address) |
The function that calls Protocol1PacketHandler::readTx() function for reading 2 byte data The function calls Protocol1PacketHandler::readTx() function for reading 2 byte data. | |
int | read2ByteTxRx (PortHandler *port, uint8_t id, uint16_t address, uint16_t *data, uint8_t *error=0) |
The function that calls Protocol1PacketHandler::readTxRx() function for reading 2 byte data The function calls Protocol1PacketHandler::readTxRx(), gets 2 byte data from the packet. | |
int | read4ByteRx (PortHandler *port, uint8_t id, uint32_t *data, uint8_t *error=0) |
The function that calls Protocol1PacketHandler::readRx() function and reads 4 byte data on the packet The function calls Protocol1PacketHandler::readRx() function, gets 4 byte data from the packet. | |
int | read4ByteTx (PortHandler *port, uint8_t id, uint16_t address) |
The function that calls Protocol1PacketHandler::readTx() function for reading 4 byte data The function calls Protocol1PacketHandler::readTx() function for reading 4 byte data. | |
int | read4ByteTxRx (PortHandler *port, uint8_t id, uint16_t address, uint32_t *data, uint8_t *error=0) |
The function that calls Protocol1PacketHandler::readTxRx() function for reading 4 byte data The function calls Protocol1PacketHandler::readTxRx(), gets 4 byte data from the packet. | |
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. | |
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 Protocol1PacketHandler::txPacket(). It breaks out when it tries to transmit to BROADCAST_ID. | |
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 Protocol1PacketHandler::txRxPacket(), gets the data from the packet. It breaks out when it tries to transmit to BROADCAST_ID. | |
int | reboot (PortHandler *port, uint8_t id, uint8_t *error=0) |
(Available only in Protocol 2.0) The function that makes Dynamixel reboot | |
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 Protocol1PacketHandler::txPacket(). The data written in the register will act when INST_ACTION instruction packet is transmitted to the Dynamxel. | |
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 Protocol1PacketHandler::txRxPacket(), gets the error from the packet. The data written in the register will act when INST_ACTION instruction packet is transmitted to the Dynamxel. | |
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. | |
int | syncReadTx (PortHandler *port, uint16_t start_address, uint16_t data_length, uint8_t *param, uint16_t param_length) |
(Available only in Protocol 2.0) The function that transmits Sync Read instruction packet | |
int | syncWriteTxOnly (PortHandler *port, uint16_t start_address, uint16_t data_length, uint8_t *param, uint16_t param_length) |
The function that transmits Sync Write instruction packet The function makes an instruction packet with INST_SYNC_WRITE, transmits the packet with Protocol1PacketHandler::txRxPacket(). | |
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. | |
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 Protocol1PacketHandler::txPacket(), and calls Protocol1PacketHandler::rxPacket() if it succeeds Protocol1PacketHandler::txPacket(). It breaks out when it fails Protocol1PacketHandler::txPacket(), when txpacket is called by Protocol1PacketHandler::broadcastPing() / Protocol1PacketHandler::syncWriteTxOnly() / Protocol1PacketHandler::regWriteTxOnly / Protocol1PacketHandler::action. | |
int | write1ByteTxOnly (PortHandler *port, uint8_t id, uint16_t address, uint8_t data) |
The function that calls Protocol1PacketHandler::writeTxOnly() for writing 1 byte data The function calls Protocol1PacketHandler::writeTxOnly() for writing 1 byte data. | |
int | write1ByteTxRx (PortHandler *port, uint8_t id, uint16_t address, uint8_t data, uint8_t *error=0) |
The function that calls Protocol1PacketHandler::writeTxRx() for writing 1 byte data and receives the packet The function calls Protocol1PacketHandler::writeTxRx() for writing 1 byte data and receves the packet, gets the error from the packet. | |
int | write2ByteTxOnly (PortHandler *port, uint8_t id, uint16_t address, uint16_t data) |
The function that calls Protocol1PacketHandler::writeTxOnly() for writing 2 byte data The function calls Protocol1PacketHandler::writeTxOnly() for writing 2 byte data. | |
int | write2ByteTxRx (PortHandler *port, uint8_t id, uint16_t address, uint16_t data, uint8_t *error=0) |
The function that calls Protocol1PacketHandler::writeTxRx() for writing 2 byte data and receives the packet The function calls Protocol1PacketHandler::writeTxRx() for writing 2 byte data and receves the packet, gets the error from the packet. | |
int | write4ByteTxOnly (PortHandler *port, uint8_t id, uint16_t address, uint32_t data) |
The function that calls Protocol1PacketHandler::writeTxOnly() for writing 4 byte data The function calls Protocol1PacketHandler::writeTxOnly() for writing 4 byte data. | |
int | write4ByteTxRx (PortHandler *port, uint8_t id, uint16_t address, uint32_t data, uint8_t *error=0) |
The function that calls Protocol1PacketHandler::writeTxRx() for writing 4 byte data and receives the packet The function calls Protocol1PacketHandler::writeTxRx() for writing 4 byte data and receves the packet, gets the error from the packet. | |
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 Protocol1PacketHandler::txPacket(). | |
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 Protocol1PacketHandler::txRxPacket(), gets the error from the packet. | |
virtual | ~Protocol1PacketHandler () |
Static Public Member Functions | |
static Protocol1PacketHandler * | getInstance () |
The function that returns Protocol1PacketHandler instance. | |
Private Member Functions | |
Protocol1PacketHandler () | |
Static Private Attributes | |
static Protocol1PacketHandler * | unique_instance_ = new Protocol1PacketHandler() |
The class for control Dynamixel by using Protocol1.0.
Definition at line 34 of file protocol1_packet_handler.h.
Protocol1PacketHandler::Protocol1PacketHandler | ( | ) | [private] |
Definition at line 58 of file protocol1_packet_handler.cpp.
virtual dynamixel::Protocol1PacketHandler::~Protocol1PacketHandler | ( | ) | [inline, virtual] |
Definition at line 48 of file protocol1_packet_handler.h.
int Protocol1PacketHandler::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 Protocol1PacketHandler::txRxPacket(). To use this function, Dynamixel register should be set by Protocol1PacketHandler::regWriteTxOnly() or Protocol1PacketHandler::regWriteTxRx()
port | PortHandler instance |
id | Dynamixel ID |
Implements dynamixel::PacketHandler.
Definition at line 352 of file protocol1_packet_handler.cpp.
int Protocol1PacketHandler::broadcastPing | ( | PortHandler * | port, |
std::vector< uint8_t > & | id_list | ||
) | [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 |
Implements dynamixel::PacketHandler.
Definition at line 347 of file protocol1_packet_handler.cpp.
int Protocol1PacketHandler::bulkReadTx | ( | PortHandler * | port, |
uint8_t * | param, | ||
uint16_t | param_length | ||
) | [virtual] |
(Available only on Dynamixel MX / X series) The function that transmits Bulk Read instruction packet The function makes an instruction packet with INST_BULK_READ, transmits the packet with Protocol1PacketHandler::txPacket().
port | PortHandler instance |
param | Parameter for Bulk Read {LEN1, ID1, ADDR1, LEN2, ID2, ADDR2, ...} |
param_length | Length of the data for Bulk Read |
Implements dynamixel::PacketHandler.
Definition at line 689 of file protocol1_packet_handler.cpp.
int Protocol1PacketHandler::bulkWriteTxOnly | ( | PortHandler * | port, |
uint8_t * | param, | ||
uint16_t | param_length | ||
) | [virtual] |
(Available only in Protocol 2.0) The function that transmits Bulk Write instruction packet
port | PortHandler instance |
param | Parameter for Bulk Write |
param_length | Length of the data for Bulk Write |
Implements dynamixel::PacketHandler.
Definition at line 720 of file protocol1_packet_handler.cpp.
int Protocol1PacketHandler::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 Protocol1PacketHandler::txRxPacket(). Be careful of the use.
port | PortHandler instance |
id | Dynamixel ID |
option | (Not available in Protocol 1.0) Reset option |
error | Dynamixel hardware error |
Implements dynamixel::PacketHandler.
Definition at line 368 of file protocol1_packet_handler.cpp.
static Protocol1PacketHandler* dynamixel::Protocol1PacketHandler::getInstance | ( | ) | [inline, static] |
The function that returns Protocol1PacketHandler instance.
Definition at line 46 of file protocol1_packet_handler.h.
float dynamixel::Protocol1PacketHandler::getProtocolVersion | ( | ) | [inline, virtual] |
The function that returns Protocol version used in Protocol1PacketHandler (1.0)
Implements dynamixel::PacketHandler.
Definition at line 54 of file protocol1_packet_handler.h.
const char * Protocol1PacketHandler::getRxPacketError | ( | uint8_t | error | ) | [virtual] |
The function that gets description of hardware error.
error | Dynamixel hardware error which might be gotten by the tx rx functions |
Implements dynamixel::PacketHandler.
Definition at line 96 of file protocol1_packet_handler.cpp.
const char * Protocol1PacketHandler::getTxRxResult | ( | int | result | ) | [virtual] |
The function that gets description of communication result.
result | Communication result which might be gotten by the tx rx functions |
Implements dynamixel::PacketHandler.
Definition at line 60 of file protocol1_packet_handler.cpp.
int Protocol1PacketHandler::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 Protocol1PacketHandler::ping() which gets Dynamixel model number, but doesn't carry the model number.
port | PortHandler instance |
id | Dynamixel ID |
error | Dynamixel hardware error |
Implements dynamixel::PacketHandler.
Definition at line 317 of file protocol1_packet_handler.cpp.
int Protocol1PacketHandler::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 Protocol1PacketHandler::txRxPacket(), and call Protocol1PacketHandler::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 |
Implements dynamixel::PacketHandler.
Definition at line 322 of file protocol1_packet_handler.cpp.
int Protocol1PacketHandler::read1ByteRx | ( | PortHandler * | port, |
uint8_t | id, | ||
uint8_t * | data, | ||
uint8_t * | error = 0 |
||
) | [virtual] |
The function that calls Protocol1PacketHandler::readRx() function and reads 1 byte data on the packet The function calls Protocol1PacketHandler::readRx() function, gets 1 byte data from the packet.
port | PortHandler instance |
data | Data extracted from the packet |
error | Dynamixel hardware error |
Implements dynamixel::PacketHandler.
Definition at line 471 of file protocol1_packet_handler.cpp.
int Protocol1PacketHandler::read1ByteTx | ( | PortHandler * | port, |
uint8_t | id, | ||
uint16_t | address | ||
) | [virtual] |
The function that calls Protocol1PacketHandler::readTx() function for reading 1 byte data The function calls Protocol1PacketHandler::readTx() function for reading 1 byte data.
port | PortHandler instance |
id | Dynamixel ID |
address | Address of the data for read |
Implements dynamixel::PacketHandler.
Definition at line 467 of file protocol1_packet_handler.cpp.
int Protocol1PacketHandler::read1ByteTxRx | ( | PortHandler * | port, |
uint8_t | id, | ||
uint16_t | address, | ||
uint8_t * | data, | ||
uint8_t * | error = 0 |
||
) | [virtual] |
The function that calls Protocol1PacketHandler::readTxRx() function for reading 1 byte data The function calls Protocol1PacketHandler::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 |
Implements dynamixel::PacketHandler.
Definition at line 479 of file protocol1_packet_handler.cpp.
int Protocol1PacketHandler::read2ByteRx | ( | PortHandler * | port, |
uint8_t | id, | ||
uint16_t * | data, | ||
uint8_t * | error = 0 |
||
) | [virtual] |
The function that calls Protocol1PacketHandler::readRx() function and reads 2 byte data on the packet The function calls Protocol1PacketHandler::readRx() function, gets 2 byte data from the packet.
port | PortHandler instance |
data | Data extracted from the packet |
error | Dynamixel hardware error |
Implements dynamixel::PacketHandler.
Definition at line 492 of file protocol1_packet_handler.cpp.
int Protocol1PacketHandler::read2ByteTx | ( | PortHandler * | port, |
uint8_t | id, | ||
uint16_t | address | ||
) | [virtual] |
The function that calls Protocol1PacketHandler::readTx() function for reading 2 byte data The function calls Protocol1PacketHandler::readTx() function for reading 2 byte data.
port | PortHandler instance |
id | Dynamixel ID |
address | Address of the data for read |
Implements dynamixel::PacketHandler.
Definition at line 488 of file protocol1_packet_handler.cpp.
int Protocol1PacketHandler::read2ByteTxRx | ( | PortHandler * | port, |
uint8_t | id, | ||
uint16_t | address, | ||
uint16_t * | data, | ||
uint8_t * | error = 0 |
||
) | [virtual] |
The function that calls Protocol1PacketHandler::readTxRx() function for reading 2 byte data The function calls Protocol1PacketHandler::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 |
Implements dynamixel::PacketHandler.
Definition at line 500 of file protocol1_packet_handler.cpp.
int Protocol1PacketHandler::read4ByteRx | ( | PortHandler * | port, |
uint8_t | id, | ||
uint32_t * | data, | ||
uint8_t * | error = 0 |
||
) | [virtual] |
The function that calls Protocol1PacketHandler::readRx() function and reads 4 byte data on the packet The function calls Protocol1PacketHandler::readRx() function, gets 4 byte data from the packet.
port | PortHandler instance |
data | Data extracted from the packet |
error | Dynamixel hardware error |
Implements dynamixel::PacketHandler.
Definition at line 513 of file protocol1_packet_handler.cpp.
int Protocol1PacketHandler::read4ByteTx | ( | PortHandler * | port, |
uint8_t | id, | ||
uint16_t | address | ||
) | [virtual] |
The function that calls Protocol1PacketHandler::readTx() function for reading 4 byte data The function calls Protocol1PacketHandler::readTx() function for reading 4 byte data.
port | PortHandler instance |
id | Dynamixel ID |
address | Address of the data for read |
Implements dynamixel::PacketHandler.
Definition at line 509 of file protocol1_packet_handler.cpp.
int Protocol1PacketHandler::read4ByteTxRx | ( | PortHandler * | port, |
uint8_t | id, | ||
uint16_t | address, | ||
uint32_t * | data, | ||
uint8_t * | error = 0 |
||
) | [virtual] |
The function that calls Protocol1PacketHandler::readTxRx() function for reading 4 byte data The function calls Protocol1PacketHandler::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 |
Implements dynamixel::PacketHandler.
Definition at line 521 of file protocol1_packet_handler.cpp.
int Protocol1PacketHandler::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.
port | PortHandler instance |
length | Length of the data for read |
data | Data extracted from the packet |
error | Dynamixel hardware error |
Implements dynamixel::PacketHandler.
Definition at line 404 of file protocol1_packet_handler.cpp.
int Protocol1PacketHandler::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 Protocol1PacketHandler::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 |
Implements dynamixel::PacketHandler.
Definition at line 380 of file protocol1_packet_handler.cpp.
int Protocol1PacketHandler::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 Protocol1PacketHandler::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 |
Implements dynamixel::PacketHandler.
Definition at line 432 of file protocol1_packet_handler.cpp.
int Protocol1PacketHandler::reboot | ( | PortHandler * | port, |
uint8_t | id, | ||
uint8_t * | error = 0 |
||
) | [virtual] |
(Available only in Protocol 2.0) The function that makes Dynamixel reboot
port | PortHandler instance |
id | Dynamixel ID |
error | Dynamixel hardware error |
Implements dynamixel::PacketHandler.
Definition at line 363 of file protocol1_packet_handler.cpp.
int Protocol1PacketHandler::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 Protocol1PacketHandler::txPacket(). The data written in the register will act when INST_ACTION instruction packet is transmitted to the Dynamxel.
port | PortHandler instance |
id | Dynamixel ID |
address | Address of the data for write |
length | Length of the data for write |
data | Data for write |
Implements dynamixel::PacketHandler.
Definition at line 611 of file protocol1_packet_handler.cpp.
int Protocol1PacketHandler::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 Protocol1PacketHandler::txRxPacket(), gets the error from the packet. The data written in the register will act when INST_ACTION instruction packet is transmitted to the Dynamxel.
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 |
Implements dynamixel::PacketHandler.
Definition at line 635 of file protocol1_packet_handler.cpp.
int Protocol1PacketHandler::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.
port | PortHandler instance |
rxpacket | received packet |
Implements dynamixel::PacketHandler.
Definition at line 160 of file protocol1_packet_handler.cpp.
int Protocol1PacketHandler::syncReadTx | ( | PortHandler * | port, |
uint16_t | start_address, | ||
uint16_t | data_length, | ||
uint8_t * | param, | ||
uint16_t | param_length | ||
) | [virtual] |
(Available only in Protocol 2.0) The function that transmits Sync Read instruction packet
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 |
Implements dynamixel::PacketHandler.
Definition at line 659 of file protocol1_packet_handler.cpp.
int Protocol1PacketHandler::syncWriteTxOnly | ( | PortHandler * | port, |
uint16_t | start_address, | ||
uint16_t | data_length, | ||
uint8_t * | param, | ||
uint16_t | param_length | ||
) | [virtual] |
The function that transmits Sync Write instruction packet The function makes an instruction packet with INST_SYNC_WRITE, transmits the packet with Protocol1PacketHandler::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 {ID1, DATA0, DATA1, ..., DATAn, ID2, DATA0, DATA1, ..., DATAn, ID3, DATA0, DATA1, ..., DATAn} |
param_length | Length of the data for Sync Write |
Implements dynamixel::PacketHandler.
Definition at line 664 of file protocol1_packet_handler.cpp.
int Protocol1PacketHandler::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.
port | PortHandler instance |
txpacket | packet for transmission |
Implements dynamixel::PacketHandler.
Definition at line 122 of file protocol1_packet_handler.cpp.
int Protocol1PacketHandler::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 Protocol1PacketHandler::txPacket(), and calls Protocol1PacketHandler::rxPacket() if it succeeds Protocol1PacketHandler::txPacket(). It breaks out when it fails Protocol1PacketHandler::txPacket(), when txpacket is called by Protocol1PacketHandler::broadcastPing() / Protocol1PacketHandler::syncWriteTxOnly() / Protocol1PacketHandler::regWriteTxOnly / Protocol1PacketHandler::action.
port | PortHandler instance |
txpacket | packet for transmission |
rxpacket | received packet |
Implements dynamixel::PacketHandler.
Definition at line 272 of file protocol1_packet_handler.cpp.
int Protocol1PacketHandler::write1ByteTxOnly | ( | PortHandler * | port, |
uint8_t | id, | ||
uint16_t | address, | ||
uint8_t | data | ||
) | [virtual] |
The function that calls Protocol1PacketHandler::writeTxOnly() for writing 1 byte data The function calls Protocol1PacketHandler::writeTxOnly() for writing 1 byte data.
port | PortHandler instance |
id | Dynamixel ID |
address | Address of the data for write |
data | Data for write |
Implements dynamixel::PacketHandler.
Definition at line 578 of file protocol1_packet_handler.cpp.
int Protocol1PacketHandler::write1ByteTxRx | ( | PortHandler * | port, |
uint8_t | id, | ||
uint16_t | address, | ||
uint8_t | data, | ||
uint8_t * | error = 0 |
||
) | [virtual] |
The function that calls Protocol1PacketHandler::writeTxRx() for writing 1 byte data and receives the packet The function calls Protocol1PacketHandler::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 |
Implements dynamixel::PacketHandler.
Definition at line 583 of file protocol1_packet_handler.cpp.
int Protocol1PacketHandler::write2ByteTxOnly | ( | PortHandler * | port, |
uint8_t | id, | ||
uint16_t | address, | ||
uint16_t | data | ||
) | [virtual] |
The function that calls Protocol1PacketHandler::writeTxOnly() for writing 2 byte data The function calls Protocol1PacketHandler::writeTxOnly() for writing 2 byte data.
port | PortHandler instance |
id | Dynamixel ID |
address | Address of the data for write |
data | Data for write |
Implements dynamixel::PacketHandler.
Definition at line 589 of file protocol1_packet_handler.cpp.
int Protocol1PacketHandler::write2ByteTxRx | ( | PortHandler * | port, |
uint8_t | id, | ||
uint16_t | address, | ||
uint16_t | data, | ||
uint8_t * | error = 0 |
||
) | [virtual] |
The function that calls Protocol1PacketHandler::writeTxRx() for writing 2 byte data and receives the packet The function calls Protocol1PacketHandler::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 |
Implements dynamixel::PacketHandler.
Definition at line 594 of file protocol1_packet_handler.cpp.
int Protocol1PacketHandler::write4ByteTxOnly | ( | PortHandler * | port, |
uint8_t | id, | ||
uint16_t | address, | ||
uint32_t | data | ||
) | [virtual] |
The function that calls Protocol1PacketHandler::writeTxOnly() for writing 4 byte data The function calls Protocol1PacketHandler::writeTxOnly() for writing 4 byte data.
port | PortHandler instance |
id | Dynamixel ID |
address | Address of the data for write |
data | Data for write |
Implements dynamixel::PacketHandler.
Definition at line 600 of file protocol1_packet_handler.cpp.
int Protocol1PacketHandler::write4ByteTxRx | ( | PortHandler * | port, |
uint8_t | id, | ||
uint16_t | address, | ||
uint32_t | data, | ||
uint8_t * | error = 0 |
||
) | [virtual] |
The function that calls Protocol1PacketHandler::writeTxRx() for writing 4 byte data and receives the packet The function calls Protocol1PacketHandler::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 |
Implements dynamixel::PacketHandler.
Definition at line 605 of file protocol1_packet_handler.cpp.
int Protocol1PacketHandler::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 Protocol1PacketHandler::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 |
Implements dynamixel::PacketHandler.
Definition at line 530 of file protocol1_packet_handler.cpp.
int Protocol1PacketHandler::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 Protocol1PacketHandler::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 |
Implements dynamixel::PacketHandler.
Definition at line 554 of file protocol1_packet_handler.cpp.
Protocol1PacketHandler * Protocol1PacketHandler::unique_instance_ = new Protocol1PacketHandler() [static, private] |
Definition at line 37 of file protocol1_packet_handler.h.