Public Member Functions | Private Member Functions | Private Attributes | List of all members
dynamixel::GroupSyncRead Class Reference

The class for reading multiple Dynamixel data from same address with same length at once. More...

#include <group_sync_read.h>

Public Member Functions

bool addParam (uint8_t id)
 The function that adds id, start_address, data_length to the Sync Read list. More...
 
void clearParam ()
 The function that clears the Sync 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 GroupSyncRead::rxPacket or GroupSyncRead::txRxPacket. More...
 
bool getError (uint8_t id, uint8_t *error)
 The function that gets the error which might be received by GroupSyncRead::rxPacket or GroupSyncRead::txRxPacket. More...
 
PacketHandlergetPacketHandler ()
 The function that returns PacketHandler instance. More...
 
PortHandlergetPortHandler ()
 The function that returns PortHandler instance. More...
 
 GroupSyncRead (PortHandler *port, PacketHandler *ph, uint16_t start_address, uint16_t data_length)
 The function that Initializes instance for Sync 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 GroupSyncRead::rxPacket or GroupSyncRead::txRxPacket. More...
 
void removeParam (uint8_t id)
 The function that removes id from the Sync 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 Sync Read instruction packet which might be constructed by GroupSyncRead::addParam function. More...
 
int txRxPacket ()
 The function that transmits and receives the packet which might be come from the Dynamixel. More...
 
 ~GroupSyncRead ()
 The function that calls clearParam function to clear the parameter list for Sync Read. More...
 

Private Member Functions

void makeParam ()
 

Private Attributes

uint16_t data_length_
 
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_
 
uint8_t * param_
 
PacketHandlerph_
 
PortHandlerport_
 
uint16_t start_address_
 

Detailed Description

The class for reading multiple Dynamixel data from same address with same length at once.

Definition at line 37 of file group_sync_read.h.

Constructor & Destructor Documentation

GroupSyncRead::GroupSyncRead ( PortHandler port,
PacketHandler ph,
uint16_t  start_address,
uint16_t  data_length 
)

The function that Initializes instance for Sync Read.

Parameters
portPortHandler instance
phPacketHandler instance
start_addressAddress of the data for read
data_lengthLength of the data for read

Definition at line 34 of file group_sync_read.cpp.

dynamixel::GroupSyncRead::~GroupSyncRead ( )
inline

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

Definition at line 69 of file group_sync_read.h.

Member Function Documentation

bool GroupSyncRead::addParam ( uint8_t  id)

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

Parameters
idDynamixel ID
Returns
false
when the ID exists already in the list
when the protocol1.0 has been used
or true

Definition at line 62 of file group_sync_read.cpp.

void GroupSyncRead::clearParam ( )

The function that clears the Sync Read list.

Definition at line 94 of file group_sync_read.cpp.

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

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

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

Definition at line 177 of file group_sync_read.cpp.

bool GroupSyncRead::getError ( uint8_t  id,
uint8_t *  error 
)

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

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

Definition at line 199 of file group_sync_read.cpp.

PacketHandler* dynamixel::GroupSyncRead::getPacketHandler ( )
inline

The function that returns PacketHandler instance.

Returns
PacketHandler instance

Definition at line 81 of file group_sync_read.h.

PortHandler* dynamixel::GroupSyncRead::getPortHandler ( )
inline

The function that returns PortHandler instance.

Returns
PortHandler instance

Definition at line 75 of file group_sync_read.h.

bool GroupSyncRead::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 GroupSyncRead::rxPacket or GroupSyncRead::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
when the protocol1.0 has been used
or true

Definition at line 166 of file group_sync_read.cpp.

void GroupSyncRead::makeParam ( )
private

Definition at line 46 of file group_sync_read.cpp.

void GroupSyncRead::removeParam ( uint8_t  id)

The function that removes id from the Sync Read list.

Parameters
idDynamixel ID

Definition at line 77 of file group_sync_read.cpp.

int GroupSyncRead::rxPacket ( )

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

Returns
COMM_NOT_AVAILABLE
when the list for Sync Read is empty
when the protocol1.0 has been used
COMM_SUCCESS
when there is packet recieved
or the other communication results

Definition at line 124 of file group_sync_read.cpp.

int GroupSyncRead::txPacket ( )

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

Returns
COMM_NOT_AVAILABLE
when the list for Sync Read is empty
when the protocol1.0 has been used
or the other communication results which come from PacketHandler::syncReadTx

Definition at line 113 of file group_sync_read.cpp.

int GroupSyncRead::txRxPacket ( )

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

Returns
COMM_NOT_AVAILABLE
when the protocol1.0 has been used
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 152 of file group_sync_read.cpp.

Member Data Documentation

uint16_t dynamixel::GroupSyncRead::data_length_
private

Definition at line 52 of file group_sync_read.h.

std::map<uint8_t, uint8_t *> dynamixel::GroupSyncRead::data_list_
private

Definition at line 44 of file group_sync_read.h.

std::map<uint8_t, uint8_t *> dynamixel::GroupSyncRead::error_list_
private

Definition at line 45 of file group_sync_read.h.

std::vector<uint8_t> dynamixel::GroupSyncRead::id_list_
private

Definition at line 43 of file group_sync_read.h.

bool dynamixel::GroupSyncRead::is_param_changed_
private

Definition at line 48 of file group_sync_read.h.

bool dynamixel::GroupSyncRead::last_result_
private

Definition at line 47 of file group_sync_read.h.

uint8_t* dynamixel::GroupSyncRead::param_
private

Definition at line 50 of file group_sync_read.h.

PacketHandler* dynamixel::GroupSyncRead::ph_
private

Definition at line 41 of file group_sync_read.h.

PortHandler* dynamixel::GroupSyncRead::port_
private

Definition at line 40 of file group_sync_read.h.

uint16_t dynamixel::GroupSyncRead::start_address_
private

Definition at line 51 of file group_sync_read.h.


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


dynamixel_sdk
Author(s): Gilbert , Zerom , Darby Lim , Leon
autogenerated on Fri Apr 16 2021 02:25:55