Public Member Functions | Static Public Member Functions | Private Member Functions | Static Private Attributes
dynamixel::Protocol1PacketHandler Class Reference

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

#include <protocol1_packet_handler.h>

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

List of all members.

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 Protocol1PacketHandlergetInstance ()
 The function that returns Protocol1PacketHandler instance.

Private Member Functions

 Protocol1PacketHandler ()

Static Private Attributes

static Protocol1PacketHandlerunique_instance_ = new Protocol1PacketHandler()

Detailed Description

The class for control Dynamixel by using Protocol1.0.

Definition at line 34 of file protocol1_packet_handler.h.


Constructor & Destructor Documentation

Definition at line 58 of file protocol1_packet_handler.cpp.

Definition at line 48 of file protocol1_packet_handler.h.


Member Function Documentation

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()

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

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

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

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().

Parameters:
portPortHandler instance
paramParameter for Bulk Read {LEN1, ID1, ADDR1, LEN2, ID2, ADDR2, ...}
param_lengthLength of the data for Bulk Read
Returns:
communication results which come from Protocol1PacketHandler::txPacket()

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

Parameters:
portPortHandler instance
paramParameter for Bulk Write
param_lengthLength of the data for Bulk Write
Returns:
COMM_NOT_AVAILABLE

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.

Parameters:
portPortHandler instance
idDynamixel ID
option(Not available in Protocol 1.0) Reset option
errorDynamixel hardware error
Returns:
communication results which come from Protocol1PacketHandler::txRxPacket()

Implements dynamixel::PacketHandler.

Definition at line 368 of file protocol1_packet_handler.cpp.

The function that returns Protocol1PacketHandler instance.

Returns:
Protocol1PacketHandler instance

Definition at line 46 of file protocol1_packet_handler.h.

The function that returns Protocol version used in Protocol1PacketHandler (1.0)

Returns:
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.

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 96 of file protocol1_packet_handler.cpp.

const char * Protocol1PacketHandler::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 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.

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

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.

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 Protocol1PacketHandler::txRxPacket() and Protocol1PacketHandler::readTxRx()

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.

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

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.

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

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.

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 Protocol1PacketHandler::txRxPacket()

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.

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

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.

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

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.

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 Protocol1PacketHandler::txRxPacket()

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.

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

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.

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

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.

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 Protocol1PacketHandler::txRxPacket()

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.

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

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.

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 Protocol1PacketHandler::txPacket()

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.

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 Protocol1PacketHandler::txRxPacket()

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

Parameters:
portPortHandler instance
idDynamixel ID
errorDynamixel hardware error
Returns:
COMM_NOT_AVAILABLE

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.

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 Protocol1PacketHandler::txPacket()

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.

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 Protocol1PacketHandler::txRxPacket()

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.

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 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

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:
COMM_NOT_AVAILABLE

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().

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 Protocol1PacketHandler::txRxPacket()

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.

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 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.

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

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.

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

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.

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

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.

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

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.

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

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.

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

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.

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

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().

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 Protocol1PacketHandler::txPacket()

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.

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 Protocol1PacketHandler::txRxPacket()

Implements dynamixel::PacketHandler.

Definition at line 554 of file protocol1_packet_handler.cpp.


Member Data Documentation

Definition at line 37 of file protocol1_packet_handler.h.


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


ros
Author(s): Pyo , Zerom , Leon
autogenerated on Sat Jun 8 2019 18:32:12