The class for reading multiple Dynamixel data from different addresses with different lengths at once.
More...
#include <group_bulk_read.h>
|
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. More...
|
|
void | clearParam () |
| The function that clears the Bulk Read list. More...
|
|
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. More...
|
|
bool | getError (uint8_t id, uint8_t *error) |
| The function that gets the error which might be received by GroupBulkRead::rxPacket or GroupBulkRead::txRxPacket. More...
|
|
PacketHandler * | getPacketHandler () |
| The function that returns PacketHandler instance. More...
|
|
PortHandler * | getPortHandler () |
| The function that returns PortHandler instance. More...
|
|
| GroupBulkRead (PortHandler *port, PacketHandler *ph) |
| The function that Initializes instance for Bulk Read. More...
|
|
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. More...
|
|
void | removeParam (uint8_t id) |
| The function that removes id from the Bulk Read list. More...
|
|
int | rxPacket () |
| The function that receives the packet which might be come from the Dynamixel. More...
|
|
int | txPacket () |
| The function that transmits the Bulk Read instruction packet which might be constructed by GroupBulkRead::addParam function. More...
|
|
int | txRxPacket () |
| The function that transmits and receives the packet which might be come from the Dynamixel. More...
|
|
| ~GroupBulkRead () |
| The function that calls clearParam function to clear the parameter list for Bulk Read. More...
|
|
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.
The function that Initializes instance for Bulk Read.
- Parameters
-
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.
- Parameters
-
id | Dynamixel ID |
start_address | Address of the data for read Length of the data for read |
- Returns
- false
-
when the ID exists already in the list
-
or true
Definition at line 84 of file group_bulk_read.cpp.
void GroupBulkRead::clearParam |
( |
| ) |
|
uint32_t GroupBulkRead::getData |
( |
uint8_t |
id, |
|
|
uint16_t |
address, |
|
|
uint16_t |
data_length |
|
) |
| |
bool GroupBulkRead::getError |
( |
uint8_t |
id, |
|
|
uint8_t * |
error |
|
) |
| |
PortHandler* dynamixel::GroupBulkRead::getPortHandler |
( |
| ) |
|
|
inline |
bool GroupBulkRead::isAvailable |
( |
uint8_t |
id, |
|
|
uint16_t |
address, |
|
|
uint16_t |
data_length |
|
) |
| |
void GroupBulkRead::makeParam |
( |
| ) |
|
|
private |
void GroupBulkRead::removeParam |
( |
uint8_t |
id | ) |
|
The function that removes id from the Bulk Read list.
- Parameters
-
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.
- Returns
- COMM_NOT_AVAILABLE
-
when the list for Bulk Read is empty
-
COMM_RX_FAIL
-
when there is no packet recieved
-
COMM_SUCCESS
-
when there is packet recieved
-
or the other communication results
Definition at line 155 of file group_bulk_read.cpp.
int GroupBulkRead::txPacket |
( |
| ) |
|
int GroupBulkRead::txRxPacket |
( |
| ) |
|
The function that transmits and receives the packet which might be come from the Dynamixel.
- Returns
- COMM_RX_FAIL
-
when there is no packet recieved
-
COMM_SUCCESS
-
when there is packet recieved
-
or the other communication results which come from GroupBulkRead::txPacket or GroupBulkRead::rxPacket
Definition at line 180 of file group_bulk_read.cpp.
std::map<uint8_t, uint16_t> dynamixel::GroupBulkRead::address_list_ |
|
private |
std::map<uint8_t, uint8_t *> dynamixel::GroupBulkRead::data_list_ |
|
private |
std::map<uint8_t, uint8_t *> dynamixel::GroupBulkRead::error_list_ |
|
private |
std::vector<uint8_t> dynamixel::GroupBulkRead::id_list_ |
|
private |
bool dynamixel::GroupBulkRead::is_param_changed_ |
|
private |
bool dynamixel::GroupBulkRead::last_result_ |
|
private |
std::map<uint8_t, uint16_t> dynamixel::GroupBulkRead::length_list_ |
|
private |
uint8_t* dynamixel::GroupBulkRead::param_ |
|
private |
The documentation for this class was generated from the following files: