Go to the documentation of this file.
20 #ifndef TTL_DRIVER_HPP
21 #define TTL_DRIVER_HPP
23 #include "common/util/util_defs.hpp"
24 #include "common/util/i_bus_manager.hpp"
38 #include "ros/node_handle.h"
41 #include "dynamixel_sdk/dynamixel_sdk.h"
42 #include "niryo_robot_msgs/MotorHeader.h"
43 #include "niryo_robot_msgs/SetInt.h"
44 #include "niryo_robot_msgs/CommandStatus.h"
49 #include "ttl_driver/MotorCommand.h"
51 #include "common/model/dxl_motor_state.hpp"
52 #include "common/model/synchronize_motor_cmd.hpp"
53 #include "common/model/single_motor_cmd.hpp"
54 #include "common/model/stepper_calibration_status_enum.hpp"
55 #include "common/model/conveyor_state.hpp"
98 bool init(ros::NodeHandle &
nh)
override;
100 int addHardwareComponent(std::shared_ptr<common::model::AbstractHardwareState> &&state)
override;
106 bool ping(uint8_t
id)
override;
109 void getBusState(
bool &connection_state, std::vector<uint8_t> &motor_id, std::string &debug_msg)
const override;
114 int changeId(common::model::EHardwareType motor_type, uint8_t old_id, uint8_t new_id);
117 int writeSingleCommand(std::unique_ptr<common::model::AbstractTtlSingleMotorCmd> &&cmd);
126 int readCustomCommand(uint8_t
id, int32_t reg_address,
int &value,
int byte_number);
139 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,
140 uint16_t &vel_i_gain, uint16_t &ff1_gain, uint16_t &ff2_gain);
142 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,
143 uint32_t &d_max, uint32_t &d_1, uint32_t &v_stop);
161 uint32_t
getPosition(
const common::model::JointState &motor_state);
164 std::vector<std::shared_ptr<common::model::JointState>>
getMotorsStates()
const;
165 std::vector<std::shared_ptr<common::model::ConveyorState>>
getConveyorsStates()
const;
166 std::shared_ptr<common::model::AbstractHardwareState>
getHardwareState(uint8_t motor_id)
const;
173 bool changeTool(
int value, std::string &message,
int &status);
181 void readFakeConfig(
bool use_simu_gripper,
bool use_simu_conveyor);
182 template <
typename Reg>
184 std::vector<int> hw_ids = {});
188 bool isMotorType(common::model::EHardwareType type);
194 std::shared_ptr<ttl_driver::AbstractStepperDriver>
driver;
213 std::map<uint8_t, std::shared_ptr<common::model::AbstractHardwareState>>
_state_map;
215 std::map<common::model::EHardwareType, std::vector<uint8_t>>
_ids_map;
217 std::map<common::model::EHardwareType, std::shared_ptr<ttl_driver::AbstractTtlDriver>>
_driver_map;
243 common::model::EStepperCalibrationStatus
_calibration_status{ common::model::EStepperCalibrationStatus::OK };
282 _time = ros::Time::now().toSec();
290 int newState =
static_cast<int>(
s);
294 _time = ros::Time::now().toSec();
295 s =
static_cast<State>(newState);
389 return (
_driver_map.count(common::model::EHardwareType::END_EFFECTOR) ||
390 _driver_map.count(common::model::EHardwareType::NED3PRO_END_EFFECTOR) ||
391 _driver_map.count(common::model::EHardwareType::FAKE_END_EFFECTOR));
399 template <
typename Reg>
401 std::vector<int> hw_ids)
403 if (hw_ids.size() == 0)
405 _nh.getParam(current_ns +
"id", hw_ids);
407 std::vector<int> hw_positions;
408 _nh.getParam(current_ns +
"position", hw_positions);
409 assert(hw_ids.size() == hw_positions.size());
411 std::vector<int> hw_velocities;
412 _nh.getParam(current_ns +
"velocity", hw_velocities);
413 assert(hw_ids.size() == hw_velocities.size());
415 std::vector<int> hw_temperatures;
416 _nh.getParam(current_ns +
"temperature", hw_temperatures);
417 assert(hw_positions.size() == hw_temperatures.size());
419 std::vector<double> hw_voltages;
420 _nh.getParam(current_ns +
"voltage", hw_voltages);
421 assert(hw_temperatures.size() == hw_voltages.size());
423 std::vector<int> hw_min_positions;
424 _nh.getParam(current_ns +
"min_position", hw_min_positions);
425 assert(hw_voltages.size() == hw_min_positions.size());
427 std::vector<int> hw_max_positions;
428 _nh.getParam(current_ns +
"max_position", hw_max_positions);
429 assert(hw_min_positions.size() == hw_max_positions.size());
431 std::vector<int> hw_model_numbers;
432 _nh.getParam(current_ns +
"model_number", hw_model_numbers);
433 assert(hw_max_positions.size() == hw_model_numbers.size());
435 std::vector<std::string> hw_firmwares;
436 _nh.getParam(current_ns +
"firmware", hw_firmwares);
437 assert(hw_firmwares.size() == hw_firmwares.size());
439 for (
size_t i = 0; i < hw_ids.size(); i++)
442 tmp.id =
static_cast<uint8_t
>(hw_ids.at(i));
443 tmp.position =
static_cast<uint32_t
>(hw_positions.at(i));
444 tmp.velocity =
static_cast<uint32_t
>(hw_velocities.at(i));
445 tmp.temperature =
static_cast<uint8_t
>(hw_temperatures.at(i));
446 tmp.voltage = hw_voltages.at(i);
447 tmp.model_number =
static_cast<uint16_t
>(hw_model_numbers.at(i));
448 tmp.firmware = hw_firmwares.at(i);
449 fake_params.insert(std::make_pair(tmp.id, tmp));
464 #endif // TTLDRIVER_HPP
void startCalibration() override
TtlManager::startCalibration.
common::model::EHardwareType hardware_type
int addHardwareComponent(std::shared_ptr< common::model::AbstractHardwareState > &&state) override
TtlManager::addHardwareComponent add hardware component like joint, ee, tool... to ttl manager.
bool readEndEffectorStatus()
TtlManager::readEndEffectorStatus.
int readCustomCommand(uint8_t id, int32_t reg_address, int &value, int byte_number)
TtlManager::readCustomCommand.
std::string _debug_error_message
bool isCalibrationInProgress() const
TtlManager::isCalibrationInProgress.
std::vector< int > _current_tool_vector
GetJointsStepperDriverResult getJointsStepperDriver()
: Return the driver of the joints
int writeSingleCommand(std::unique_ptr< common::model::AbstractTtlSingleMotorCmd > &&cmd)
TtlManager::writeSingleCommand.
constexpr int TTL_SCAN_MISSING_MOTOR
std::map< uint8_t, std::shared_ptr< common::model::AbstractHardwareState > > _state_map
CalibrationMachineState _calib_machine_state
bool readHardwareStatus()
TtlManager::readHardwareStatus.
bool getCollisionStatus() const
TtlManager::getCollisionStatus.
int32_t getCalibrationResult(uint8_t id) const override
TtlManager::getCalibrationResult.
void retrieveFakeMotorData(const std::string ¤t_ns, std::map< uint8_t, Reg > &fake_params, std::vector< int > hw_ids={})
TtlManager::retrieveFakeMotorData.
common::model::EStepperCalibrationStatus _calibration_status
int scanAndCheck() override
TtlManager::scanAndCheck.
bool checkCollision()
TtlManager::checkCollision.
uint32_t _hw_fail_counter_read
std::vector< uint32_t > _position_goal_params
constexpr int TTL_FAIL_OPEN_PORT
std::vector< uint8_t > _position_goal_ids
std::vector< uint8_t > _all_ids_connected
double _last_collision_detection_activating
int sendCustomCommand(uint8_t id, int reg_address, int value, int byte_number)
TtlManager::sendCustomCommand.
uint8_t readSteppersStatus()
TtlManager::readCalibrationStatus : reads specific steppers related information (ned2 only)
constexpr int TTL_FAIL_PORT_SET_BAUDRATE
int changeId(common::model::EHardwareType motor_type, uint8_t old_id, uint8_t new_id)
TtlManager::changeId.
int getAllIdsOnBus(std::vector< uint8_t > &id_list)
TtlManager::getAllIdsOnDxlBus.
void removeHardwareComponent(uint8_t id) override
TtlManager::removeHardwareComponent.
common::model::EStepperCalibrationStatus getCalibrationStatus() const override
TtlManager::getCalibrationStatus.
bool readHomingAbsPosition()
std::shared_ptr< common::model::AbstractHardwareState > getHardwareState(uint8_t motor_id) const
TtlManager::getHardwareState.
bool readJointsStatus()
TtlManager::readJointsStatus.
std::shared_ptr< dynamixel::PacketHandler > _packetHandler
void executeJointTrajectoryCmd(std::vector< std::pair< uint8_t, uint32_t >> cmd_vec)
TtlManager::executeJointTrajectoryCmd.
bool init(ros::NodeHandle &nh) override
TtlManager::init.
std::vector< std::shared_ptr< common::model::ConveyorState > > getConveyorsStates() const
uint32_t getPosition(const common::model::JointState &motor_state)
TtlManager::getPosition.
void resetCalibration() override
TtlManager::resetCalibration.
void getBusState(bool &connection_state, std::vector< uint8_t > &motor_id, std::string &debug_msg) const override
TtlManager::getBusState.
bool changeTool(int value, std::string &message, int &status)
TtlManager::changeTool.
void resetTorques()
TtlManager::resetTorques.
bool isMotorType(common::model::EHardwareType type)
TtlManager::isMotorType.
std::vector< int > _available_tools
size_t getNbMotors() const override
TtlManager::getNbMotors.
bool readCollisionStatus()
TtlManager::readCollisionStatus.
std::shared_ptr< ttl_driver::AbstractStepperDriver > driver
static constexpr uint32_t MAX_READ_EE_FAILURE
int setLeds(int led)
TtlManager::setLeds.
int writeSynchronizeCommand(std::unique_ptr< common::model::AbstractTtlSynchronizeMotorCmd > &&cmd)
TtlManager::writeSynchronizeCommand.
The TtlManager class manages the different motor drivers connected on the TTL bus it is used by ttl_i...
static constexpr double _calibration_timeout
TtlManager & operator=(TtlManager &&)=delete
bool ping(uint8_t id) override
TtlManager::ping.
std::shared_ptr< ttl_driver::AbstractTtlDriver > _default_ttl_driver
int rebootHardware(uint8_t id)
TtlManager::rebootHardware.
std::shared_ptr< FakeTtlData > _fake_data
uint8_t readNed3ProSteppersStatus()
uint32_t _end_effector_fail_counter_read
std::vector< uint8_t > getRemovedMotorList() const override
TtlManager::getRemovedMotorList.
static std::unique_ptr< ros::NodeHandle > nh
bool isConnectionOk() const override
TtlManager::isConnectionOk.
std::vector< uint32_t > _position_list
constexpr int TTL_FAIL_SETUP_GPIO
constexpr int TTL_SCAN_OK
int readMoving(uint8_t id, uint8_t &status)
TtlManager::readMoving.
std::vector< uint8_t > _removed_motor_id_list
uint32_t _current_tool_id
std::map< common::model::EHardwareType, std::vector< uint8_t > > _ids_map
void next()
next : next state, stops at updating (dont circle)
std::shared_ptr< dynamixel::PortHandler > _portHandler
std::map< common::model::EHardwareType, std::shared_ptr< ttl_driver::AbstractTtlDriver > > _driver_map
int setupCommunication() override
TtlManager::setupCommunication.
static constexpr uint32_t MAX_HW_FAILURE
std::vector< std::shared_ptr< common::model::JointState > > getMotorsStates() const
TtlManager::getMotorsStates.
~TtlManager() override
TtlManager::~TtlManager.
std::vector< uint8_t > _conveyor_list
void addHardwareDriver(common::model::EHardwareType hardware_type) override
TtlManager::addHardwareDriver.
bool hasEndEffector() const
TtlManager::hasEndEffector.
ros::Publisher _calibration_status_publisher
std::string getErrorMessage() const override
TtlManager::getErrorMessage.
std::string _led_motor_type_cfg
int readControlMode(uint8_t id, uint8_t &control_mode)
TtlManager::readControlMode.
constexpr float TTL_BUS_PROTOCOL_VERSION
constexpr int TTL_SCAN_UNALLOWED_MOTOR
constexpr int TTL_WRONG_TYPE
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.
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.
void readFakeConfig(bool use_simu_gripper, bool use_simu_conveyor)
TtlManager::readFakeConfig.
bool needCalibration() const
TtlManager::needCalibration.
ttl_driver
Author(s): Clement Cocquempot
autogenerated on Fri Mar 6 2026 15:24:15