Public Member Functions | Protected Member Functions | List of all members
ttl_driver::AbstractStepperDriver Class Referenceabstract

#include <abstract_stepper_driver.hpp>

Inheritance diagram for ttl_driver::AbstractStepperDriver:
Inheritance graph
[legend]

Public Member Functions

 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...
 
virtual int readFirmwareRunning (uint8_t id, bool &is_running)=0
 
virtual int readHomingStatus (uint8_t id, uint8_t &status)=0
 
virtual int startHoming (uint8_t id)=0
 
std::string str () const override
 AbstractStepperDriver::str. More...
 
virtual int syncReadHomingAbsPosition (const std::vector< uint8_t > &id_list, std::vector< uint32_t > &abs_position)=0
 
virtual int syncReadHomingStatus (const std::vector< uint8_t > &id_list, std::vector< uint8_t > &status_list)=0
 
virtual int syncWriteHomingAbsPosition (const std::vector< uint8_t > &id_list, const std::vector< uint32_t > &abs_position)=0
 
virtual float velocityUnit () const =0
 writeVelocityGoal: define the unit of the velocity in RPM More...
 
virtual int writeHomingSetup (uint8_t id, uint8_t direction, uint8_t stall_threshold)=0
 
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 > &params) override
 AbstractStepperDriver::writeSyncCmd. More...
 
- Public Member Functions inherited from ttl_driver::AbstractMotorDriver
 AbstractMotorDriver ()=default
 
 AbstractMotorDriver (std::shared_ptr< dynamixel::PortHandler > portHandler, std::shared_ptr< dynamixel::PacketHandler > packetHandler)
 
virtual int changeId (uint8_t id, uint8_t new_id)=0
 
virtual int readControlMode (uint8_t id, uint8_t &mode)=0
 
virtual int readMaxPosition (uint8_t id, uint32_t &max_pos)=0
 
virtual int readMinPosition (uint8_t id, uint32_t &min_pos)=0
 
virtual int readPosition (uint8_t id, uint32_t &present_position)=0
 
virtual int readVelocity (uint8_t id, uint32_t &present_velocity)=0
 
virtual int readVelocityProfile (uint8_t id, std::vector< uint32_t > &data_list)=0
 
virtual int syncReadJointStatus (const std::vector< uint8_t > &id_list, std::vector< std::array< uint32_t, 2 > > &data_array_list)=0
 
virtual int syncReadPosition (const std::vector< uint8_t > &id_list, std::vector< uint32_t > &position_list)=0
 
virtual int syncReadVelocity (const std::vector< uint8_t > &id_list, std::vector< uint32_t > &velocity_list)=0
 
virtual int syncWritePositionGoal (const std::vector< uint8_t > &id_list, const std::vector< uint32_t > &position_list)=0
 
virtual int syncWriteTorquePercentage (const std::vector< uint8_t > &id_list, const std::vector< uint8_t > &torque_percentage_list)=0
 
virtual int syncWriteVelocityGoal (const std::vector< uint8_t > &id_list, const std::vector< uint32_t > &velocity_list)=0
 
virtual int writeControlMode (uint8_t id, uint8_t mode)=0
 
virtual int writePositionGoal (uint8_t id, uint32_t position)=0
 
virtual int writeTorquePercentage (uint8_t id, uint8_t torque_percentage)=0
 
virtual int writeVelocityGoal (uint8_t id, uint32_t velocity)=0
 
virtual int writeVelocityProfile (uint8_t id, const std::vector< uint32_t > &data_list)=0
 
- Public Member Functions inherited from ttl_driver::AbstractTtlDriver
 AbstractTtlDriver ()=default
 
 AbstractTtlDriver (std::shared_ptr< dynamixel::PortHandler > portHandler, std::shared_ptr< dynamixel::PacketHandler > packetHandler)
 AbstractTtlDriver::AbstractTtlDriver. More...
 
virtual int checkModelNumber (uint8_t id)=0
 
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 readFirmwareVersion (uint8_t id, std::string &version)=0
 
virtual int readHwErrorStatus (uint8_t id, uint8_t &hardware_error_status)=0
 
virtual int readTemperature (uint8_t id, uint8_t &temperature)=0
 
virtual int readVoltage (uint8_t id, double &voltage)=0
 
virtual int reboot (uint8_t id)
 AbstractTtlDriver::reboot. More...
 
virtual int scan (std::vector< uint8_t > &id_list)
 AbstractTtlDriver::scan. More...
 
virtual int syncReadFirmwareVersion (const std::vector< uint8_t > &id_list, std::vector< std::string > &firmware_version)=0
 
virtual int syncReadHwErrorStatus (const std::vector< uint8_t > &id_list, std::vector< uint8_t > &hw_error_list)=0
 
virtual int syncReadHwStatus (const std::vector< uint8_t > &id_list, std::vector< std::pair< double, uint8_t > > &data_array_list)=0
 
virtual int syncReadRawVoltage (const std::vector< uint8_t > &id_list, std::vector< double > &voltage_list)=0
 
virtual int syncReadTemperature (const std::vector< uint8_t > &id_list, std::vector< uint8_t > &temperature_list)=0
 
virtual int syncReadVoltage (const std::vector< uint8_t > &id_list, std::vector< double > &voltage_list)=0
 
virtual int writeCustom (uint16_t address, uint8_t data_len, uint8_t id, uint32_t data)
 AbstractTtlDriver::writeCustom. More...
 
virtual ~AbstractTtlDriver ()=default
 

Protected Member Functions

std::string interpretFirmwareVersion (uint32_t fw_version) const override
 AbstractStepperDriver::interpretFirmwareVersion. More...
 
- Protected Member Functions inherited from ttl_driver::AbstractTtlDriver
 AbstractTtlDriver (AbstractTtlDriver &&)=default
 
 AbstractTtlDriver (const AbstractTtlDriver &)=default
 
AbstractTtlDriveroperator= (AbstractTtlDriver &&)=default
 
AbstractTtlDriveroperator= (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)
 

Additional Inherited Members

- Static Protected Attributes inherited from ttl_driver::AbstractTtlDriver
static constexpr int PING_WRONG_MODEL_NUMBER = 30
 

Detailed Description

Definition at line 34 of file abstract_stepper_driver.hpp.

Constructor & Destructor Documentation

◆ AbstractStepperDriver() [1/2]

ttl_driver::AbstractStepperDriver::AbstractStepperDriver ( )
default

◆ AbstractStepperDriver() [2/2]

ttl_driver::AbstractStepperDriver::AbstractStepperDriver ( std::shared_ptr< dynamixel::PortHandler >  portHandler,
std::shared_ptr< dynamixel::PacketHandler >  packetHandler 
)

Member Function Documentation

◆ factoryCalibration()

int ttl_driver::AbstractStepperDriver::factoryCalibration ( const uint8_t  id,
const uint32_t &  command 
)
virtual

◆ interpretErrorState()

std::string ttl_driver::AbstractStepperDriver::interpretErrorState ( uint32_t  hw_state) const
overridevirtual

AbstractStepperDriver::interpretErrorState.

Parameters
hw_state
Returns

Implements ttl_driver::AbstractTtlDriver.

Definition at line 175 of file abstract_stepper_driver.cpp.

◆ interpretFirmwareVersion()

std::string ttl_driver::AbstractStepperDriver::interpretFirmwareVersion ( uint32_t  fw_version) const
overrideprotectedvirtual

AbstractStepperDriver::interpretFirmwareVersion.

Parameters
fw_version
Returns

Implements ttl_driver::AbstractTtlDriver.

Definition at line 157 of file abstract_stepper_driver.cpp.

◆ interpretHomingData()

common::model::EStepperCalibrationStatus ttl_driver::AbstractStepperDriver::interpretHomingData ( uint8_t  status) const
virtual

AbstractStepperDriver::interpretHomingData.

Parameters
status
Returns

Reimplemented in ttl_driver::Ned3ProStepperDriver< reg_type >.

Definition at line 213 of file abstract_stepper_driver.cpp.

◆ readConveyorVelocity()

int ttl_driver::AbstractStepperDriver::readConveyorVelocity ( uint8_t  id,
int32_t &  velocity,
int32_t &  direction 
)

Returns the velocity of the conveyor in percentage.

Definition at line 254 of file abstract_stepper_driver.cpp.

◆ readFirmwareRunning()

virtual int ttl_driver::AbstractStepperDriver::readFirmwareRunning ( uint8_t  id,
bool &  is_running 
)
pure virtual

◆ readHomingStatus()

virtual int ttl_driver::AbstractStepperDriver::readHomingStatus ( uint8_t  id,
uint8_t &  status 
)
pure virtual

◆ startHoming()

virtual int ttl_driver::AbstractStepperDriver::startHoming ( uint8_t  id)
pure virtual

◆ str()

std::string ttl_driver::AbstractStepperDriver::str ( ) const
overridevirtual

◆ syncReadHomingAbsPosition()

virtual int ttl_driver::AbstractStepperDriver::syncReadHomingAbsPosition ( const std::vector< uint8_t > &  id_list,
std::vector< uint32_t > &  abs_position 
)
pure virtual

◆ syncReadHomingStatus()

virtual int ttl_driver::AbstractStepperDriver::syncReadHomingStatus ( const std::vector< uint8_t > &  id_list,
std::vector< uint8_t > &  status_list 
)
pure virtual

◆ syncWriteHomingAbsPosition()

virtual int ttl_driver::AbstractStepperDriver::syncWriteHomingAbsPosition ( const std::vector< uint8_t > &  id_list,
const std::vector< uint32_t > &  abs_position 
)
pure virtual

◆ velocityUnit()

virtual float ttl_driver::AbstractStepperDriver::velocityUnit ( ) const
pure virtual

writeVelocityGoal: define the unit of the velocity in RPM

Implemented in ttl_driver::Ned3ProStepperDriver< reg_type >, ttl_driver::MockStepperDriver, and ttl_driver::StepperDriver< reg_type >.

◆ writeHomingSetup()

virtual int ttl_driver::AbstractStepperDriver::writeHomingSetup ( uint8_t  id,
uint8_t  direction,
uint8_t  stall_threshold 
)
pure virtual

◆ writeSingleCmd()

int ttl_driver::AbstractStepperDriver::writeSingleCmd ( const std::unique_ptr< common::model::AbstractTtlSingleMotorCmd > &  cmd)
overridevirtual

◆ writeSyncCmd()

int ttl_driver::AbstractStepperDriver::writeSyncCmd ( int  type,
const std::vector< uint8_t > &  ids,
const std::vector< uint32_t > &  params 
)
overridevirtual

AbstractStepperDriver::writeSyncCmd.

Parameters
type
ids
params

Implements ttl_driver::AbstractTtlDriver.

Definition at line 111 of file abstract_stepper_driver.cpp.


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


ttl_driver
Author(s): Clement Cocquempot
autogenerated on Wed May 21 2025 08:30:15