MercurySDK
Software development kit for Mercury digital servos
Public Member Functions | Protected Member Functions | Protected Attributes | List of all members
mercury::GroupSyncRead Class Reference

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

#include <group_sync_read.h>

Inheritance diagram for mercury::GroupSyncRead:
mercury::GroupHandler

Public Member Functions

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

Protected Member Functions

void makeParam ()
 

Protected Attributes

std::map< uint8_t, uint8_t * > error_list_
 
bool last_result_
 
uint16_t start_address_
 
uint16_t data_length_
 
- Protected Attributes inherited from mercury::GroupHandler
PortHandlerport_
 
PacketHandlerph_
 
std::vector< uint8_t > id_list_
 
std::map< uint8_t, uint8_t * > data_list_
 
bool is_param_changed_
 
uint8_t * param_
 

Detailed Description

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

Definition at line 36 of file group_sync_read.h.

Constructor & Destructor Documentation

◆ GroupSyncRead()

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.

◆ ~GroupSyncRead()

mercury::GroupSyncRead::~GroupSyncRead ( )
inline

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

Definition at line 61 of file group_sync_read.h.

Member Function Documentation

◆ addParam()

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 59 of file group_sync_read.cpp.

◆ clearParam()

void GroupSyncRead::clearParam ( )

The function that clears the Sync Read list.

Definition at line 91 of file group_sync_read.cpp.

◆ getData()

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 @data_length Length of the data for read
Returns
data value

Definition at line 174 of file group_sync_read.cpp.

◆ getError()

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 error of Dynamixel
Returns
true
when Dynamixel returned specific error byte
or false

Definition at line 196 of file group_sync_read.cpp.

◆ isAvailable()

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 163 of file group_sync_read.cpp.

◆ makeParam()

void GroupSyncRead::makeParam ( )
protected

Definition at line 43 of file group_sync_read.cpp.

◆ removeParam()

void GroupSyncRead::removeParam ( uint8_t  id)

The function that removes id from the Sync Read list.

Parameters
idDynamixel ID

Definition at line 74 of file group_sync_read.cpp.

◆ rxPacket()

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 121 of file group_sync_read.cpp.

◆ txPacket()

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 110 of file group_sync_read.cpp.

◆ txRxPacket()

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 149 of file group_sync_read.cpp.

Member Data Documentation

◆ data_length_

uint16_t mercury::GroupSyncRead::data_length_
protected

Definition at line 44 of file group_sync_read.h.

◆ error_list_

std::map<uint8_t, uint8_t *> mercury::GroupSyncRead::error_list_
protected

Definition at line 39 of file group_sync_read.h.

◆ last_result_

bool mercury::GroupSyncRead::last_result_
protected

Definition at line 41 of file group_sync_read.h.

◆ start_address_

uint16_t mercury::GroupSyncRead::start_address_
protected

Definition at line 43 of file group_sync_read.h.


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