The StepperDriver class. More...
#include <stepper_driver.hpp>
Public Member Functions | |
int | changeId (uint8_t id, uint8_t new_id) override |
StepperDriver<reg_type>::changeId. More... | |
int | checkModelNumber (uint8_t id) override |
StepperDriver<reg_type>::checkModelNumber. More... | |
int | readControlMode (uint8_t id, uint8_t &operating_mode) override |
int | readFirmwareRunning (uint8_t id, bool &is_running) override |
StepperDriver<reg_type>::readFirmwareRunning. More... | |
int | readFirmwareVersion (uint8_t id, std::string &version) override |
StepperDriver<reg_type>::readFirmwareVersion. More... | |
int | readHomingStatus (uint8_t id, uint8_t &status) override |
StepperDriver<reg_type>::readHomingStatus. More... | |
int | readHwErrorStatus (uint8_t id, uint8_t &hardware_error_status) override |
StepperDriver<reg_type>::readHwErrorStatus. More... | |
int | readMaxPosition (uint8_t id, uint32_t &max_pos) override |
StepperDriver<reg_type>::readMaxPosition. More... | |
int | readMinPosition (uint8_t id, uint32_t &min_pos) override |
StepperDriver<reg_type>::readMinPosition. More... | |
int | readPosition (uint8_t id, uint32_t &present_position) override |
StepperDriver<reg_type>::readPosition. More... | |
int | readTemperature (uint8_t id, uint8_t &temperature) override |
StepperDriver<reg_type>::readTemperature. More... | |
int | readVelocity (uint8_t id, uint32_t &present_velocity) override |
StepperDriver<reg_type>::readVelocity. More... | |
int | readVelocityProfile (uint8_t id, std::vector< uint32_t > &data_list) override |
StepperDriver::readVelocityProfile. More... | |
int | readVoltage (uint8_t id, double &voltage) override |
StepperDriver<reg_type>::readVoltage. More... | |
int | startHoming (uint8_t id) override |
StepperDriver<reg_type>::startHoming. More... | |
StepperDriver (std::shared_ptr< dynamixel::PortHandler > portHandler, std::shared_ptr< dynamixel::PacketHandler > packetHandler) | |
DxlDriver<reg_type>::DxlDriver. More... | |
std::string | str () const override |
StepperDriver<reg_type>::str. More... | |
int | syncReadFirmwareVersion (const std::vector< uint8_t > &id_list, std::vector< std::string > &firmware_list) override |
StepperDriver<reg_type>::syncReadFirmwareVersion. More... | |
int | syncReadHomingAbsPosition (const std::vector< uint8_t > &id_list, std::vector< uint32_t > &abs_position) override |
StepperDriver<reg_type>::syncReadHomingAbsPosition. More... | |
int | syncReadHomingStatus (const std::vector< uint8_t > &id_list, std::vector< uint8_t > &status_list) override |
StepperDriver<reg_type>::syncReadHomingStatus. More... | |
int | syncReadHwErrorStatus (const std::vector< uint8_t > &id_list, std::vector< uint8_t > &hw_error_list) override |
StepperDriver<reg_type>::syncReadHwErrorStatus. More... | |
int | syncReadHwStatus (const std::vector< uint8_t > &id_list, std::vector< std::pair< double, uint8_t >> &data_list) override |
StepperDriver<reg_type>::syncReadHwStatus. More... | |
int | syncReadJointStatus (const std::vector< uint8_t > &id_list, std::vector< std::array< uint32_t, 2 >> &data_array_list) override |
StepperDriver<reg_type>::syncReadJointStatus. More... | |
int | syncReadPosition (const std::vector< uint8_t > &id_list, std::vector< uint32_t > &position_list) override |
StepperDriver<reg_type>::syncReadPosition. More... | |
int | syncReadRawVoltage (const std::vector< uint8_t > &id_list, std::vector< double > &voltage_list) override |
StepperDriver<reg_type>::syncReadRawVoltage. More... | |
int | syncReadTemperature (const std::vector< uint8_t > &id_list, std::vector< uint8_t > &temperature_list) override |
StepperDriver<reg_type>::syncReadTemperature. More... | |
int | syncReadVelocity (const std::vector< uint8_t > &id_list, std::vector< uint32_t > &velocity_list) override |
StepperDriver<reg_type>::syncReadVelocity. More... | |
int | syncReadVoltage (const std::vector< uint8_t > &id_list, std::vector< double > &voltage_list) override |
StepperDriver<reg_type>::syncReadVoltage. More... | |
int | syncWriteHomingAbsPosition (const std::vector< uint8_t > &id_list, const std::vector< uint32_t > &abs_position) override |
StepperDriver<reg_type>::syncWriteHomingAbsPosition. More... | |
int | syncWritePositionGoal (const std::vector< uint8_t > &id_list, const std::vector< uint32_t > &position_list) override |
StepperDriver<reg_type>::syncWritePositionGoal. More... | |
int | syncWriteTorquePercentage (const std::vector< uint8_t > &id_list, const std::vector< uint8_t > &torque_percentage_list) override |
StepperDriver<reg_type>::syncWriteTorquePercentage. More... | |
int | syncWriteVelocityGoal (const std::vector< uint8_t > &id_list, const std::vector< uint32_t > &velocity_list) override |
StepperDriver<reg_type>::syncWriteVelocityGoal. More... | |
float | velocityUnit () const |
writeVelocityGoal: define the unit of the velocity in RPM More... | |
int | writeControlMode (uint8_t id, uint8_t operating_mode) |
int | writeHomingSetup (uint8_t id, uint8_t direction, uint8_t stall_threshold) override |
StepperDriver<reg_type>::writeHomingDirection. More... | |
int | writePositionGoal (uint8_t id, uint32_t position) override |
StepperDriver<reg_type>::writePositionGoal. More... | |
int | writeTorquePercentage (uint8_t id, uint8_t torque_enable) override |
StepperDriver<reg_type>::writeTorquePercentage. More... | |
int | writeVelocityGoal (uint8_t id, uint32_t velocity) override |
StepperDriver<reg_type>::writeVelocityGoal. More... | |
int | writeVelocityProfile (uint8_t id, const std::vector< uint32_t > &data_list) override |
StepperDriver<reg_type>::writeVelocityProfile. More... | |
![]() | |
AbstractStepperDriver ()=default | |
AbstractStepperDriver (std::shared_ptr< dynamixel::PortHandler > portHandler, std::shared_ptr< dynamixel::PacketHandler > packetHandler) | |
AbstractStepperDriver::AbstractStepperDriver. More... | |
virtual int | factoryCalibration (const uint8_t id, const uint32_t &command) |
AbstractStepperDriver::factoryCalibration. More... | |
std::string | interpretErrorState (uint32_t hw_state) const override |
AbstractStepperDriver::interpretErrorState. More... | |
virtual common::model::EStepperCalibrationStatus | interpretHomingData (uint8_t status) const |
AbstractStepperDriver::interpretHomingData. More... | |
int | readConveyorVelocity (uint8_t id, int32_t &velocity, int32_t &direction) |
Returns the velocity of the conveyor in percentage. More... | |
int | writeSingleCmd (const std::unique_ptr< common::model::AbstractTtlSingleMotorCmd > &cmd) override |
AbstractStepperDriver::writeSingleCmd. More... | |
int | writeSyncCmd (int type, const std::vector< uint8_t > &ids, const std::vector< uint32_t > ¶ms) override |
AbstractStepperDriver::writeSyncCmd. More... | |
![]() | |
AbstractMotorDriver ()=default | |
AbstractMotorDriver (std::shared_ptr< dynamixel::PortHandler > portHandler, std::shared_ptr< dynamixel::PacketHandler > packetHandler) | |
virtual int | syncReadJointStatus (const std::vector< uint8_t > &id_list, std::vector< std::array< uint32_t, 2 > > &data_array_list)=0 |
![]() | |
AbstractTtlDriver ()=default | |
AbstractTtlDriver (std::shared_ptr< dynamixel::PortHandler > portHandler, std::shared_ptr< dynamixel::PacketHandler > packetHandler) | |
AbstractTtlDriver::AbstractTtlDriver. More... | |
virtual int | getModelNumber (uint8_t id, uint16_t &model_number) |
AbstractTtlDriver::getModelNumber. More... | |
virtual int | ping (uint8_t id) |
AbstractTtlDriver::ping. More... | |
virtual int | readCustom (uint16_t address, uint8_t data_len, uint8_t id, uint32_t &data) |
AbstractTtlDriver::readCustom. More... | |
virtual int | reboot (uint8_t id) |
AbstractTtlDriver::reboot. More... | |
virtual int | scan (std::vector< uint8_t > &id_list) |
AbstractTtlDriver::scan. More... | |
virtual int | syncReadHwStatus (const std::vector< uint8_t > &id_list, std::vector< std::pair< double, uint8_t > > &data_array_list)=0 |
virtual int | writeCustom (uint16_t address, uint8_t data_len, uint8_t id, uint32_t data) |
AbstractTtlDriver::writeCustom. More... | |
virtual | ~AbstractTtlDriver ()=default |
Private Member Functions | |
int | writeA1 (uint8_t id, uint32_t a_1) |
StepperDriver<reg_type>::writeA1. More... | |
int | writeAMax (uint8_t id, uint32_t a_max) |
StepperDriver<reg_type>::writeAMax. More... | |
int | writeD1 (uint8_t id, uint32_t d_1) |
StepperDriver<reg_type>::writeD1. More... | |
int | writeDMax (uint8_t id, uint32_t d_max) |
StepperDriver<reg_type>::writeDMax. More... | |
int | writeV1 (uint8_t id, uint32_t v_1) |
StepperDriver<reg_type>::writeV1. More... | |
int | writeVMax (uint8_t id, uint32_t v_max) |
StepperDriver<reg_type>::writeVMax. More... | |
int | writeVStart (uint8_t id, uint32_t v_start) |
StepperDriver<reg_type>::writeVStart. More... | |
int | writeVStop (uint8_t id, uint32_t v_stop) |
StepperDriver<reg_type>::writeVStop. More... | |
Additional Inherited Members | |
![]() | |
std::string | interpretFirmwareVersion (uint32_t fw_version) const override |
AbstractStepperDriver::interpretFirmwareVersion. More... | |
![]() | |
AbstractTtlDriver (AbstractTtlDriver &&)=default | |
AbstractTtlDriver (const AbstractTtlDriver &)=default | |
AbstractTtlDriver & | operator= (AbstractTtlDriver &&)=default |
AbstractTtlDriver & | operator= (const AbstractTtlDriver &)=default |
template<typename T > | |
int | read (uint16_t address, uint8_t id, T &data) |
AbstractTtlDriver::read. More... | |
template<typename T > | |
int | syncRead (uint16_t address, const std::vector< uint8_t > &id_list, std::vector< T > &data_list) |
AbstractTtlDriver::syncRead. More... | |
template<typename T , const size_t N> | |
int | syncReadConsecutiveBytes (uint16_t address, const std::vector< uint8_t > &id_list, std::vector< std::array< T, N > > &data_list) |
AbstractTtlDriver::syncReadConsecutiveBytes. More... | |
template<typename T > | |
int | syncWrite (uint16_t address, const std::vector< uint8_t > &id_list, const std::vector< T > &data_list) |
template<typename T > | |
int | write (uint16_t address, uint8_t id, T data) |
![]() | |
static constexpr int | PING_WRONG_MODEL_NUMBER = 30 |
The StepperDriver class.
Definition at line 38 of file stepper_driver.hpp.
ttl_driver::StepperDriver< reg_type >::StepperDriver | ( | std::shared_ptr< dynamixel::PortHandler > | portHandler, |
std::shared_ptr< dynamixel::PacketHandler > | packetHandler | ||
) |
DxlDriver<reg_type>::DxlDriver.
Definition at line 127 of file stepper_driver.hpp.
|
overridevirtual |
StepperDriver<reg_type>::changeId.
id | |
new_id |
Implements ttl_driver::AbstractMotorDriver.
Definition at line 154 of file stepper_driver.hpp.
|
overridevirtual |
StepperDriver<reg_type>::checkModelNumber.
id |
Implements ttl_driver::AbstractTtlDriver.
Definition at line 170 of file stepper_driver.hpp.
|
overridevirtual |
Implements ttl_driver::AbstractMotorDriver.
Definition at line 549 of file stepper_driver.hpp.
|
overridevirtual |
StepperDriver<reg_type>::readFirmwareRunning.
id | |
is_running |
Implements ttl_driver::AbstractStepperDriver.
Definition at line 788 of file stepper_driver.hpp.
|
overridevirtual |
StepperDriver<reg_type>::readFirmwareVersion.
id | |
version |
Implements ttl_driver::AbstractTtlDriver.
Definition at line 193 of file stepper_driver.hpp.
|
overridevirtual |
StepperDriver<reg_type>::readHomingStatus.
id | |
status |
Implements ttl_driver::AbstractStepperDriver.
Definition at line 764 of file stepper_driver.hpp.
|
overridevirtual |
StepperDriver<reg_type>::readHwErrorStatus.
id | |
hardware_error_status |
Implements ttl_driver::AbstractTtlDriver.
Definition at line 368 of file stepper_driver.hpp.
|
overridevirtual |
StepperDriver<reg_type>::readMaxPosition.
id | |
pos |
Implements ttl_driver::AbstractMotorDriver.
Definition at line 221 of file stepper_driver.hpp.
|
overridevirtual |
StepperDriver<reg_type>::readMinPosition.
id | |
pos |
Implements ttl_driver::AbstractMotorDriver.
Definition at line 209 of file stepper_driver.hpp.
|
overridevirtual |
StepperDriver<reg_type>::readPosition.
id | |
present_position |
Implements ttl_driver::AbstractMotorDriver.
Definition at line 317 of file stepper_driver.hpp.
|
overridevirtual |
StepperDriver<reg_type>::readTemperature.
id | |
temperature |
Implements ttl_driver::AbstractTtlDriver.
Definition at line 341 of file stepper_driver.hpp.
|
overridevirtual |
StepperDriver<reg_type>::readVelocity.
id | |
present_velocity |
Implements ttl_driver::AbstractMotorDriver.
Definition at line 329 of file stepper_driver.hpp.
|
overridevirtual |
StepperDriver::readVelocityProfile.
id | |
data_list |
Implements ttl_driver::AbstractMotorDriver.
Definition at line 567 of file stepper_driver.hpp.
|
overridevirtual |
StepperDriver<reg_type>::readVoltage.
id | |
voltage |
Implements ttl_driver::AbstractTtlDriver.
Definition at line 353 of file stepper_driver.hpp.
|
overridevirtual |
StepperDriver<reg_type>::startHoming.
id |
Implements ttl_driver::AbstractStepperDriver.
Definition at line 716 of file stepper_driver.hpp.
|
overridevirtual |
Reimplemented from ttl_driver::AbstractStepperDriver.
Definition at line 142 of file stepper_driver.hpp.
|
overridevirtual |
StepperDriver<reg_type>::syncReadFirmwareVersion.
id_list | |
firmware_list |
Implements ttl_driver::AbstractTtlDriver.
Definition at line 446 of file stepper_driver.hpp.
|
overridevirtual |
StepperDriver<reg_type>::syncReadHomingAbsPosition.
id | |
abs_position |
Implements ttl_driver::AbstractStepperDriver.
Definition at line 815 of file stepper_driver.hpp.
|
overridevirtual |
StepperDriver<reg_type>::syncReadHomingStatus.
id_list | |
status_list |
Implements ttl_driver::AbstractStepperDriver.
Definition at line 776 of file stepper_driver.hpp.
|
overridevirtual |
StepperDriver<reg_type>::syncReadHwErrorStatus.
id_list | |
hw_error_list |
Implements ttl_driver::AbstractTtlDriver.
Definition at line 539 of file stepper_driver.hpp.
|
override |
StepperDriver<reg_type>::syncReadHwStatus.
id_list | |
data_list |
Definition at line 510 of file stepper_driver.hpp.
|
override |
StepperDriver<reg_type>::syncReadJointStatus.
id_list | |
data_array_list |
Definition at line 405 of file stepper_driver.hpp.
|
overridevirtual |
StepperDriver<reg_type>::syncReadPosition.
id_list | |
position_list |
Implements ttl_driver::AbstractMotorDriver.
Definition at line 380 of file stepper_driver.hpp.
|
overridevirtual |
StepperDriver<reg_type>::syncReadRawVoltage.
id_list | |
voltage_list |
Implements ttl_driver::AbstractTtlDriver.
Definition at line 493 of file stepper_driver.hpp.
|
overridevirtual |
StepperDriver<reg_type>::syncReadTemperature.
id_list | |
temperature_list |
Implements ttl_driver::AbstractTtlDriver.
Definition at line 464 of file stepper_driver.hpp.
|
overridevirtual |
StepperDriver<reg_type>::syncReadVelocity.
id_list | |
velocity_list |
Implements ttl_driver::AbstractMotorDriver.
Definition at line 392 of file stepper_driver.hpp.
|
overridevirtual |
StepperDriver<reg_type>::syncReadVoltage.
id_list | |
voltage_list |
Implements ttl_driver::AbstractTtlDriver.
Definition at line 476 of file stepper_driver.hpp.
|
overridevirtual |
StepperDriver<reg_type>::syncWriteHomingAbsPosition.
id | |
abs_position |
Implements ttl_driver::AbstractStepperDriver.
Definition at line 803 of file stepper_driver.hpp.
|
overridevirtual |
StepperDriver<reg_type>::syncWritePositionGoal.
id_list | |
position_list |
Implements ttl_driver::AbstractMotorDriver.
Definition at line 291 of file stepper_driver.hpp.
|
overridevirtual |
StepperDriver<reg_type>::syncWriteTorquePercentage.
id_list | |
torque_percentage_list |
Implements ttl_driver::AbstractMotorDriver.
Definition at line 273 of file stepper_driver.hpp.
|
overridevirtual |
StepperDriver<reg_type>::syncWriteVelocityGoal.
id_list | |
velocity_list |
Implements ttl_driver::AbstractMotorDriver.
Definition at line 303 of file stepper_driver.hpp.
|
virtual |
writeVelocityGoal: define the unit of the velocity in RPM
Implements ttl_driver::AbstractStepperDriver.
Definition at line 919 of file stepper_driver.hpp.
|
private |
StepperDriver<reg_type>::writeA1.
id | |
a_1 |
Definition at line 841 of file stepper_driver.hpp.
|
private |
StepperDriver<reg_type>::writeAMax.
id | |
a_max |
Definition at line 865 of file stepper_driver.hpp.
|
virtual |
Implements ttl_driver::AbstractMotorDriver.
Definition at line 555 of file stepper_driver.hpp.
|
private |
StepperDriver<reg_type>::writeD1.
id | |
d_1 |
Definition at line 901 of file stepper_driver.hpp.
|
private |
StepperDriver<reg_type>::writeDMax.
id | |
d_max |
Definition at line 889 of file stepper_driver.hpp.
|
overridevirtual |
StepperDriver<reg_type>::writeHomingDirection.
id | |
direction | |
stall_threshold |
Implements ttl_driver::AbstractStepperDriver.
Definition at line 730 of file stepper_driver.hpp.
|
overridevirtual |
StepperDriver<reg_type>::writePositionGoal.
id | |
position |
Implements ttl_driver::AbstractMotorDriver.
Definition at line 248 of file stepper_driver.hpp.
|
overridevirtual |
StepperDriver<reg_type>::writeTorquePercentage.
id | |
torque_percentage |
Implements ttl_driver::AbstractMotorDriver.
Definition at line 235 of file stepper_driver.hpp.
|
private |
StepperDriver<reg_type>::writeV1.
id | |
v_1 |
Definition at line 853 of file stepper_driver.hpp.
|
overridevirtual |
StepperDriver<reg_type>::writeVelocityGoal.
id | |
velocity |
Implements ttl_driver::AbstractMotorDriver.
Definition at line 261 of file stepper_driver.hpp.
|
overridevirtual |
StepperDriver<reg_type>::writeVelocityProfile.
id | |
data_list |
Implements ttl_driver::AbstractMotorDriver.
Definition at line 603 of file stepper_driver.hpp.
|
private |
StepperDriver<reg_type>::writeVMax.
id | |
v_max |
Definition at line 877 of file stepper_driver.hpp.
|
private |
StepperDriver<reg_type>::writeVStart.
id | |
v_start |
Definition at line 829 of file stepper_driver.hpp.
|
private |
StepperDriver<reg_type>::writeVStop.
id | |
v_stop |
Definition at line 913 of file stepper_driver.hpp.