Public Member Functions | Private Member Functions | Private Attributes | List of all members
DynamixelDriver Class Reference

#include <dynamixel_driver.h>

Inheritance diagram for DynamixelDriver:
Inheritance graph
[legend]

Public Member Functions

bool addBulkReadParam (uint8_t id, uint16_t address, uint16_t length, const char **log=NULL)
 
bool addBulkReadParam (uint8_t id, const char *item_name, const char **log=NULL)
 
bool addBulkWriteParam (uint8_t id, uint16_t address, uint16_t length, int32_t data, const char **log=NULL)
 
bool addBulkWriteParam (uint8_t id, const char *item_name, int32_t data, const char **log=NULL)
 
bool addSyncReadHandler (uint16_t address, uint16_t length, const char **log=NULL)
 
bool addSyncReadHandler (uint8_t id, const char *item_name, const char **log=NULL)
 
bool addSyncWriteHandler (uint16_t address, uint16_t length, const char **log=NULL)
 
bool addSyncWriteHandler (uint8_t id, const char *item_name, const char **log=NULL)
 
bool begin (const char *device_name="/dev/ttyUSB0", uint32_t baud_rate=57600, const char **log=NULL)
 
bool bulkRead (const char **log=NULL)
 
bool bulkWrite (const char **log=NULL)
 
bool clearBulkReadParam (void)
 
bool clearMultiTurn (uint8_t id, const char **log=NULL)
 
 DynamixelDriver ()
 
uint32_t getBaudrate (void)
 
bool getBulkReadData (int32_t *data, const char **log=NULL)
 
bool getBulkReadData (uint8_t *id, uint8_t id_num, uint16_t *address, uint16_t *length, int32_t *data, const char **log=NULL)
 
const ControlItemgetControlTable (uint8_t id, const char **log=NULL)
 
const ControlItemgetItemInfo (uint8_t id, const char *item_name, const char **log=NULL)
 
const ModelInfogetModelInfo (uint8_t id, const char **log=NULL)
 
const char * getModelName (uint8_t id, const char **log=NULL)
 
uint16_t getModelNumber (uint8_t id, const char **log=NULL)
 
void getParam (int32_t data, uint8_t *param)
 
float getProtocolVersion (void)
 
bool getSyncReadData (uint8_t index, int32_t *data, const char **log=NULL)
 
bool getSyncReadData (uint8_t index, uint8_t *id, uint8_t id_num, int32_t *data, const char **log=NULL)
 
bool getSyncReadData (uint8_t index, uint8_t *id, uint8_t id_num, uint16_t address, uint16_t length, int32_t *data, const char **log=NULL)
 
uint8_t getTheNumberOfBulkReadParam (void)
 
uint8_t getTheNumberOfControlItem (uint8_t id, const char **log=NULL)
 
uint8_t getTheNumberOfSyncReadHandler (void)
 
uint8_t getTheNumberOfSyncWriteHandler (void)
 
bool init (const char *device_name="/dev/ttyUSB0", uint32_t baud_rate=57600, const char **log=NULL)
 
bool initBulkRead (const char **log=NULL)
 
bool initBulkWrite (const char **log=NULL)
 
bool ping (uint8_t id, uint16_t *get_model_number, const char **log=NULL)
 
bool ping (uint8_t id, const char **log=NULL)
 
bool readRegister (uint8_t id, uint16_t address, uint16_t length, uint32_t *data, const char **log=NULL)
 
bool readRegister (uint8_t id, const char *item_name, int32_t *data, const char **log=NULL)
 
bool reboot (uint8_t id, const char **log=NULL)
 
bool reset (uint8_t id, const char **log=NULL)
 
bool scan (uint8_t *get_id, uint8_t *get_the_number_of_id, uint8_t range=253, const char **log=NULL)
 
bool scan (uint8_t *get_id, uint8_t *get_the_number_of_id, uint8_t start_number, uint8_t end_number, const char **log=NULL)
 
bool setBaudrate (uint32_t baud_rate, const char **log=NULL)
 
bool setPacketHandler (float protocol_version, const char **log=NULL)
 
bool setPortHandler (const char *device_name, const char **log=NULL)
 
bool syncRead (uint8_t index, const char **log=NULL)
 
bool syncRead (uint8_t index, uint8_t *id, uint8_t id_num, const char **log=NULL)
 
bool syncWrite (uint8_t index, int32_t *data, const char **log=NULL)
 
bool syncWrite (uint8_t index, uint8_t *id, uint8_t id_num, int32_t *data, uint8_t data_num_for_each_id, const char **log=NULL)
 
bool writeOnlyRegister (uint8_t id, uint16_t address, uint16_t length, uint8_t *data, const char **log=NULL)
 
bool writeOnlyRegister (uint8_t id, const char *item_name, int32_t data, const char **log=NULL)
 
bool writeRegister (uint8_t id, uint16_t address, uint16_t length, uint8_t *data, const char **log=NULL)
 
bool writeRegister (uint8_t id, const char *item_name, int32_t data, const char **log=NULL)
 
 ~DynamixelDriver ()
 

Private Member Functions

uint8_t getTool (uint8_t id, const char **log=NULL)
 
void initTools (void)
 
bool setTool (uint16_t model_number, uint8_t id, const char **log=NULL)
 

Private Attributes

BulkParameter bulk_read_param_ [MAX_BULK_PARAMETER]
 
uint8_t bulk_read_parameter_cnt_
 
dynamixel::GroupBulkReadgroupBulkRead_
 
dynamixel::GroupBulkWritegroupBulkWrite_
 
dynamixel::PacketHandlerpacketHandler_
 
dynamixel::PortHandlerportHandler_
 
uint8_t sync_read_handler_cnt_
 
uint8_t sync_write_handler_cnt_
 
SyncReadHandler syncReadHandler_ [MAX_HANDLER_NUM]
 
SyncWriteHandler syncWriteHandler_ [MAX_HANDLER_NUM]
 
DynamixelTool tools_ [MAX_DXL_SERIES_NUM]
 
uint8_t tools_cnt_
 

Detailed Description

Definition at line 63 of file dynamixel_driver.h.

Constructor & Destructor Documentation

DynamixelDriver::DynamixelDriver ( )

Definition at line 21 of file dynamixel_driver.cpp.

DynamixelDriver::~DynamixelDriver ( )

Definition at line 29 of file dynamixel_driver.cpp.

Member Function Documentation

bool DynamixelDriver::addBulkReadParam ( uint8_t  id,
uint16_t  address,
uint16_t  length,
const char **  log = NULL 
)

Definition at line 1343 of file dynamixel_driver.cpp.

bool DynamixelDriver::addBulkReadParam ( uint8_t  id,
const char *  item_name,
const char **  log = NULL 
)

Definition at line 1373 of file dynamixel_driver.cpp.

bool DynamixelDriver::addBulkWriteParam ( uint8_t  id,
uint16_t  address,
uint16_t  length,
int32_t  data,
const char **  log = NULL 
)

Definition at line 1254 of file dynamixel_driver.cpp.

bool DynamixelDriver::addBulkWriteParam ( uint8_t  id,
const char *  item_name,
int32_t  data,
const char **  log = NULL 
)

Definition at line 1275 of file dynamixel_driver.cpp.

bool DynamixelDriver::addSyncReadHandler ( uint16_t  address,
uint16_t  length,
const char **  log = NULL 
)

Definition at line 1047 of file dynamixel_driver.cpp.

bool DynamixelDriver::addSyncReadHandler ( uint8_t  id,
const char *  item_name,
const char **  log = NULL 
)

Definition at line 1068 of file dynamixel_driver.cpp.

bool DynamixelDriver::addSyncWriteHandler ( uint16_t  address,
uint16_t  length,
const char **  log = NULL 
)

Definition at line 921 of file dynamixel_driver.cpp.

bool DynamixelDriver::addSyncWriteHandler ( uint8_t  id,
const char *  item_name,
const char **  log = NULL 
)

Definition at line 942 of file dynamixel_driver.cpp.

bool DynamixelDriver::begin ( const char *  device_name = "/dev/ttyUSB0",
uint32_t  baud_rate = 57600,
const char **  log = NULL 
)

Definition at line 122 of file dynamixel_driver.cpp.

bool DynamixelDriver::bulkRead ( const char **  log = NULL)

Definition at line 1411 of file dynamixel_driver.cpp.

bool DynamixelDriver::bulkWrite ( const char **  log = NULL)

Definition at line 1304 of file dynamixel_driver.cpp.

bool DynamixelDriver::clearBulkReadParam ( void  )

Definition at line 1478 of file dynamixel_driver.cpp.

bool DynamixelDriver::clearMultiTurn ( uint8_t  id,
const char **  log = NULL 
)

Definition at line 387 of file dynamixel_driver.cpp.

uint32_t DynamixelDriver::getBaudrate ( void  )

Definition at line 172 of file dynamixel_driver.cpp.

bool DynamixelDriver::getBulkReadData ( int32_t *  data,
const char **  log = NULL 
)

Definition at line 1426 of file dynamixel_driver.cpp.

bool DynamixelDriver::getBulkReadData ( uint8_t *  id,
uint8_t  id_num,
uint16_t *  address,
uint16_t *  length,
int32_t *  data,
const char **  log = NULL 
)

Definition at line 1452 of file dynamixel_driver.cpp.

const ControlItem * DynamixelDriver::getControlTable ( uint8_t  id,
const char **  log = NULL 
)

Definition at line 202 of file dynamixel_driver.cpp.

const ControlItem * DynamixelDriver::getItemInfo ( uint8_t  id,
const char *  item_name,
const char **  log = NULL 
)

Definition at line 210 of file dynamixel_driver.cpp.

const ModelInfo * DynamixelDriver::getModelInfo ( uint8_t  id,
const char **  log = NULL 
)

Definition at line 232 of file dynamixel_driver.cpp.

const char * DynamixelDriver::getModelName ( uint8_t  id,
const char **  log = NULL 
)

Definition at line 177 of file dynamixel_driver.cpp.

uint16_t DynamixelDriver::getModelNumber ( uint8_t  id,
const char **  log = NULL 
)

Definition at line 188 of file dynamixel_driver.cpp.

void DynamixelDriver::getParam ( int32_t  data,
uint8_t *  param 
)

Definition at line 913 of file dynamixel_driver.cpp.

float DynamixelDriver::getProtocolVersion ( void  )

Definition at line 167 of file dynamixel_driver.cpp.

bool DynamixelDriver::getSyncReadData ( uint8_t  index,
int32_t *  data,
const char **  log = NULL 
)

Definition at line 1152 of file dynamixel_driver.cpp.

bool DynamixelDriver::getSyncReadData ( uint8_t  index,
uint8_t *  id,
uint8_t  id_num,
int32_t *  data,
const char **  log = NULL 
)

Definition at line 1181 of file dynamixel_driver.cpp.

bool DynamixelDriver::getSyncReadData ( uint8_t  index,
uint8_t *  id,
uint8_t  id_num,
uint16_t  address,
uint16_t  length,
int32_t *  data,
const char **  log = NULL 
)

Definition at line 1207 of file dynamixel_driver.cpp.

uint8_t DynamixelDriver::getTheNumberOfBulkReadParam ( void  )

Definition at line 250 of file dynamixel_driver.cpp.

uint8_t DynamixelDriver::getTheNumberOfControlItem ( uint8_t  id,
const char **  log = NULL 
)

Definition at line 224 of file dynamixel_driver.cpp.

uint8_t DynamixelDriver::getTheNumberOfSyncReadHandler ( void  )

Definition at line 245 of file dynamixel_driver.cpp.

uint8_t DynamixelDriver::getTheNumberOfSyncWriteHandler ( void  )

Definition at line 240 of file dynamixel_driver.cpp.

uint8_t DynamixelDriver::getTool ( uint8_t  id,
const char **  log = NULL 
)
private

Definition at line 89 of file dynamixel_driver.cpp.

bool DynamixelDriver::init ( const char *  device_name = "/dev/ttyUSB0",
uint32_t  baud_rate = 57600,
const char **  log = NULL 
)

Definition at line 106 of file dynamixel_driver.cpp.

bool DynamixelDriver::initBulkRead ( const char **  log = NULL)

Definition at line 1321 of file dynamixel_driver.cpp.

bool DynamixelDriver::initBulkWrite ( const char **  log = NULL)

Definition at line 1233 of file dynamixel_driver.cpp.

void DynamixelDriver::initTools ( void  )
private

Definition at line 42 of file dynamixel_driver.cpp.

bool DynamixelDriver::ping ( uint8_t  id,
uint16_t *  get_model_number,
const char **  log = NULL 
)

Definition at line 334 of file dynamixel_driver.cpp.

bool DynamixelDriver::ping ( uint8_t  id,
const char **  log = NULL 
)

Definition at line 382 of file dynamixel_driver.cpp.

bool DynamixelDriver::readRegister ( uint8_t  id,
uint16_t  address,
uint16_t  length,
uint32_t *  data,
const char **  log = NULL 
)

Definition at line 772 of file dynamixel_driver.cpp.

bool DynamixelDriver::readRegister ( uint8_t  id,
const char *  item_name,
int32_t *  data,
const char **  log = NULL 
)

Definition at line 824 of file dynamixel_driver.cpp.

bool DynamixelDriver::reboot ( uint8_t  id,
const char **  log = NULL 
)

Definition at line 411 of file dynamixel_driver.cpp.

bool DynamixelDriver::reset ( uint8_t  id,
const char **  log = NULL 
)

Definition at line 449 of file dynamixel_driver.cpp.

bool DynamixelDriver::scan ( uint8_t *  get_id,
uint8_t *  get_the_number_of_id,
uint8_t  range = 253,
const char **  log = NULL 
)

Definition at line 329 of file dynamixel_driver.cpp.

bool DynamixelDriver::scan ( uint8_t *  get_id,
uint8_t *  get_the_number_of_id,
uint8_t  start_number,
uint8_t  end_number,
const char **  log = NULL 
)

Definition at line 255 of file dynamixel_driver.cpp.

bool DynamixelDriver::setBaudrate ( uint32_t  baud_rate,
const char **  log = NULL 
)

Definition at line 141 of file dynamixel_driver.cpp.

bool DynamixelDriver::setPacketHandler ( float  protocol_version,
const char **  log = NULL 
)

Definition at line 153 of file dynamixel_driver.cpp.

bool DynamixelDriver::setPortHandler ( const char *  device_name,
const char **  log = NULL 
)

Definition at line 127 of file dynamixel_driver.cpp.

bool DynamixelDriver::setTool ( uint16_t  model_number,
uint8_t  id,
const char **  log = NULL 
)
private

Definition at line 50 of file dynamixel_driver.cpp.

bool DynamixelDriver::syncRead ( uint8_t  index,
const char **  log = NULL 
)

Definition at line 1097 of file dynamixel_driver.cpp.

bool DynamixelDriver::syncRead ( uint8_t  index,
uint8_t *  id,
uint8_t  id_num,
const char **  log = NULL 
)

Definition at line 1126 of file dynamixel_driver.cpp.

bool DynamixelDriver::syncWrite ( uint8_t  index,
int32_t *  data,
const char **  log = NULL 
)

Definition at line 971 of file dynamixel_driver.cpp.

bool DynamixelDriver::syncWrite ( uint8_t  index,
uint8_t *  id,
uint8_t  id_num,
int32_t *  data,
uint8_t  data_num_for_each_id,
const char **  log = NULL 
)

Definition at line 1007 of file dynamixel_driver.cpp.

bool DynamixelDriver::writeOnlyRegister ( uint8_t  id,
uint16_t  address,
uint16_t  length,
uint8_t *  data,
const char **  log = NULL 
)

Definition at line 680 of file dynamixel_driver.cpp.

bool DynamixelDriver::writeOnlyRegister ( uint8_t  id,
const char *  item_name,
int32_t  data,
const char **  log = NULL 
)

Definition at line 709 of file dynamixel_driver.cpp.

bool DynamixelDriver::writeRegister ( uint8_t  id,
uint16_t  address,
uint16_t  length,
uint8_t *  data,
const char **  log = NULL 
)

Definition at line 569 of file dynamixel_driver.cpp.

bool DynamixelDriver::writeRegister ( uint8_t  id,
const char *  item_name,
int32_t  data,
const char **  log = NULL 
)

Definition at line 604 of file dynamixel_driver.cpp.

Member Data Documentation

BulkParameter DynamixelDriver::bulk_read_param_[MAX_BULK_PARAMETER]
private

Definition at line 74 of file dynamixel_driver.h.

uint8_t DynamixelDriver::bulk_read_parameter_cnt_
private

Definition at line 81 of file dynamixel_driver.h.

dynamixel::GroupBulkRead* DynamixelDriver::groupBulkRead_
private

Definition at line 72 of file dynamixel_driver.h.

dynamixel::GroupBulkWrite* DynamixelDriver::groupBulkWrite_
private

Definition at line 73 of file dynamixel_driver.h.

dynamixel::PacketHandler* DynamixelDriver::packetHandler_
private

Definition at line 67 of file dynamixel_driver.h.

dynamixel::PortHandler* DynamixelDriver::portHandler_
private

Definition at line 66 of file dynamixel_driver.h.

uint8_t DynamixelDriver::sync_read_handler_cnt_
private

Definition at line 80 of file dynamixel_driver.h.

uint8_t DynamixelDriver::sync_write_handler_cnt_
private

Definition at line 79 of file dynamixel_driver.h.

SyncReadHandler DynamixelDriver::syncReadHandler_[MAX_HANDLER_NUM]
private

Definition at line 70 of file dynamixel_driver.h.

SyncWriteHandler DynamixelDriver::syncWriteHandler_[MAX_HANDLER_NUM]
private

Definition at line 69 of file dynamixel_driver.h.

DynamixelTool DynamixelDriver::tools_[MAX_DXL_SERIES_NUM]
private

Definition at line 76 of file dynamixel_driver.h.

uint8_t DynamixelDriver::tools_cnt_
private

Definition at line 78 of file dynamixel_driver.h.


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


dynamixel_workbench_toolbox
Author(s): Darby Lim , Ryan Shim
autogenerated on Mon Sep 28 2020 03:37:05