Public Member Functions | List of all members
ttl_driver::Ned3ProStepperDriver< reg_type > Class Template Reference

The Ned3ProStepperDriver class. More...

#include <ned3pro_stepper_driver.hpp>

Inheritance diagram for ttl_driver::Ned3ProStepperDriver< reg_type >:
Inheritance graph
[legend]

Public Member Functions

int changeId (uint8_t id, uint8_t new_id) override
 Ned3ProStepperDriver<reg_type>::changeId. More...
 
int checkModelNumber (uint8_t id) override
 Ned3ProStepperDriver<reg_type>::checkModelNumber. More...
 
int factoryCalibration (const uint8_t id, const uint32_t &control)
 Ned3ProStepperDriver<reg_type>::factoryCalibration. More...
 
common::model::EStepperCalibrationStatus interpretHomingData (uint8_t status) const override
 AbstractStepperDriver::interpretHomingData. More...
 
 Ned3ProStepperDriver (std::shared_ptr< dynamixel::PortHandler > portHandler, std::shared_ptr< dynamixel::PacketHandler > packetHandler)
 DxlDriver<reg_type>::DxlDriver. More...
 
int readControlMode (uint8_t id, uint8_t &operating_mode) override
 
int readEncAngle (uint8_t id, const uint32_t &enc_angle)
 Ned3ProStepperDriver<reg_type>::readEncAngle. More...
 
int readFirmwareRunning (uint8_t id, bool &is_running) override
 Ned3ProStepperDriver<reg_type>::readFirmwareRunning. More...
 
int readFirmwareVersion (uint8_t id, std::string &version) override
 Ned3ProStepperDriver<reg_type>::readFirmwareVersion. More...
 
int readHomingStatus (uint8_t id, uint8_t &status)
 
int readHwErrorStatus (uint8_t id, uint8_t &hardware_error_status) override
 Ned3ProStepperDriver<reg_type>::readHwErrorStatus. More...
 
int readMaxPosition (uint8_t id, uint32_t &max_pos) override
 
int readMinPosition (uint8_t id, uint32_t &min_pos) override
 
int readPosition (uint8_t id, uint32_t &present_position) override
 Ned3ProStepperDriver<reg_type>::readPosition. More...
 
int readStatus (uint8_t id, const uint32_t &status)
 Ned3ProStepperDriver<reg_type>::readStatus. More...
 
int readTemperature (uint8_t id, uint8_t &temperature) override
 Ned3ProStepperDriver<reg_type>::readTemperature. More...
 
int readVelocity (uint8_t id, uint32_t &present_velocity) override
 Ned3ProStepperDriver<reg_type>::readVelocity. More...
 
int readVelocityProfile (uint8_t id, std::vector< uint32_t > &data_list) override
 
int readVoltage (uint8_t id, double &voltage) override
 Ned3ProStepperDriver<reg_type>::readVoltage. More...
 
int startHoming (uint8_t id)
 
std::string str () const override
 Ned3ProStepperDriver<reg_type>::str. More...
 
int syncReadFirmwareVersion (const std::vector< uint8_t > &id_list, std::vector< std::string > &firmware_list) override
 Ned3ProStepperDriver<reg_type>::syncReadFirmwareVersion. More...
 
int syncReadHomingAbsPosition (const std::vector< uint8_t > &id_list, std::vector< uint32_t > &abs_position)
 
int syncReadHomingStatus (const std::vector< uint8_t > &id_list, std::vector< uint8_t > &status_list)
 
int syncReadHwErrorStatus (const std::vector< uint8_t > &id_list, std::vector< uint8_t > &hw_error_list) override
 Ned3ProStepperDriver<reg_type>::syncReadHwErrorStatus. More...
 
int syncReadHwStatus (const std::vector< uint8_t > &id_list, std::vector< std::pair< double, uint8_t >> &data_list) override
 Ned3ProStepperDriver<reg_type>::syncReadHwStatus. More...
 
int syncReadJointStatus (const std::vector< uint8_t > &id_list, std::vector< std::array< uint32_t, 2 >> &data_array_list) override
 Ned3ProStepperDriver<reg_type>::syncReadJointStatus. More...
 
int syncReadPosition (const std::vector< uint8_t > &id_list, std::vector< uint32_t > &position_list) override
 Ned3ProStepperDriver<reg_type>::syncReadPosition. More...
 
int syncReadRawVoltage (const std::vector< uint8_t > &id_list, std::vector< double > &voltage_list) override
 Ned3ProStepperDriver<reg_type>::syncReadRawVoltage. More...
 
int syncReadTemperature (const std::vector< uint8_t > &id_list, std::vector< uint8_t > &temperature_list) override
 Ned3ProStepperDriver<reg_type>::syncReadTemperature. More...
 
int syncReadVelocity (const std::vector< uint8_t > &id_list, std::vector< uint32_t > &velocity_list) override
 Ned3ProStepperDriver<reg_type>::syncReadVelocity. More...
 
int syncReadVoltage (const std::vector< uint8_t > &id_list, std::vector< double > &voltage_list) override
 Ned3ProStepperDriver<reg_type>::syncReadVoltage. More...
 
int syncWriteHomingAbsPosition (const std::vector< uint8_t > &id_list, const std::vector< uint32_t > &abs_position)
 
int syncWritePositionGoal (const std::vector< uint8_t > &id_list, const std::vector< uint32_t > &position_list) override
 Ned3ProStepperDriver<reg_type>::syncWritePositionGoal. More...
 
int syncWriteTorquePercentage (const std::vector< uint8_t > &id_list, const std::vector< uint8_t > &torque_percentage_list) override
 Ned3ProStepperDriver<reg_type>::syncWriteTorquePercentage. More...
 
int syncWriteVelocityGoal (const std::vector< uint8_t > &id_list, const std::vector< uint32_t > &velocity_list) override
 Ned3ProStepperDriver<reg_type>::syncWriteVelocityGoal. More...
 
float velocityUnit () const override
 writeVelocityGoal: define the unit of the velocity in RPM More...
 
int writeAccelerationProfile (uint8_t id, const uint32_t &acceleration_profile)
 Ned3ProStepperDriver<reg_type>::writeAccelerationProfile. More...
 
int writeControlMode (uint8_t id, uint8_t operating_mode) override
 Ned3ProStepperDriver<reg_type>::writeOperatingMode. More...
 
int writeHomingSetup (uint8_t id, uint8_t direction, uint8_t stall_threshold)
 
int writePositionGoal (uint8_t id, uint32_t position) override
 Ned3ProStepperDriver<reg_type>::writePositionGoal. More...
 
int writeTorquePercentage (uint8_t id, uint8_t torque_percentage) override
 Ned3ProStepperDriver<reg_type>::writeTorquePercentage. More...
 
int writeVelocityGoal (uint8_t id, uint32_t velocity) override
 Ned3ProStepperDriver<reg_type>::writeVelocityGoal. More...
 
int writeVelocityProfile (uint8_t id, const std::vector< uint32_t > &data_list) override
 
int writeVelocityProfile (uint8_t id, const uint32_t &velocity_profile)
 Ned3ProStepperDriver<reg_type>::writeVelocityProfile. More...
 
- Public Member Functions inherited from ttl_driver::AbstractStepperDriver
 AbstractStepperDriver ()=default
 
 AbstractStepperDriver (std::shared_ptr< dynamixel::PortHandler > portHandler, std::shared_ptr< dynamixel::PacketHandler > packetHandler)
 AbstractStepperDriver::AbstractStepperDriver. More...
 
std::string interpretErrorState (uint32_t hw_state) const override
 AbstractStepperDriver::interpretErrorState. 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 > &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 syncReadJointStatus (const std::vector< uint8_t > &id_list, std::vector< std::array< uint32_t, 2 > > &data_array_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 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
 

Additional Inherited Members

- Protected Member Functions inherited from ttl_driver::AbstractStepperDriver
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)
 
- Static Protected Attributes inherited from ttl_driver::AbstractTtlDriver
static constexpr int PING_WRONG_MODEL_NUMBER = 30
 

Detailed Description

template<typename reg_type = Ned3ProStepperReg>
class ttl_driver::Ned3ProStepperDriver< reg_type >

The Ned3ProStepperDriver class.

Definition at line 40 of file ned3pro_stepper_driver.hpp.

Constructor & Destructor Documentation

◆ Ned3ProStepperDriver()

template<typename reg_type >
ttl_driver::Ned3ProStepperDriver< reg_type >::Ned3ProStepperDriver ( std::shared_ptr< dynamixel::PortHandler >  portHandler,
std::shared_ptr< dynamixel::PacketHandler >  packetHandler 
)

Member Function Documentation

◆ changeId()

template<typename reg_type >
int ttl_driver::Ned3ProStepperDriver< reg_type >::changeId ( uint8_t  id,
uint8_t  new_id 
)
overridevirtual

Ned3ProStepperDriver<reg_type>::changeId.

Parameters
id
new_id
Returns

Implements ttl_driver::AbstractMotorDriver.

Definition at line 157 of file ned3pro_stepper_driver.hpp.

◆ checkModelNumber()

template<typename reg_type >
int ttl_driver::Ned3ProStepperDriver< reg_type >::checkModelNumber ( uint8_t  id)
overridevirtual

◆ factoryCalibration()

template<typename reg_type >
int ttl_driver::Ned3ProStepperDriver< reg_type >::factoryCalibration ( const uint8_t  id,
const uint32_t &  command 
)
virtual

Ned3ProStepperDriver<reg_type>::factoryCalibration.

Parameters
id
control
Returns

Reimplemented from ttl_driver::AbstractStepperDriver.

Definition at line 584 of file ned3pro_stepper_driver.hpp.

◆ interpretHomingData()

template<typename reg_type >
common::model::EStepperCalibrationStatus ttl_driver::Ned3ProStepperDriver< reg_type >::interpretHomingData ( uint8_t  status) const
overridevirtual

AbstractStepperDriver::interpretHomingData.

Parameters
status
Returns

Reimplemented from ttl_driver::AbstractStepperDriver.

Definition at line 526 of file ned3pro_stepper_driver.hpp.

◆ readControlMode()

template<typename reg_type >
int ttl_driver::Ned3ProStepperDriver< reg_type >::readControlMode ( uint8_t  id,
uint8_t &  operating_mode 
)
overridevirtual

Implements ttl_driver::AbstractMotorDriver.

Definition at line 657 of file ned3pro_stepper_driver.hpp.

◆ readEncAngle()

template<typename reg_type >
int ttl_driver::Ned3ProStepperDriver< reg_type >::readEncAngle ( uint8_t  id,
const uint32_t &  enc_angle 
)

Ned3ProStepperDriver<reg_type>::readEncAngle.

Parameters
id
enc_angle
Returns

Definition at line 619 of file ned3pro_stepper_driver.hpp.

◆ readFirmwareRunning()

template<typename reg_type >
int ttl_driver::Ned3ProStepperDriver< reg_type >::readFirmwareRunning ( uint8_t  id,
bool &  is_running 
)
overridevirtual

Ned3ProStepperDriver<reg_type>::readFirmwareRunning.

Parameters
id
is_running
Returns

Implements ttl_driver::AbstractStepperDriver.

Definition at line 631 of file ned3pro_stepper_driver.hpp.

◆ readFirmwareVersion()

template<typename reg_type >
int ttl_driver::Ned3ProStepperDriver< reg_type >::readFirmwareVersion ( uint8_t  id,
std::string &  version 
)
overridevirtual

Ned3ProStepperDriver<reg_type>::readFirmwareVersion.

Parameters
id
version
Returns

Implements ttl_driver::AbstractTtlDriver.

Definition at line 196 of file ned3pro_stepper_driver.hpp.

◆ readHomingStatus()

template<typename reg_type >
int ttl_driver::Ned3ProStepperDriver< reg_type >::readHomingStatus ( uint8_t  id,
uint8_t &  status 
)
virtual

Implements ttl_driver::AbstractStepperDriver.

Definition at line 726 of file ned3pro_stepper_driver.hpp.

◆ readHwErrorStatus()

template<typename reg_type >
int ttl_driver::Ned3ProStepperDriver< reg_type >::readHwErrorStatus ( uint8_t  id,
uint8_t &  hardware_error_status 
)
overridevirtual

Ned3ProStepperDriver<reg_type>::readHwErrorStatus.

Parameters
id
hardware_error_status
Returns

Implements ttl_driver::AbstractTtlDriver.

Definition at line 340 of file ned3pro_stepper_driver.hpp.

◆ readMaxPosition()

template<typename reg_type >
int ttl_driver::Ned3ProStepperDriver< reg_type >::readMaxPosition ( uint8_t  id,
uint32_t &  max_pos 
)
overridevirtual

Implements ttl_driver::AbstractMotorDriver.

Definition at line 649 of file ned3pro_stepper_driver.hpp.

◆ readMinPosition()

template<typename reg_type >
int ttl_driver::Ned3ProStepperDriver< reg_type >::readMinPosition ( uint8_t  id,
uint32_t &  min_pos 
)
overridevirtual

Implements ttl_driver::AbstractMotorDriver.

Definition at line 641 of file ned3pro_stepper_driver.hpp.

◆ readPosition()

template<typename reg_type >
int ttl_driver::Ned3ProStepperDriver< reg_type >::readPosition ( uint8_t  id,
uint32_t &  present_position 
)
overridevirtual

Ned3ProStepperDriver<reg_type>::readPosition.

Parameters
id
present_position
Returns

Implements ttl_driver::AbstractMotorDriver.

Definition at line 289 of file ned3pro_stepper_driver.hpp.

◆ readStatus()

template<typename reg_type >
int ttl_driver::Ned3ProStepperDriver< reg_type >::readStatus ( uint8_t  id,
const uint32_t &  status 
)

Ned3ProStepperDriver<reg_type>::readStatus.

Parameters
id
status
Returns

Definition at line 596 of file ned3pro_stepper_driver.hpp.

◆ readTemperature()

template<typename reg_type >
int ttl_driver::Ned3ProStepperDriver< reg_type >::readTemperature ( uint8_t  id,
uint8_t &  temperature 
)
overridevirtual

Ned3ProStepperDriver<reg_type>::readTemperature.

Parameters
id
temperature
Returns

Implements ttl_driver::AbstractTtlDriver.

Definition at line 313 of file ned3pro_stepper_driver.hpp.

◆ readVelocity()

template<typename reg_type >
int ttl_driver::Ned3ProStepperDriver< reg_type >::readVelocity ( uint8_t  id,
uint32_t &  present_velocity 
)
overridevirtual

Ned3ProStepperDriver<reg_type>::readVelocity.

Parameters
id
present_velocity
Returns

Implements ttl_driver::AbstractMotorDriver.

Definition at line 301 of file ned3pro_stepper_driver.hpp.

◆ readVelocityProfile()

template<typename reg_type >
int ttl_driver::Ned3ProStepperDriver< reg_type >::readVelocityProfile ( uint8_t  id,
std::vector< uint32_t > &  data_list 
)
overridevirtual

Implements ttl_driver::AbstractMotorDriver.

Definition at line 665 of file ned3pro_stepper_driver.hpp.

◆ readVoltage()

template<typename reg_type >
int ttl_driver::Ned3ProStepperDriver< reg_type >::readVoltage ( uint8_t  id,
double &  voltage 
)
overridevirtual

Ned3ProStepperDriver<reg_type>::readVoltage.

Parameters
id
voltage
Returns

Implements ttl_driver::AbstractTtlDriver.

Definition at line 325 of file ned3pro_stepper_driver.hpp.

◆ startHoming()

template<typename reg_type >
int ttl_driver::Ned3ProStepperDriver< reg_type >::startHoming ( uint8_t  id)
virtual

Implements ttl_driver::AbstractStepperDriver.

Definition at line 709 of file ned3pro_stepper_driver.hpp.

◆ str()

template<typename reg_type >
std::string ttl_driver::Ned3ProStepperDriver< reg_type >::str
overridevirtual

◆ syncReadFirmwareVersion()

template<typename reg_type >
int ttl_driver::Ned3ProStepperDriver< reg_type >::syncReadFirmwareVersion ( const std::vector< uint8_t > &  id_list,
std::vector< std::string > &  firmware_list 
)
overridevirtual

Ned3ProStepperDriver<reg_type>::syncReadFirmwareVersion.

Parameters
id_list
firmware_list
Returns

Implements ttl_driver::AbstractTtlDriver.

Definition at line 418 of file ned3pro_stepper_driver.hpp.

◆ syncReadHomingAbsPosition()

template<typename reg_type >
int ttl_driver::Ned3ProStepperDriver< reg_type >::syncReadHomingAbsPosition ( const std::vector< uint8_t > &  id_list,
std::vector< uint32_t > &  abs_position 
)
virtual

Implements ttl_driver::AbstractStepperDriver.

Definition at line 733 of file ned3pro_stepper_driver.hpp.

◆ syncReadHomingStatus()

template<typename reg_type >
int ttl_driver::Ned3ProStepperDriver< reg_type >::syncReadHomingStatus ( const std::vector< uint8_t > &  id_list,
std::vector< uint8_t > &  status_list 
)
virtual

Implements ttl_driver::AbstractStepperDriver.

Definition at line 602 of file ned3pro_stepper_driver.hpp.

◆ syncReadHwErrorStatus()

template<typename reg_type >
int ttl_driver::Ned3ProStepperDriver< reg_type >::syncReadHwErrorStatus ( const std::vector< uint8_t > &  id_list,
std::vector< uint8_t > &  hw_error_list 
)
overridevirtual

Ned3ProStepperDriver<reg_type>::syncReadHwErrorStatus.

Parameters
id_list
hw_error_list
Returns

Implements ttl_driver::AbstractTtlDriver.

Definition at line 511 of file ned3pro_stepper_driver.hpp.

◆ syncReadHwStatus()

template<typename reg_type >
int ttl_driver::Ned3ProStepperDriver< reg_type >::syncReadHwStatus ( const std::vector< uint8_t > &  id_list,
std::vector< std::pair< double, uint8_t >> &  data_list 
)
override

Ned3ProStepperDriver<reg_type>::syncReadHwStatus.

Parameters
id_list
data_list
Returns

Definition at line 482 of file ned3pro_stepper_driver.hpp.

◆ syncReadJointStatus()

template<typename reg_type >
int ttl_driver::Ned3ProStepperDriver< reg_type >::syncReadJointStatus ( const std::vector< uint8_t > &  id_list,
std::vector< std::array< uint32_t, 2 >> &  data_array_list 
)
override

Ned3ProStepperDriver<reg_type>::syncReadJointStatus.

Parameters
id_list
data_array_list
Returns
reads both position and velocity if torque is enabled. Reads only position otherwise

Definition at line 377 of file ned3pro_stepper_driver.hpp.

◆ syncReadPosition()

template<typename reg_type >
int ttl_driver::Ned3ProStepperDriver< reg_type >::syncReadPosition ( const std::vector< uint8_t > &  id_list,
std::vector< uint32_t > &  position_list 
)
overridevirtual

Ned3ProStepperDriver<reg_type>::syncReadPosition.

Parameters
id_list
position_list
Returns

Implements ttl_driver::AbstractMotorDriver.

Definition at line 352 of file ned3pro_stepper_driver.hpp.

◆ syncReadRawVoltage()

template<typename reg_type >
int ttl_driver::Ned3ProStepperDriver< reg_type >::syncReadRawVoltage ( const std::vector< uint8_t > &  id_list,
std::vector< double > &  voltage_list 
)
overridevirtual

Ned3ProStepperDriver<reg_type>::syncReadRawVoltage.

Parameters
id_list
voltage_list
Returns

Implements ttl_driver::AbstractTtlDriver.

Definition at line 465 of file ned3pro_stepper_driver.hpp.

◆ syncReadTemperature()

template<typename reg_type >
int ttl_driver::Ned3ProStepperDriver< reg_type >::syncReadTemperature ( const std::vector< uint8_t > &  id_list,
std::vector< uint8_t > &  temperature_list 
)
overridevirtual

Ned3ProStepperDriver<reg_type>::syncReadTemperature.

Parameters
id_list
temperature_list
Returns

Implements ttl_driver::AbstractTtlDriver.

Definition at line 436 of file ned3pro_stepper_driver.hpp.

◆ syncReadVelocity()

template<typename reg_type >
int ttl_driver::Ned3ProStepperDriver< reg_type >::syncReadVelocity ( const std::vector< uint8_t > &  id_list,
std::vector< uint32_t > &  velocity_list 
)
overridevirtual

Ned3ProStepperDriver<reg_type>::syncReadVelocity.

Parameters
id_list
velocity_list
Returns

Implements ttl_driver::AbstractMotorDriver.

Definition at line 364 of file ned3pro_stepper_driver.hpp.

◆ syncReadVoltage()

template<typename reg_type >
int ttl_driver::Ned3ProStepperDriver< reg_type >::syncReadVoltage ( const std::vector< uint8_t > &  id_list,
std::vector< double > &  voltage_list 
)
overridevirtual

Ned3ProStepperDriver<reg_type>::syncReadVoltage.

Parameters
id_list
voltage_list
Returns

Implements ttl_driver::AbstractTtlDriver.

Definition at line 448 of file ned3pro_stepper_driver.hpp.

◆ syncWriteHomingAbsPosition()

template<typename reg_type >
int ttl_driver::Ned3ProStepperDriver< reg_type >::syncWriteHomingAbsPosition ( const std::vector< uint8_t > &  id_list,
const std::vector< uint32_t > &  abs_position 
)
virtual

Implements ttl_driver::AbstractStepperDriver.

Definition at line 740 of file ned3pro_stepper_driver.hpp.

◆ syncWritePositionGoal()

template<typename reg_type >
int ttl_driver::Ned3ProStepperDriver< reg_type >::syncWritePositionGoal ( const std::vector< uint8_t > &  id_list,
const std::vector< uint32_t > &  position_list 
)
overridevirtual

Ned3ProStepperDriver<reg_type>::syncWritePositionGoal.

Parameters
id_list
position_list
Returns

Implements ttl_driver::AbstractMotorDriver.

Definition at line 263 of file ned3pro_stepper_driver.hpp.

◆ syncWriteTorquePercentage()

template<typename reg_type >
int ttl_driver::Ned3ProStepperDriver< reg_type >::syncWriteTorquePercentage ( const std::vector< uint8_t > &  id_list,
const std::vector< uint8_t > &  torque_percentage_list 
)
overridevirtual

Ned3ProStepperDriver<reg_type>::syncWriteTorquePercentage.

Parameters
id_list
torque_percentage_list
Returns

Implements ttl_driver::AbstractMotorDriver.

Definition at line 251 of file ned3pro_stepper_driver.hpp.

◆ syncWriteVelocityGoal()

template<typename reg_type >
int ttl_driver::Ned3ProStepperDriver< reg_type >::syncWriteVelocityGoal ( const std::vector< uint8_t > &  id_list,
const std::vector< uint32_t > &  velocity_list 
)
overridevirtual

Ned3ProStepperDriver<reg_type>::syncWriteVelocityGoal.

Parameters
id_list
velocity_list
Returns

Implements ttl_driver::AbstractMotorDriver.

Definition at line 275 of file ned3pro_stepper_driver.hpp.

◆ velocityUnit()

template<typename reg_type >
float ttl_driver::Ned3ProStepperDriver< reg_type >::velocityUnit ( ) const
overridevirtual

writeVelocityGoal: define the unit of the velocity in RPM

Implements ttl_driver::AbstractStepperDriver.

Definition at line 748 of file ned3pro_stepper_driver.hpp.

◆ writeAccelerationProfile()

template<typename reg_type >
int ttl_driver::Ned3ProStepperDriver< reg_type >::writeAccelerationProfile ( uint8_t  id,
const uint32_t &  acceleration_profile 
)

Ned3ProStepperDriver<reg_type>::writeAccelerationProfile.

Parameters
id
acceleration_profile
Returns

Definition at line 572 of file ned3pro_stepper_driver.hpp.

◆ writeControlMode()

template<typename reg_type >
int ttl_driver::Ned3ProStepperDriver< reg_type >::writeControlMode ( uint8_t  id,
uint8_t  operating_mode 
)
overridevirtual

Ned3ProStepperDriver<reg_type>::writeOperatingMode.

Parameters
id
operating_mode
Returns

Implements ttl_driver::AbstractMotorDriver.

Definition at line 548 of file ned3pro_stepper_driver.hpp.

◆ writeHomingSetup()

template<typename reg_type >
int ttl_driver::Ned3ProStepperDriver< reg_type >::writeHomingSetup ( uint8_t  id,
uint8_t  direction,
uint8_t  stall_threshold 
)
virtual

Implements ttl_driver::AbstractStepperDriver.

Definition at line 717 of file ned3pro_stepper_driver.hpp.

◆ writePositionGoal()

template<typename reg_type >
int ttl_driver::Ned3ProStepperDriver< reg_type >::writePositionGoal ( uint8_t  id,
uint32_t  position 
)
overridevirtual

Ned3ProStepperDriver<reg_type>::writePositionGoal.

Parameters
id
position
Returns

Implements ttl_driver::AbstractMotorDriver.

Definition at line 226 of file ned3pro_stepper_driver.hpp.

◆ writeTorquePercentage()

template<typename reg_type >
int ttl_driver::Ned3ProStepperDriver< reg_type >::writeTorquePercentage ( uint8_t  id,
uint8_t  torque_percentage 
)
overridevirtual

Ned3ProStepperDriver<reg_type>::writeTorquePercentage.

Parameters
id
torque_enable
Returns

Implements ttl_driver::AbstractMotorDriver.

Definition at line 214 of file ned3pro_stepper_driver.hpp.

◆ writeVelocityGoal()

template<typename reg_type >
int ttl_driver::Ned3ProStepperDriver< reg_type >::writeVelocityGoal ( uint8_t  id,
uint32_t  velocity 
)
overridevirtual

Ned3ProStepperDriver<reg_type>::writeVelocityGoal.

Parameters
id
velocity
Returns

Implements ttl_driver::AbstractMotorDriver.

Definition at line 239 of file ned3pro_stepper_driver.hpp.

◆ writeVelocityProfile() [1/2]

template<typename reg_type >
int ttl_driver::Ned3ProStepperDriver< reg_type >::writeVelocityProfile ( uint8_t  id,
const std::vector< uint32_t > &  data_list 
)
overridevirtual

Implements ttl_driver::AbstractMotorDriver.

Definition at line 673 of file ned3pro_stepper_driver.hpp.

◆ writeVelocityProfile() [2/2]

template<typename reg_type >
int ttl_driver::Ned3ProStepperDriver< reg_type >::writeVelocityProfile ( uint8_t  id,
const uint32_t &  velocity_profile 
)

Ned3ProStepperDriver<reg_type>::writeVelocityProfile.

Parameters
id
velocity_profile
Returns

Definition at line 560 of file ned3pro_stepper_driver.hpp.


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


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