Class GroupBulkRead

Class Documentation

class dynamixel::GroupBulkRead

The class for reading multiple Dynamixel data from different addresses with different lengths at once.

Public Functions

GroupBulkRead(PortHandler *port, PacketHandler *ph)

The function that Initializes instance for Bulk Read.

Parameters
inline ~GroupBulkRead()

The function that calls clearParam function to clear the parameter list for Bulk Read.

inline PortHandler *getPortHandler()

The function that returns PortHandler instance.

Returns

PortHandler instance

inline PacketHandler *getPacketHandler()

The function that returns PacketHandler instance.

Returns

PacketHandler instance

bool addParam(uint8_t id, uint16_t start_address, uint16_t data_length)

The function that adds id, start_address, data_length to the Bulk Read list.

Parameters
  • id – Dynamixel ID

  • start_address – Address of the data for read @data_length Length of the data for read

Returns

false

Returns

when the ID exists already in the list

Returns

or true

void removeParam(uint8_t id)

The function that removes id from the Bulk Read list.

Parameters

id – Dynamixel ID

void clearParam()

The function that clears the Bulk Read list.

int txPacket()

The function that transmits the Bulk Read instruction packet which might be constructed by GroupBulkRead::addParam function.

Returns

COMM_NOT_AVAILABLE

Returns

when the list for Bulk Read is empty

Returns

or the other communication results which come from PacketHandler::bulkReadTx

int rxPacket()

The function that receives the packet which might be come from the Dynamixel.

Returns

COMM_NOT_AVAILABLE

Returns

when the list for Bulk Read is empty

Returns

COMM_RX_FAIL

Returns

when there is no packet recieved

Returns

COMM_SUCCESS

Returns

when there is packet recieved

Returns

or the other communication results

int txRxPacket()

The function that transmits and receives the packet which might be come from the Dynamixel.

Returns

COMM_RX_FAIL

Returns

when there is no packet recieved

Returns

COMM_SUCCESS

Returns

when there is packet recieved

Returns

or the other communication results which come from GroupBulkRead::txPacket or GroupBulkRead::rxPacket

bool isAvailable(uint8_t id, uint16_t address, uint16_t data_length)

The function that checks whether there are available data which might be received by GroupBulkRead::rxPacket or GroupBulkRead::txRxPacket.

Parameters
  • id – Dynamixel ID

  • address – Address of the data for read

  • data_length – Length of the data for read

Returns

false

Returns

when there are no data available

Returns

or true

uint32_t getData(uint8_t id, uint16_t address, uint16_t data_length)

The function that gets the data which might be received by GroupBulkRead::rxPacket or GroupBulkRead::txRxPacket.

Parameters
  • id – Dynamixel ID

  • address – Address of the data for read @data_length Length of the data for read

Returns

data value

bool getError(uint8_t id, uint8_t *error)

The function that gets the error which might be received by GroupBulkRead::rxPacket or GroupBulkRead::txRxPacket.

Parameters

id – Dynamixel ID @error error of Dynamixel

Returns

true

Returns

when Dynamixel returned specific error byte

Returns

or false