The class for reading multiple Dynamixel data from different addresses with different lengths at once. More...
#include <group_bulk_read.h>
Public Member Functions | |
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. | |
void | clearParam () |
The function that clears the Bulk Read list. | |
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. | |
bool | getError (uint8_t id, uint8_t *error) |
The function that gets the error which might be received by GroupBulkRead::rxPacket or GroupBulkRead::txRxPacket. | |
PacketHandler * | getPacketHandler () |
The function that returns PacketHandler instance. | |
PortHandler * | getPortHandler () |
The function that returns PortHandler instance. | |
GroupBulkRead (PortHandler *port, PacketHandler *ph) | |
The function that Initializes instance for Bulk Read. | |
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. | |
void | removeParam (uint8_t id) |
The function that removes id from the Bulk Read list. | |
int | rxPacket () |
The function that receives the packet which might be come from the Dynamixel. | |
int | txPacket () |
The function that transmits the Bulk Read instruction packet which might be constructed by GroupBulkRead::addParam function. | |
int | txRxPacket () |
The function that transmits and receives the packet which might be come from the Dynamixel. | |
~GroupBulkRead () | |
The function that calls clearParam function to clear the parameter list for Bulk Read. | |
Private Member Functions | |
void | makeParam () |
Private Attributes | |
std::map< uint8_t, uint16_t > | address_list_ |
std::map< uint8_t, uint8_t * > | data_list_ |
std::map< uint8_t, uint8_t * > | error_list_ |
std::vector< uint8_t > | id_list_ |
bool | is_param_changed_ |
bool | last_result_ |
std::map< uint8_t, uint16_t > | length_list_ |
uint8_t * | param_ |
PacketHandler * | ph_ |
PortHandler * | port_ |
The class for reading multiple Dynamixel data from different addresses with different lengths at once.
Definition at line 37 of file group_bulk_read.h.
GroupBulkRead::GroupBulkRead | ( | PortHandler * | port, |
PacketHandler * | ph | ||
) |
The function that Initializes instance for Bulk Read.
port | PortHandler instance |
ph | PacketHandler instance |
Definition at line 35 of file group_bulk_read.cpp.
dynamixel::GroupBulkRead::~GroupBulkRead | ( | ) | [inline] |
The function that calls clearParam function to clear the parameter list for Bulk Read.
Definition at line 67 of file group_bulk_read.h.
bool GroupBulkRead::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.
id | Dynamixel ID |
start_address | Address of the data for read Length of the data for read |
Definition at line 84 of file group_bulk_read.cpp.
void GroupBulkRead::clearParam | ( | ) |
The function that clears the Bulk Read list.
Definition at line 116 of file group_bulk_read.cpp.
uint32_t GroupBulkRead::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.
id | Dynamixel ID |
address | Address of the data for read Length of the data for read |
Definition at line 206 of file group_bulk_read.cpp.
bool GroupBulkRead::getError | ( | uint8_t | id, |
uint8_t * | error | ||
) |
The function that gets the error which might be received by GroupBulkRead::rxPacket or GroupBulkRead::txRxPacket.
id | Dynamixel ID error of Dynamixel |
Definition at line 230 of file group_bulk_read.cpp.
PacketHandler* dynamixel::GroupBulkRead::getPacketHandler | ( | ) | [inline] |
The function that returns PacketHandler instance.
Definition at line 79 of file group_bulk_read.h.
PortHandler* dynamixel::GroupBulkRead::getPortHandler | ( | ) | [inline] |
The function that returns PortHandler instance.
Definition at line 73 of file group_bulk_read.h.
bool GroupBulkRead::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.
id | Dynamixel ID |
address | Address of the data for read |
data_length | Length of the data for read |
Definition at line 191 of file group_bulk_read.cpp.
void GroupBulkRead::makeParam | ( | ) | [private] |
Definition at line 45 of file group_bulk_read.cpp.
void GroupBulkRead::removeParam | ( | uint8_t | id | ) |
The function that removes id from the Bulk Read list.
id | Dynamixel ID |
Definition at line 99 of file group_bulk_read.cpp.
int GroupBulkRead::rxPacket | ( | ) |
The function that receives the packet which might be come from the Dynamixel.
Definition at line 155 of file group_bulk_read.cpp.
int GroupBulkRead::txPacket | ( | ) |
The function that transmits the Bulk Read instruction packet which might be constructed by GroupBulkRead::addParam function.
Definition at line 137 of file group_bulk_read.cpp.
int GroupBulkRead::txRxPacket | ( | ) |
The function that transmits and receives the packet which might be come from the Dynamixel.
Definition at line 180 of file group_bulk_read.cpp.
std::map<uint8_t, uint16_t> dynamixel::GroupBulkRead::address_list_ [private] |
Definition at line 44 of file group_bulk_read.h.
std::map<uint8_t, uint8_t *> dynamixel::GroupBulkRead::data_list_ [private] |
Definition at line 46 of file group_bulk_read.h.
std::map<uint8_t, uint8_t *> dynamixel::GroupBulkRead::error_list_ [private] |
Definition at line 47 of file group_bulk_read.h.
std::vector<uint8_t> dynamixel::GroupBulkRead::id_list_ [private] |
Definition at line 43 of file group_bulk_read.h.
bool dynamixel::GroupBulkRead::is_param_changed_ [private] |
Definition at line 50 of file group_bulk_read.h.
bool dynamixel::GroupBulkRead::last_result_ [private] |
Definition at line 49 of file group_bulk_read.h.
std::map<uint8_t, uint16_t> dynamixel::GroupBulkRead::length_list_ [private] |
Definition at line 45 of file group_bulk_read.h.
uint8_t* dynamixel::GroupBulkRead::param_ [private] |
Definition at line 52 of file group_bulk_read.h.
PacketHandler* dynamixel::GroupBulkRead::ph_ [private] |
Definition at line 41 of file group_bulk_read.h.
PortHandler* dynamixel::GroupBulkRead::port_ [private] |
Definition at line 40 of file group_bulk_read.h.