Public Member Functions | Private Member Functions | Private Attributes
dynamixel::GroupBulkRead Class Reference

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

#include <group_bulk_read.h>

List of all members.

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.
PacketHandlergetPacketHandler ()
 The function that returns PacketHandler instance.
PortHandlergetPortHandler ()
 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_
PacketHandlerph_
PortHandlerport_

Detailed Description

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.


Constructor & Destructor Documentation

The function that Initializes instance for Bulk Read.

Parameters:
portPortHandler instance
phPacketHandler instance

Definition at line 35 of file group_bulk_read.cpp.

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

Definition at line 67 of file group_bulk_read.h.


Member Function Documentation

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:
idDynamixel ID
start_addressAddress 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.

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.

Parameters:
idDynamixel ID
addressAddress of the data for read Length of the data for read
Returns:
data value

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.

Parameters:
idDynamixel ID error of Dynamixel
Returns:
true
when Dynamixel returned specific error byte
or false

Definition at line 230 of file group_bulk_read.cpp.

The function that returns PacketHandler instance.

Returns:
PacketHandler instance

Definition at line 79 of file group_bulk_read.h.

The function that returns PortHandler instance.

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.

Parameters:
idDynamixel ID
addressAddress of the data for read
data_lengthLength of the data for read
Returns:
false
when there are no data available
or true

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.

Parameters:
idDynamixel ID

Definition at line 99 of file group_bulk_read.cpp.

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.

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

Returns:
COMM_NOT_AVAILABLE
when the list for Bulk Read is empty
or the other communication results which come from PacketHandler::bulkReadTx

Definition at line 137 of file group_bulk_read.cpp.

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.


Member Data Documentation

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.

Definition at line 50 of file group_bulk_read.h.

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.

Definition at line 52 of file group_bulk_read.h.

Definition at line 41 of file group_bulk_read.h.

Definition at line 40 of file group_bulk_read.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