Classes | Public Member Functions | Private Member Functions | Private Attributes | Static Private Attributes | List of all members
ttl_driver::TtlManager Class Reference

The TtlManager class manages the different motor drivers connected on the TTL bus it is used by ttl_interface_core to send or receive data to the ttl bus it also manages the lifecycle of all motors driver (do we need to add also the end effector driver in it ?) More...

#include <ttl_manager.hpp>

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

Classes

class  CalibrationMachineState
 
struct  GetJointsStepperDriverResult
 

Public Member Functions

int addHardwareComponent (std::shared_ptr< common::model::AbstractHardwareState > &&state) override
 TtlManager::addHardwareComponent add hardware component like joint, ee, tool... to ttl manager. More...
 
int changeId (common::model::EHardwareType motor_type, uint8_t old_id, uint8_t new_id)
 TtlManager::changeId. More...
 
void executeJointTrajectoryCmd (std::vector< std::pair< uint8_t, uint32_t > > cmd_vec)
 TtlManager::executeJointTrajectoryCmd. More...
 
int getAllIdsOnBus (std::vector< uint8_t > &id_list)
 TtlManager::getAllIdsOnDxlBus. More...
 
void getBusState (bool &connection_state, std::vector< uint8_t > &motor_id, std::string &debug_msg) const override
 TtlManager::getBusState. More...
 
int32_t getCalibrationResult (uint8_t id) const override
 TtlManager::getCalibrationResult. More...
 
common::model::EStepperCalibrationStatus getCalibrationStatus () const override
 TtlManager::getCalibrationStatus. More...
 
bool getCollisionStatus () const
 TtlManager::getCollisionStatus. More...
 
std::vector< std::shared_ptr< common::model::ConveyorState > > getConveyorsStates () const
 
std::string getErrorMessage () const override
 TtlManager::getErrorMessage. More...
 
std::shared_ptr< common::model::AbstractHardwareState > getHardwareState (uint8_t motor_id) const
 TtlManager::getHardwareState. More...
 
int getLedState () const
 
std::vector< std::shared_ptr< common::model::JointState > > getMotorsStates () const
 TtlManager::getMotorsStates. More...
 
size_t getNbMotors () const override
 TtlManager::getNbMotors. More...
 
uint32_t getPosition (const common::model::JointState &motor_state)
 TtlManager::getPosition. More...
 
std::vector< uint8_t > getRemovedMotorList () const override
 TtlManager::getRemovedMotorList. More...
 
bool hasEndEffector () const
 TtlManager::hasEndEffector. More...
 
bool init (ros::NodeHandle &nh) override
 TtlManager::init. More...
 
bool isCalibrationInProgress () const
 TtlManager::isCalibrationInProgress. More...
 
bool isConnectionOk () const override
 TtlManager::isConnectionOk. More...
 
bool needCalibration () const
 TtlManager::needCalibration. More...
 
TtlManageroperator= (const TtlManager &)=delete
 
TtlManageroperator= (TtlManager &&)=delete
 
bool ping (uint8_t id) override
 TtlManager::ping. More...
 
bool readCollisionStatus ()
 TtlManager::readCollisionStatus. More...
 
int readControlMode (uint8_t id, uint8_t &control_mode)
 TtlManager::readControlMode. More...
 
int readCustomCommand (uint8_t id, int32_t reg_address, int &value, int byte_number)
 TtlManager::readCustomCommand. More...
 
bool readEndEffectorStatus ()
 TtlManager::readEndEffectorStatus. More...
 
bool readHardwareStatus ()
 TtlManager::readHardwareStatus. More...
 
bool readHomingAbsPosition ()
 
bool readJointsStatus ()
 TtlManager::readJointsStatus. More...
 
int readMotorPID (uint8_t id, uint16_t &pos_p_gain, uint16_t &pos_i_gain, uint16_t &pos_d_gain, uint16_t &vel_p_gain, uint16_t &vel_i_gain, uint16_t &ff1_gain, uint16_t &ff2_gain)
 TtlManager::readMotorPID. More...
 
int readMoving (uint8_t id, uint8_t &status)
 TtlManager::readMoving. More...
 
uint8_t readNed3ProSteppersStatus ()
 
uint8_t readSteppersStatus ()
 TtlManager::readCalibrationStatus : reads specific steppers related information (ned2 only) More...
 
int readVelocityProfile (uint8_t id, uint32_t &v_start, uint32_t &a_1, uint32_t &v_1, uint32_t &a_max, uint32_t &v_max, uint32_t &d_max, uint32_t &d_1, uint32_t &v_stop)
 TtlManager::readVelocityProfile. More...
 
int rebootHardware (uint8_t id)
 TtlManager::rebootHardware. More...
 
void removeHardwareComponent (uint8_t id) override
 TtlManager::removeHardwareComponent. More...
 
void resetCalibration () override
 TtlManager::resetCalibration. More...
 
void resetTorques ()
 TtlManager::resetTorques. More...
 
int scanAndCheck () override
 TtlManager::scanAndCheck. More...
 
int sendCustomCommand (uint8_t id, int reg_address, int value, int byte_number)
 TtlManager::sendCustomCommand. More...
 
int setLeds (int led)
 TtlManager::setLeds. More...
 
void startCalibration () override
 TtlManager::startCalibration. More...
 
 TtlManager ()=delete
 
 TtlManager (const TtlManager &)=delete
 
 TtlManager (ros::NodeHandle &nh)
 TtlManager::TtlManager. More...
 
 TtlManager (TtlManager &&)=delete
 
int writeSingleCommand (std::unique_ptr< common::model::AbstractTtlSingleMotorCmd > &&cmd)
 TtlManager::writeSingleCommand. More...
 
int writeSynchronizeCommand (std::unique_ptr< common::model::AbstractTtlSynchronizeMotorCmd > &&cmd)
 TtlManager::writeSynchronizeCommand. More...
 
 ~TtlManager () override
 TtlManager::~TtlManager. More...
 

Private Member Functions

void addHardwareDriver (common::model::EHardwareType hardware_type) override
 TtlManager::addHardwareDriver. More...
 
bool checkCollision ()
 TtlManager::checkCollision. More...
 
GetJointsStepperDriverResult getJointsStepperDriver ()
 : Return the driver of the joints More...
 
bool isMotorType (common::model::EHardwareType type)
 TtlManager::isMotorType. More...
 
void readFakeConfig (bool use_simu_gripper, bool use_simu_conveyor)
 TtlManager::readFakeConfig. More...
 
template<typename Reg >
void retrieveFakeMotorData (const std::string &current_ns, std::map< uint8_t, Reg > &fake_params)
 TtlManager::retrieveFakeMotorData. More...
 
int setupCommunication () override
 TtlManager::setupCommunication. More...
 

Private Attributes

std::vector< uint8_t > _all_ids_connected
 
int _baudrate {1000000}
 
CalibrationMachineState _calib_machine_state
 
common::model::EStepperCalibrationStatus _calibration_status {common::model::EStepperCalibrationStatus::OK}
 
ros::Publisher _calibration_status_publisher
 
bool _collision_status {false}
 
std::vector< uint8_t > _conveyor_list
 
std::string _debug_error_message
 
std::shared_ptr< ttl_driver::AbstractTtlDriver_default_ttl_driver
 
std::string _device_name
 
std::map< common::model::EHardwareType, std::shared_ptr< ttl_driver::AbstractTtlDriver > > _driver_map
 
uint32_t _end_effector_fail_counter_read {0}
 
std::shared_ptr< FakeTtlData_fake_data
 
uint32_t _hw_fail_counter_read {0}
 
std::map< common::model::EHardwareType, std::vector< uint8_t > > _ids_map
 
bool _is_connection_ok {false}
 
bool _isRealCollision {true}
 
bool _isWrongAction {false}
 
double _last_collision_detection_activating {0.0}
 
std::string _led_motor_type_cfg
 
int _led_state = 0
 
ros::NodeHandle _nh
 
std::shared_ptr< dynamixel::PacketHandler > _packetHandler
 
std::shared_ptr< dynamixel::PortHandler > _portHandler
 
std::vector< uint8_t > _position_goal_ids
 
std::vector< uint32_t > _position_goal_params
 
std::vector< uint32_t > _position_list
 
std::vector< uint8_t > _removed_motor_id_list
 
bool _simulation_mode {false}
 
std::map< uint8_t, std::shared_ptr< common::model::AbstractHardwareState > > _state_map
 
std::mutex _sync_mutex
 

Static Private Attributes

static constexpr uint32_t MAX_HW_FAILURE = 150
 
static constexpr uint32_t MAX_READ_EE_FAILURE = 150
 

Detailed Description

The TtlManager class manages the different motor drivers connected on the TTL bus it is used by ttl_interface_core to send or receive data to the ttl bus it also manages the lifecycle of all motors driver (do we need to add also the end effector driver in it ?)

Parameters for Stepper

Definition at line 85 of file ttl_manager.hpp.

Constructor & Destructor Documentation

◆ TtlManager() [1/4]

ttl_driver::TtlManager::TtlManager ( )
delete

◆ TtlManager() [2/4]

ttl_driver::TtlManager::TtlManager ( ros::NodeHandle &  nh)

TtlManager::TtlManager.

Definition at line 80 of file ttl_manager.cpp.

◆ ~TtlManager()

ttl_driver::TtlManager::~TtlManager ( )
override

TtlManager::~TtlManager.

Definition at line 93 of file ttl_manager.cpp.

◆ TtlManager() [3/4]

ttl_driver::TtlManager::TtlManager ( const TtlManager )
delete

◆ TtlManager() [4/4]

ttl_driver::TtlManager::TtlManager ( TtlManager &&  )
delete

Member Function Documentation

◆ addHardwareComponent()

int ttl_driver::TtlManager::addHardwareComponent ( std::shared_ptr< common::model::AbstractHardwareState > &&  state)
override

TtlManager::addHardwareComponent add hardware component like joint, ee, tool... to ttl manager.

Parameters
state

Definition at line 207 of file ttl_manager.cpp.

◆ addHardwareDriver()

void ttl_driver::TtlManager::addHardwareDriver ( common::model::EHardwareType  hardware_type)
overrideprivate

TtlManager::addHardwareDriver.

Parameters
hardware_type

Definition at line 2137 of file ttl_manager.cpp.

◆ changeId()

int ttl_driver::TtlManager::changeId ( common::model::EHardwareType  motor_type,
uint8_t  old_id,
uint8_t  new_id 
)

TtlManager::changeId.

Parameters
motor_type
old_id
new_id
Returns

Definition at line 338 of file ttl_manager.cpp.

◆ checkCollision()

bool ttl_driver::TtlManager::checkCollision ( )
private

TtlManager::checkCollision.

Returns
false if read failed. Careful, there can be lots of errors as the TTL bus is not perfect better not use the return status

Definition at line 890 of file ttl_manager.cpp.

◆ executeJointTrajectoryCmd()

void ttl_driver::TtlManager::executeJointTrajectoryCmd ( std::vector< std::pair< uint8_t, uint32_t > >  cmd_vec)

TtlManager::executeJointTrajectoryCmd.

Parameters
cmd_vec

Definition at line 1948 of file ttl_manager.cpp.

◆ getAllIdsOnBus()

int ttl_driver::TtlManager::getAllIdsOnBus ( std::vector< uint8_t > &  id_list)

TtlManager::getAllIdsOnDxlBus.

Parameters
id_list
Returns
The scan method is identical to all drivers, we can just use the first one (same behaviour in ping with ping method)

Definition at line 1424 of file ttl_manager.cpp.

◆ getBusState()

void ttl_driver::TtlManager::getBusState ( bool &  connection_state,
std::vector< uint8_t > &  motor_id,
std::string &  debug_msg 
) const
override

TtlManager::getBusState.

Parameters
connection_state
motor_id
debug_msg

Definition at line 2076 of file ttl_manager.cpp.

◆ getCalibrationResult()

int32_t ttl_driver::TtlManager::getCalibrationResult ( uint8_t  motor_id) const
override

TtlManager::getCalibrationResult.

Parameters
motor_id
Returns

Definition at line 2058 of file ttl_manager.cpp.

◆ getCalibrationStatus()

common::model::EStepperCalibrationStatus ttl_driver::TtlManager::getCalibrationStatus ( ) const
inlineoverride

TtlManager::getCalibrationStatus.

Returns

Definition at line 363 of file ttl_manager.hpp.

◆ getCollisionStatus()

bool ttl_driver::TtlManager::getCollisionStatus ( ) const
inline

TtlManager::getCollisionStatus.

Returns

Definition at line 462 of file ttl_manager.hpp.

◆ getConveyorsStates()

std::vector< std::shared_ptr< ConveyorState > > ttl_driver::TtlManager::getConveyorsStates ( ) const

Definition at line 2102 of file ttl_manager.cpp.

◆ getErrorMessage()

std::string ttl_driver::TtlManager::getErrorMessage ( ) const
inlineoverride

TtlManager::getErrorMessage.

Returns

Definition at line 352 of file ttl_manager.hpp.

◆ getHardwareState()

std::shared_ptr< common::model::AbstractHardwareState > ttl_driver::TtlManager::getHardwareState ( uint8_t  motor_id) const

TtlManager::getHardwareState.

Parameters
motor_id
Returns

Definition at line 2121 of file ttl_manager.cpp.

◆ getJointsStepperDriver()

TtlManager::GetJointsStepperDriverResult ttl_driver::TtlManager::getJointsStepperDriver ( )
private

: Return the driver of the joints

All stepper joints should have the same type of driver

Definition at line 2260 of file ttl_manager.cpp.

◆ getLedState()

int ttl_driver::TtlManager::getLedState ( ) const

◆ getMotorsStates()

std::vector< std::shared_ptr< JointState > > ttl_driver::TtlManager::getMotorsStates ( ) const

TtlManager::getMotorsStates.

Returns
only the joints states

Definition at line 2087 of file ttl_manager.cpp.

◆ getNbMotors()

size_t ttl_driver::TtlManager::getNbMotors ( ) const
inlineoverride

TtlManager::getNbMotors.

Returns

Definition at line 332 of file ttl_manager.hpp.

◆ getPosition()

uint32_t ttl_driver::TtlManager::getPosition ( const common::model::JointState &  motor_state)

TtlManager::getPosition.

Parameters
motor_state
Returns

Definition at line 566 of file ttl_manager.cpp.

◆ getRemovedMotorList()

std::vector< uint8_t > ttl_driver::TtlManager::getRemovedMotorList ( ) const
inlineoverride

TtlManager::getRemovedMotorList.

Returns

Definition at line 342 of file ttl_manager.hpp.

◆ hasEndEffector()

bool ttl_driver::TtlManager::hasEndEffector ( ) const
inline

TtlManager::hasEndEffector.

Returns

Definition at line 394 of file ttl_manager.hpp.

◆ init()

bool ttl_driver::TtlManager::init ( ros::NodeHandle &  nh)
override

TtlManager::init.

Parameters
nh
Returns

Definition at line 107 of file ttl_manager.cpp.

◆ isCalibrationInProgress()

bool ttl_driver::TtlManager::isCalibrationInProgress ( ) const
inline

TtlManager::isCalibrationInProgress.

Returns

Definition at line 384 of file ttl_manager.hpp.

◆ isConnectionOk()

bool ttl_driver::TtlManager::isConnectionOk ( ) const
inlineoverride

TtlManager::isConnectionOk.

Returns

Definition at line 322 of file ttl_manager.hpp.

◆ isMotorType()

bool ttl_driver::TtlManager::isMotorType ( common::model::EHardwareType  type)
private

TtlManager::isMotorType.

Parameters
type
Returns
true
false

Definition at line 321 of file ttl_manager.cpp.

◆ needCalibration()

bool ttl_driver::TtlManager::needCalibration ( ) const
inline

TtlManager::needCalibration.

Returns

Definition at line 373 of file ttl_manager.hpp.

◆ operator=() [1/2]

TtlManager& ttl_driver::TtlManager::operator= ( const TtlManager )
delete

◆ operator=() [2/2]

TtlManager& ttl_driver::TtlManager::operator= ( TtlManager &&  )
delete

◆ ping()

bool ttl_driver::TtlManager::ping ( uint8_t  id)
override

TtlManager::ping.

Parameters
id
Returns
The ping method is identical to all drivers, we can just use the first one (same behaviour in getAllIdsOnBus with scan method)

Definition at line 464 of file ttl_manager.cpp.

◆ readCollisionStatus()

bool ttl_driver::TtlManager::readCollisionStatus ( )

TtlManager::readCollisionStatus.

Returns

Definition at line 973 of file ttl_manager.cpp.

◆ readControlMode()

int ttl_driver::TtlManager::readControlMode ( uint8_t  id,
uint8_t &  control_mode 
)

TtlManager::readControlMode.

Parameters
id
control_mode
Returns

Definition at line 1791 of file ttl_manager.cpp.

◆ readCustomCommand()

int ttl_driver::TtlManager::readCustomCommand ( uint8_t  id,
int32_t  reg_address,
int &  value,
int  byte_number 
)

TtlManager::readCustomCommand.

Parameters
id
reg_address
value
byte_number
Returns

Definition at line 1585 of file ttl_manager.cpp.

◆ readEndEffectorStatus()

bool ttl_driver::TtlManager::readEndEffectorStatus ( )

TtlManager::readEndEffectorStatus.

Returns

Definition at line 780 of file ttl_manager.cpp.

◆ readFakeConfig()

void ttl_driver::TtlManager::readFakeConfig ( bool  use_simu_gripper,
bool  use_simu_conveyor 
)
private

TtlManager::readFakeConfig.

Definition at line 2193 of file ttl_manager.cpp.

◆ readHardwareStatus()

bool ttl_driver::TtlManager::readHardwareStatus ( )

TtlManager::readHardwareStatus.

Definition at line 1040 of file ttl_manager.cpp.

◆ readHomingAbsPosition()

bool ttl_driver::TtlManager::readHomingAbsPosition ( )

Definition at line 601 of file ttl_manager.cpp.

◆ readJointsStatus()

bool ttl_driver::TtlManager::readJointsStatus ( )

TtlManager::readJointsStatus.

Returns

Definition at line 671 of file ttl_manager.cpp.

◆ readMotorPID()

int ttl_driver::TtlManager::readMotorPID ( uint8_t  id,
uint16_t &  pos_p_gain,
uint16_t &  pos_i_gain,
uint16_t &  pos_d_gain,
uint16_t &  vel_p_gain,
uint16_t &  vel_i_gain,
uint16_t &  ff1_gain,
uint16_t &  ff2_gain 
)

TtlManager::readMotorPID.

Parameters
id
pos_p_gain
pos_i_gain
pos_d_gain
vel_p_gain
vel_i_gain
ff1_gain
ff2_gain
Returns

Definition at line 1635 of file ttl_manager.cpp.

◆ readMoving()

int ttl_driver::TtlManager::readMoving ( uint8_t  id,
uint8_t &  status 
)

TtlManager::readMoving.

Parameters
id
status
Returns

Definition at line 1752 of file ttl_manager.cpp.

◆ readNed3ProSteppersStatus()

uint8_t ttl_driver::TtlManager::readNed3ProSteppersStatus ( )

Definition at line 1324 of file ttl_manager.cpp.

◆ readSteppersStatus()

uint8_t ttl_driver::TtlManager::readSteppersStatus ( )

TtlManager::readCalibrationStatus : reads specific steppers related information (ned2 only)

Returns

Definition at line 1161 of file ttl_manager.cpp.

◆ readVelocityProfile()

int ttl_driver::TtlManager::readVelocityProfile ( uint8_t  id,
uint32_t &  v_start,
uint32_t &  a_1,
uint32_t &  v_1,
uint32_t &  a_max,
uint32_t &  v_max,
uint32_t &  d_max,
uint32_t &  d_1,
uint32_t &  v_stop 
)

TtlManager::readVelocityProfile.

Parameters
id
v_start
a_1
v_1
a_max
v_max
d_max
d_1
v_stop
Returns

Definition at line 1699 of file ttl_manager.cpp.

◆ rebootHardware()

int ttl_driver::TtlManager::rebootHardware ( uint8_t  hw_id)

TtlManager::rebootHardware.

Parameters
hw_id
Returns

Definition at line 482 of file ttl_manager.cpp.

◆ removeHardwareComponent()

void ttl_driver::TtlManager::removeHardwareComponent ( uint8_t  id)
override

TtlManager::removeHardwareComponent.

Parameters
id

Definition at line 288 of file ttl_manager.cpp.

◆ resetCalibration()

void ttl_driver::TtlManager::resetCalibration ( )
override

TtlManager::resetCalibration.

Definition at line 2025 of file ttl_manager.cpp.

◆ resetTorques()

void ttl_driver::TtlManager::resetTorques ( )

TtlManager::resetTorques.

Returns

Definition at line 526 of file ttl_manager.cpp.

◆ retrieveFakeMotorData()

template<typename Reg >
void ttl_driver::TtlManager::retrieveFakeMotorData ( const std::string &  current_ns,
std::map< uint8_t, Reg > &  fake_params 
)
private

TtlManager::retrieveFakeMotorData.

Parameters
current_ns
fake_params

Definition at line 406 of file ttl_manager.hpp.

◆ scanAndCheck()

int ttl_driver::TtlManager::scanAndCheck ( )
override

TtlManager::scanAndCheck.

Returns

Definition at line 395 of file ttl_manager.cpp.

◆ sendCustomCommand()

int ttl_driver::TtlManager::sendCustomCommand ( uint8_t  id,
int  reg_address,
int  value,
int  byte_number 
)

TtlManager::sendCustomCommand.

Parameters
id
reg_address
value
byte_number
Returns

Definition at line 1535 of file ttl_manager.cpp.

◆ setLeds()

int ttl_driver::TtlManager::setLeds ( int  led)

TtlManager::setLeds.

Parameters
led
Returns

Definition at line 1476 of file ttl_manager.cpp.

◆ setupCommunication()

int ttl_driver::TtlManager::setupCommunication ( )
overrideprivate

TtlManager::setupCommunication.

Returns

Definition at line 150 of file ttl_manager.cpp.

◆ startCalibration()

void ttl_driver::TtlManager::startCalibration ( )
override

TtlManager::startCalibration.

Definition at line 1986 of file ttl_manager.cpp.

◆ writeSingleCommand()

int ttl_driver::TtlManager::writeSingleCommand ( std::unique_ptr< common::model::AbstractTtlSingleMotorCmd > &&  cmd)

TtlManager::writeSingleCommand.

Parameters
cmd
Returns

Definition at line 1898 of file ttl_manager.cpp.

◆ writeSynchronizeCommand()

int ttl_driver::TtlManager::writeSynchronizeCommand ( std::unique_ptr< common::model::AbstractTtlSynchronizeMotorCmd > &&  cmd)

TtlManager::writeSynchronizeCommand.

Parameters
cmd
Returns

Definition at line 1828 of file ttl_manager.cpp.

Member Data Documentation

◆ _all_ids_connected

std::vector<uint8_t> ttl_driver::TtlManager::_all_ids_connected
private

Definition at line 210 of file ttl_manager.hpp.

◆ _baudrate

int ttl_driver::TtlManager::_baudrate {1000000}
private

Definition at line 208 of file ttl_manager.hpp.

◆ _calib_machine_state

CalibrationMachineState ttl_driver::TtlManager::_calib_machine_state
private

Definition at line 311 of file ttl_manager.hpp.

◆ _calibration_status

common::model::EStepperCalibrationStatus ttl_driver::TtlManager::_calibration_status {common::model::EStepperCalibrationStatus::OK}
private

Definition at line 241 of file ttl_manager.hpp.

◆ _calibration_status_publisher

ros::Publisher ttl_driver::TtlManager::_calibration_status_publisher
private

Definition at line 253 of file ttl_manager.hpp.

◆ _collision_status

bool ttl_driver::TtlManager::_collision_status {false}
private

Definition at line 248 of file ttl_manager.hpp.

◆ _conveyor_list

std::vector<uint8_t> ttl_driver::TtlManager::_conveyor_list
private

Definition at line 225 of file ttl_manager.hpp.

◆ _debug_error_message

std::string ttl_driver::TtlManager::_debug_error_message
private

Definition at line 229 of file ttl_manager.hpp.

◆ _default_ttl_driver

std::shared_ptr<ttl_driver::AbstractTtlDriver> ttl_driver::TtlManager::_default_ttl_driver
private

Definition at line 221 of file ttl_manager.hpp.

◆ _device_name

std::string ttl_driver::TtlManager::_device_name
private

Definition at line 207 of file ttl_manager.hpp.

◆ _driver_map

std::map<common::model::EHardwareType, std::shared_ptr<ttl_driver::AbstractTtlDriver> > ttl_driver::TtlManager::_driver_map
private

Definition at line 218 of file ttl_manager.hpp.

◆ _end_effector_fail_counter_read

uint32_t ttl_driver::TtlManager::_end_effector_fail_counter_read {0}
private

Definition at line 232 of file ttl_manager.hpp.

◆ _fake_data

std::shared_ptr<FakeTtlData> ttl_driver::TtlManager::_fake_data
private

Definition at line 244 of file ttl_manager.hpp.

◆ _hw_fail_counter_read

uint32_t ttl_driver::TtlManager::_hw_fail_counter_read {0}
private

Definition at line 231 of file ttl_manager.hpp.

◆ _ids_map

std::map<common::model::EHardwareType, std::vector<uint8_t> > ttl_driver::TtlManager::_ids_map
private

Definition at line 216 of file ttl_manager.hpp.

◆ _is_connection_ok

bool ttl_driver::TtlManager::_is_connection_ok {false}
private

Definition at line 228 of file ttl_manager.hpp.

◆ _isRealCollision

bool ttl_driver::TtlManager::_isRealCollision {true}
private

Definition at line 250 of file ttl_manager.hpp.

◆ _isWrongAction

bool ttl_driver::TtlManager::_isWrongAction {false}
private

Definition at line 251 of file ttl_manager.hpp.

◆ _last_collision_detection_activating

double ttl_driver::TtlManager::_last_collision_detection_activating {0.0}
private

Definition at line 249 of file ttl_manager.hpp.

◆ _led_motor_type_cfg

std::string ttl_driver::TtlManager::_led_motor_type_cfg
private

Definition at line 235 of file ttl_manager.hpp.

◆ _led_state

int ttl_driver::TtlManager::_led_state = 0
private

Definition at line 234 of file ttl_manager.hpp.

◆ _nh

ros::NodeHandle ttl_driver::TtlManager::_nh
private

Definition at line 201 of file ttl_manager.hpp.

◆ _packetHandler

std::shared_ptr<dynamixel::PacketHandler> ttl_driver::TtlManager::_packetHandler
private

Definition at line 203 of file ttl_manager.hpp.

◆ _portHandler

std::shared_ptr<dynamixel::PortHandler> ttl_driver::TtlManager::_portHandler
private

Definition at line 202 of file ttl_manager.hpp.

◆ _position_goal_ids

std::vector<uint8_t> ttl_driver::TtlManager::_position_goal_ids
private

Definition at line 256 of file ttl_manager.hpp.

◆ _position_goal_params

std::vector<uint32_t> ttl_driver::TtlManager::_position_goal_params
private

Definition at line 257 of file ttl_manager.hpp.

◆ _position_list

std::vector<uint32_t> ttl_driver::TtlManager::_position_list
private

Definition at line 255 of file ttl_manager.hpp.

◆ _removed_motor_id_list

std::vector<uint8_t> ttl_driver::TtlManager::_removed_motor_id_list
private

Definition at line 211 of file ttl_manager.hpp.

◆ _simulation_mode

bool ttl_driver::TtlManager::_simulation_mode {false}
private

Definition at line 245 of file ttl_manager.hpp.

◆ _state_map

std::map<uint8_t, std::shared_ptr<common::model::AbstractHardwareState> > ttl_driver::TtlManager::_state_map
private

Definition at line 214 of file ttl_manager.hpp.

◆ _sync_mutex

std::mutex ttl_driver::TtlManager::_sync_mutex
mutableprivate

Definition at line 205 of file ttl_manager.hpp.

◆ MAX_HW_FAILURE

constexpr uint32_t ttl_driver::TtlManager::MAX_HW_FAILURE = 150
staticconstexprprivate

Definition at line 237 of file ttl_manager.hpp.

◆ MAX_READ_EE_FAILURE

constexpr uint32_t ttl_driver::TtlManager::MAX_READ_EE_FAILURE = 150
staticconstexprprivate

Definition at line 238 of file ttl_manager.hpp.


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