abstract_dxl_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 
19 #include "common/model/dxl_command_type_enum.hpp"
20 #include "common/model/single_motor_cmd.hpp"
21 
22 #include <cassert>
23 #include <memory>
24 #include <ros/ros.h>
25 #include <string>
26 #include <utility>
27 #include <vector>
28 
29 using ::common::model::EDxlCommandType;
30 
31 namespace ttl_driver
32 {
33 
37 AbstractDxlDriver::AbstractDxlDriver(std::shared_ptr<dynamixel::PortHandler> portHandler,
38  std::shared_ptr<dynamixel::PacketHandler> packetHandler)
39  : AbstractMotorDriver(std::move(portHandler), std::move(packetHandler))
40 {
41 }
42 
43 std::string AbstractDxlDriver::str() const
44 {
45  return "Dynamixel Driver (" + AbstractMotorDriver::str() + ")";
46 }
47 
52 int AbstractDxlDriver::writeSingleCmd(const std::unique_ptr<common::model::AbstractTtlSingleMotorCmd> &cmd)
53 {
54  if (cmd && cmd->isValid() && cmd->isDxlCmd())
55  {
56  switch (EDxlCommandType(cmd->getCmdType()))
57  {
58  case EDxlCommandType::CMD_TYPE_VELOCITY:
59  return writeVelocityGoal(cmd->getId(), cmd->getParam());
60  case EDxlCommandType::CMD_TYPE_POSITION:
61  return writePositionGoal(cmd->getId(), cmd->getParam());
62  case EDxlCommandType::CMD_TYPE_EFFORT:
63  return writeTorqueGoal(cmd->getId(), static_cast<uint16_t>(cmd->getParam()));
64  case EDxlCommandType::CMD_TYPE_TORQUE:
65  return writeTorquePercentage(cmd->getId(), static_cast<uint8_t>(cmd->getParam()));
66  case EDxlCommandType::CMD_TYPE_LEARNING_MODE:
67  return writeTorquePercentage(cmd->getId(), static_cast<uint8_t>(!cmd->getParam()));
68  case EDxlCommandType::CMD_TYPE_PING:
69  return ping(cmd->getId());
70  case EDxlCommandType::CMD_TYPE_PID: {
71  std::vector<uint16_t> params_conv;
72  for (auto p : cmd->getParams())
73  {
74  params_conv.emplace_back(static_cast<uint16_t>(p));
75  }
76  return writePID(cmd->getId(), params_conv);
77  }
78  case EDxlCommandType::CMD_TYPE_PROFILE:
79  return writeVelocityProfile(cmd->getId(), cmd->getParams());
80  case EDxlCommandType::CMD_TYPE_CONTROL_MODE:
81  return writeControlMode(cmd->getId(), static_cast<uint8_t>(cmd->getParam()));
82  case EDxlCommandType::CMD_TYPE_LED_STATE:
83  return writeLed(cmd->getId(), static_cast<uint8_t>(cmd->getParam()));
84  case EDxlCommandType::CMD_TYPE_STARTUP:
85  return writeStartupConfiguration(cmd->getId(), static_cast<uint8_t>(cmd->getParam()));
86  case EDxlCommandType::CMD_TYPE_TEMPERATURE_LIMIT:
87  return writeTemperatureLimit(cmd->getId(), static_cast<uint8_t>(cmd->getParam()));
88  case EDxlCommandType::CMD_TYPE_SHUTDOWN:
89  return writeShutdownConfiguration(cmd->getId(), static_cast<uint8_t>(cmd->getParam()));
90  default:
91  std::cout << "Command not implemented " << cmd->getCmdType() << std::endl;
92  }
93  }
94 
95  std::cout << "AbstractDxlDriver::writeSingleCmd : Command not validated: " << cmd->str() << std::endl;
96  return COMM_RX_CORRUPT;
97 }
98 
105 int AbstractDxlDriver::writeSyncCmd(int type, const std::vector<uint8_t> &ids, const std::vector<uint32_t> &params)
106 {
107  assert(!ids.empty() && "AbstractDxlDriver::writeSyncCmd: ids is empty");
108  assert(!params.empty() && "AbstractDxlDriver::writeSyncCmd: params is empty");
109 
110  switch (EDxlCommandType(type))
111  {
112  case EDxlCommandType::CMD_TYPE_POSITION:
113  return syncWritePositionGoal(ids, params);
114  case EDxlCommandType::CMD_TYPE_VELOCITY:
115  return syncWriteVelocityGoal(ids, params);
116  case EDxlCommandType::CMD_TYPE_EFFORT: {
117  std::vector<uint16_t> params_conv;
118  params_conv.reserve(params.size());
119  for (auto const &p : params)
120  {
121  params_conv.emplace_back(static_cast<uint16_t>(p));
122  }
123  return syncWriteTorqueGoal(ids, params_conv);
124  }
125  case EDxlCommandType::CMD_TYPE_TORQUE: {
126  std::vector<uint8_t> params_conv;
127  params_conv.reserve(params.size());
128  for (auto const &p : params)
129  {
130  params_conv.emplace_back(static_cast<uint8_t>(p));
131  }
132  return syncWriteTorquePercentage(ids, params_conv);
133  }
134  case EDxlCommandType::CMD_TYPE_LEARNING_MODE: {
135  std::vector<uint8_t> params_inv;
136  params_inv.reserve(params.size());
137  for (auto const &p : params)
138  {
139  params_inv.emplace_back(!p);
140  }
141  return syncWriteTorquePercentage(ids, params_inv);
142  }
143  default:
144  std::cout << "Command not implemented " << type << std::endl;
145  }
146 
147  std::cout << "AbstractDxlDriver::writeSyncCmd : Command not validated: " << type << std::endl;
148  return -1;
149 }
150 
151 } // namespace ttl_driver
ttl_driver::AbstractDxlDriver::writeLed
virtual int writeLed(uint8_t id, uint8_t led_value)=0
ttl_driver::AbstractTtlDriver::ping
virtual int ping(uint8_t id)
AbstractTtlDriver::ping.
Definition: abstract_ttl_driver.cpp:49
ttl_driver::AbstractDxlDriver::writeTemperatureLimit
virtual int writeTemperatureLimit(uint8_t id, uint8_t temperature_limit)=0
ttl_driver::AbstractMotorDriver::syncWritePositionGoal
virtual int syncWritePositionGoal(const std::vector< uint8_t > &id_list, const std::vector< uint32_t > &position_list)=0
ttl_driver::AbstractDxlDriver::writeSingleCmd
int writeSingleCmd(const std::unique_ptr< common::model::AbstractTtlSingleMotorCmd > &cmd) override
AbstractDxlDriver::writeSingleCmd.
Definition: abstract_dxl_driver.cpp:52
ttl_driver::AbstractMotorDriver::writeControlMode
virtual int writeControlMode(uint8_t id, uint8_t mode)=0
ttl_driver::AbstractDxlDriver::writeShutdownConfiguration
virtual int writeShutdownConfiguration(uint8_t id, uint8_t configuration)=0
ttl_driver::AbstractDxlDriver::AbstractDxlDriver
AbstractDxlDriver()=default
abstract_dxl_driver.hpp
ttl_driver::AbstractMotorDriver::writeVelocityProfile
virtual int writeVelocityProfile(uint8_t id, const std::vector< uint32_t > &data_list)=0
ttl_driver::AbstractMotorDriver::writePositionGoal
virtual int writePositionGoal(uint8_t id, uint32_t position)=0
ttl_driver
Definition: abstract_dxl_driver.hpp:30
ttl_driver::AbstractMotorDriver
The XDriver class.
Definition: abstract_motor_driver.hpp:38
ttl_driver::AbstractDxlDriver::writeStartupConfiguration
virtual int writeStartupConfiguration(uint8_t id, uint8_t config)=0
ttl_driver::AbstractMotorDriver::str
std::string str() const override
AbstractMotorDriver::str.
Definition: abstract_motor_driver.cpp:45
ttl_driver::AbstractDxlDriver::writePID
virtual int writePID(uint8_t id, const std::vector< uint16_t > &data)=0
ttl_driver::AbstractDxlDriver::str
std::string str() const override
AbstractTtlDriver::str : build a string describing the object. For debug purpose only.
Definition: abstract_dxl_driver.cpp:43
ttl_driver::AbstractMotorDriver::syncWriteVelocityGoal
virtual int syncWriteVelocityGoal(const std::vector< uint8_t > &id_list, const std::vector< uint32_t > &velocity_list)=0
ttl_driver::AbstractDxlDriver::writeTorqueGoal
virtual int writeTorqueGoal(uint8_t id, uint16_t torque)=0
ttl_driver::AbstractDxlDriver::writeSyncCmd
int writeSyncCmd(int type, const std::vector< uint8_t > &ids, const std::vector< uint32_t > &params) override
AbstractDxlDriver::writeSyncCmd.
Definition: abstract_dxl_driver.cpp:105
ttl_driver::AbstractMotorDriver::writeTorquePercentage
virtual int writeTorquePercentage(uint8_t id, uint8_t torque_percentage)=0
ttl_driver::AbstractDxlDriver::syncWriteTorqueGoal
virtual int syncWriteTorqueGoal(const std::vector< uint8_t > &id_list, const std::vector< uint16_t > &torque_list)=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 Fri Mar 6 2026 15:24:15