abstract_stepper_driver.cpp
Go to the documentation of this file.
1 /*
2  abstract_motor_driver.cpp
3  Copyright (C) 2020 Niryo
4  All rights reserved.
5  This program is free software: you can redistribute it and/or modify
6  it under the terms of the GNU General Public License as published by
7  the Free Software Foundation, either version 3 of the License, or
8  (at your option) any later version.
9  This program is distributed in the hope that it will be useful,
10  but WITHOUT ANY WARRANTY; without even the implied warranty of
11  MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
12  GNU General Public License for more details.
13  You should have received a copy of the GNU General Public License
14  along with this program. If not, see <http:// www.gnu.org/licenses/>.
15 */
16 
18 #include "common/model/stepper_command_type_enum.hpp"
19 
20 #include <cassert>
21 #include <memory>
22 #include <ros/ros.h>
23 #include <string>
24 #include <utility>
25 #include <vector>
26 #include <algorithm>
27 
28 using ::common::model::EStepperCalibrationStatus;
29 using ::common::model::EStepperCommandType;
30 
31 namespace ttl_driver
32 {
33 
34 inline constexpr auto MAX_CONVEYOR_RPM = 50;
35 
39 AbstractStepperDriver::AbstractStepperDriver(std::shared_ptr<dynamixel::PortHandler> portHandler, std::shared_ptr<dynamixel::PacketHandler> packetHandler)
40  : AbstractMotorDriver(std::move(portHandler), std::move(packetHandler))
41 {
42 }
43 
48 std::string AbstractStepperDriver::str() const { return "Abstract Stepper Driver (" + AbstractMotorDriver::str() + ")"; }
49 
54 int AbstractStepperDriver::writeSingleCmd(const std::unique_ptr<common::model::AbstractTtlSingleMotorCmd> &cmd)
55 {
56  if (cmd->isValid() && cmd->isStepperCmd())
57  {
58  switch (EStepperCommandType(cmd->getCmdType()))
59  {
60  case EStepperCommandType::CMD_TYPE_VELOCITY:
61  return writeVelocityGoal(cmd->getId(), cmd->getParam());
62  case EStepperCommandType::CMD_TYPE_POSITION:
63  return writePositionGoal(cmd->getId(), cmd->getParam());
64  case EStepperCommandType::CMD_TYPE_TORQUE:
65  return writeTorquePercentage(cmd->getId(), static_cast<uint8_t>(cmd->getParam()));
66  case EStepperCommandType::CMD_TYPE_LEARNING_MODE:
67  return writeTorquePercentage(cmd->getId(), static_cast<uint8_t>(!cmd->getParam()));
68  case EStepperCommandType::CMD_TYPE_CALIBRATION:
69  return startHoming(cmd->getId());
70  case EStepperCommandType::CMD_TYPE_FACTORY_CALIBRATION:
71  return factoryCalibration(cmd->getId(), cmd->getParam());
72  case EStepperCommandType::CMD_TYPE_CALIBRATION_SETUP:
73  return writeHomingSetup(cmd->getId(), static_cast<uint8_t>(cmd->getParams().at(0)), static_cast<uint8_t>(cmd->getParams().at(1)));
74  case EStepperCommandType::CMD_TYPE_PING:
75  return ping(cmd->getId());
76  case EStepperCommandType::CMD_TYPE_CONVEYOR:
77  {
78  std::vector<uint32_t> params = cmd->getParams();
79  if (!params[0])
80  {
81  return writeVelocityGoal(cmd->getId(), 0);
82  }
83 
84  // convert direction and speed into signed speed
85  uint32_t dir = static_cast<uint32_t>(cmd->getParams().at(2));
86  uint32_t speed_percent = std::clamp(static_cast<uint32_t>(cmd->getParams().at(1)), 0u, 100u);
87  // normal warning : we need to put an int32 inside an uint32_t
88  uint32_t speed = static_cast<uint32_t>(dir * static_cast<int>(speed_percent * MAX_CONVEYOR_RPM / (100 * velocityUnit())));
89  ROS_INFO("AbstractStepperDriver::writeSingleCmd: speed = %d", speed);
90  return writeVelocityGoal(cmd->getId(), speed);
91  }
92  case EStepperCommandType::CMD_TYPE_VELOCITY_PROFILE:
93  return writeVelocityProfile(cmd->getId(), cmd->getParams());
94  case EStepperCommandType::CMD_TYPE_OPERATING_MODE:
95  return writeControlMode(cmd->getId(), static_cast<uint8_t>(cmd->getParam()));
96  default:
97  std::cout << "Command not implemented " << cmd->getCmdType() << std::endl;
98  }
99  }
100 
101  std::cout << "AbstractStepperDriver::writeSingleCmd: Command not validated : " << cmd->str() << std::endl;
102  return -1;
103 }
104 
111 int AbstractStepperDriver::writeSyncCmd(int type, const std::vector<uint8_t> &ids, const std::vector<uint32_t> &params)
112 {
113  assert(!ids.empty() && "AbstractStepperDriver::writeSyncCmdwriteSyncCmd: ids is empty");
114  assert(!params.empty() && "AbstractStepperDriver::writeSyncCmdwriteSyncCmd: params is empty");
115 
116  switch (EStepperCommandType(type))
117  {
118  case EStepperCommandType::CMD_TYPE_POSITION:
119  return syncWritePositionGoal(ids, params);
120  case EStepperCommandType::CMD_TYPE_VELOCITY:
121  return syncWriteVelocityGoal(ids, params);
122  case EStepperCommandType::CMD_TYPE_TORQUE:
123  {
124  std::vector<uint8_t> params_conv;
125  params_conv.reserve(params.size());
126  for (auto const &p : params)
127  {
128  params_conv.emplace_back(static_cast<uint8_t>(p));
129  }
130  return syncWriteTorquePercentage(ids, params_conv);
131  }
132  case EStepperCommandType::CMD_TYPE_LEARNING_MODE:
133  {
134  std::vector<uint8_t> params_inv;
135  params_inv.reserve(params.size());
136  for (auto const &p : params)
137  {
138  params_inv.emplace_back(!p);
139  }
140  return syncWriteTorquePercentage(ids, params_inv);
141  }
142  case EStepperCommandType::CMD_TYPE_WRITE_HOMING_ABS_POSITION:
143  return syncWriteHomingAbsPosition(ids, params);
144  default:
145  std::cout << "Command not implemented " << type << std::endl;
146  }
147 
148  std::cout << "AbstractStepperDriver::writeSyncCmd : Command not validated : " << type << std::endl;
149  return -1;
150 }
151 
157 std::string AbstractStepperDriver::interpretFirmwareVersion(uint32_t fw_version) const
158 {
159  auto v_major = static_cast<uint8_t>(fw_version >> 24);
160  auto v_minor = static_cast<uint16_t>(fw_version >> 8);
161  auto v_patch = static_cast<uint8_t>(fw_version >> 0);
162 
163  std::ostringstream ss;
164  ss << std::to_string(v_major) << "." << std::to_string(v_minor) << "." << std::to_string(v_patch);
165  std::string version = ss.str();
166 
167  return version;
168 }
169 
175 std::string AbstractStepperDriver::interpretErrorState(uint32_t hw_state) const
176 {
177  std::string hardware_message;
178 
179  if (hw_state & 1 << 0) // 0b00000001
180  {
181  hardware_message += "Input Voltage";
182  }
183  if (hw_state & 1 << 2) // 0b00000100
184  {
185  if (!hardware_message.empty())
186  hardware_message += ", ";
187  hardware_message += "OverHeating";
188  }
189  if (hw_state & 1 << 3) // 0b00001000
190  {
191  if (!hardware_message.empty())
192  hardware_message += ", ";
193  hardware_message += "Motor Encoder";
194  }
195  if (hw_state & 1 << 7) // 0b10000000 => added by us : disconnected error
196  {
197  if (!hardware_message.empty())
198  hardware_message += ", ";
199  hardware_message += "Disconnection";
200  }
201 
202  if (!hardware_message.empty())
203  hardware_message += " Error";
204 
205  return hardware_message;
206 }
207 
213 common::model::EStepperCalibrationStatus AbstractStepperDriver::interpretHomingData(uint8_t status) const
214 {
215  EStepperCalibrationStatus homing_status{EStepperCalibrationStatus::UNINITIALIZED};
216 
217  switch (status)
218  {
219  case 0:
220  homing_status = EStepperCalibrationStatus::UNINITIALIZED;
221  break;
222  case 1:
223  homing_status = EStepperCalibrationStatus::IN_PROGRESS;
224  break;
225  case 2:
226  homing_status = EStepperCalibrationStatus::OK;
227  break;
228  case 3:
229  homing_status = EStepperCalibrationStatus::FAIL;
230  break;
231  default:
232  homing_status = EStepperCalibrationStatus::FAIL;
233  break;
234  }
235 
236  return homing_status;
237 }
238 
244 int AbstractStepperDriver::factoryCalibration(const uint8_t id, const uint32_t &command)
245 {
246  ROS_WARN("AbstractStepperDriver::factoryCalibration - not implemented");
247 
248  return 0;
249 }
250 
254 int AbstractStepperDriver::readConveyorVelocity(uint8_t id, int32_t &velocity_percent, int32_t &direction)
255 {
256  uint32_t unsigned_present_velocity = 0;
257  auto res = readVelocity(id, unsigned_present_velocity);
258  if (res != COMM_SUCCESS )
259  {
260  ROS_ERROR("AbstractStepperDriver::readConveyorVelocity: readVelocity failed with error %d", res);
261  return res;
262  }
263 
264  // The typed returned by the hardware is actually an int32_t, it is just that the API returns it as an uint32_t
265  // We can safely cast it to int32_t
266  int32_t present_velocity = static_cast<int32_t>(unsigned_present_velocity);
267 
268  auto velocity_unit = velocityUnit();
269  auto velocity_rpms = present_velocity * velocity_unit;
270  direction = present_velocity > 0 ? 1 : -1;
271  velocity_percent = static_cast<int32_t>(std::abs(velocity_rpms * 100 / MAX_CONVEYOR_RPM));
272  return COMM_SUCCESS;
273 }
274 
275 } // namespace ttl_driver
ttl_driver::AbstractStepperDriver::interpretHomingData
virtual common::model::EStepperCalibrationStatus interpretHomingData(uint8_t status) const
AbstractStepperDriver::interpretHomingData.
Definition: abstract_stepper_driver.cpp:213
ttl_driver::AbstractStepperDriver::interpretErrorState
std::string interpretErrorState(uint32_t hw_state) const override
AbstractStepperDriver::interpretErrorState.
Definition: abstract_stepper_driver.cpp:175
ttl_driver::MAX_CONVEYOR_RPM
constexpr auto MAX_CONVEYOR_RPM
Definition: abstract_stepper_driver.cpp:34
ttl_driver::AbstractStepperDriver::factoryCalibration
virtual int factoryCalibration(const uint8_t id, const uint32_t &command)
AbstractStepperDriver::factoryCalibration.
Definition: abstract_stepper_driver.cpp:244
ttl_driver::AbstractStepperDriver::writeHomingSetup
virtual int writeHomingSetup(uint8_t id, uint8_t direction, uint8_t stall_threshold)=0
ttl_driver::AbstractStepperDriver::str
std::string str() const override
AbstractStepperDriver::str.
Definition: abstract_stepper_driver.cpp:48
ttl_driver::AbstractStepperDriver::syncWriteHomingAbsPosition
virtual int syncWriteHomingAbsPosition(const std::vector< uint8_t > &id_list, const std::vector< uint32_t > &abs_position)=0
ttl_driver::AbstractTtlDriver::ping
virtual int ping(uint8_t id)
AbstractTtlDriver::ping.
Definition: abstract_ttl_driver.cpp:48
ttl_driver::AbstractMotorDriver::syncWritePositionGoal
virtual int syncWritePositionGoal(const std::vector< uint8_t > &id_list, const std::vector< uint32_t > &position_list)=0
ttl_driver::AbstractStepperDriver::writeSingleCmd
int writeSingleCmd(const std::unique_ptr< common::model::AbstractTtlSingleMotorCmd > &cmd) override
AbstractStepperDriver::writeSingleCmd.
Definition: abstract_stepper_driver.cpp:54
ttl_driver::AbstractStepperDriver::AbstractStepperDriver
AbstractStepperDriver()=default
ttl_driver::AbstractStepperDriver::interpretFirmwareVersion
std::string interpretFirmwareVersion(uint32_t fw_version) const override
AbstractStepperDriver::interpretFirmwareVersion.
Definition: abstract_stepper_driver.cpp:157
ttl_driver::AbstractMotorDriver::writeControlMode
virtual int writeControlMode(uint8_t id, uint8_t mode)=0
ttl_driver::AbstractStepperDriver::velocityUnit
virtual float velocityUnit() const =0
writeVelocityGoal: define the unit of the velocity in RPM
ttl_driver::AbstractMotorDriver::writeVelocityProfile
virtual int writeVelocityProfile(uint8_t id, const std::vector< uint32_t > &data_list)=0
abstract_stepper_driver.hpp
ttl_driver::AbstractMotorDriver::writePositionGoal
virtual int writePositionGoal(uint8_t id, uint32_t position)=0
ttl_driver
Definition: abstract_dxl_driver.hpp:30
ttl_driver::AbstractStepperDriver::writeSyncCmd
int writeSyncCmd(int type, const std::vector< uint8_t > &ids, const std::vector< uint32_t > &params) override
AbstractStepperDriver::writeSyncCmd.
Definition: abstract_stepper_driver.cpp:111
ttl_driver::AbstractStepperDriver::readConveyorVelocity
int readConveyorVelocity(uint8_t id, int32_t &velocity, int32_t &direction)
Returns the velocity of the conveyor in percentage.
Definition: abstract_stepper_driver.cpp:254
ttl_driver::AbstractMotorDriver
The XDriver class.
Definition: abstract_motor_driver.hpp:38
ttl_driver::AbstractMotorDriver::str
std::string str() const override
AbstractMotorDriver::str.
Definition: abstract_motor_driver.cpp:44
ttl_driver::AbstractMotorDriver::readVelocity
virtual int readVelocity(uint8_t id, uint32_t &present_velocity)=0
ttl_driver::AbstractMotorDriver::syncWriteVelocityGoal
virtual int syncWriteVelocityGoal(const std::vector< uint8_t > &id_list, const std::vector< uint32_t > &velocity_list)=0
ttl_driver::AbstractStepperDriver::startHoming
virtual int startHoming(uint8_t id)=0
ttl_driver::AbstractMotorDriver::writeTorquePercentage
virtual int writeTorquePercentage(uint8_t id, uint8_t torque_percentage)=0
ttl_driver::AbstractMotorDriver::syncWriteTorquePercentage
virtual int syncWriteTorquePercentage(const std::vector< uint8_t > &id_list, const std::vector< uint8_t > &torque_percentage_list)=0
ttl_driver::AbstractMotorDriver::writeVelocityGoal
virtual int writeVelocityGoal(uint8_t id, uint32_t velocity)=0


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