abstract_end_effector_driver.cpp
Go to the documentation of this file.
1 /*
2  abstract_end_effector_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 <memory>
20 #include <ros/ros.h>
21 #include <sstream>
22 #include <string>
23 #include <utility>
24 #include <vector>
25 #include <cassert>
26 
27 using ::std::ostringstream;
28 using ::std::shared_ptr;
29 using ::std::string;
30 
31 namespace ttl_driver
32 {
33 
39 AbstractEndEffectorDriver::AbstractEndEffectorDriver(shared_ptr<dynamixel::PortHandler> portHandler, shared_ptr<dynamixel::PacketHandler> packetHandler)
40  : AbstractTtlDriver(std::move(portHandler), std::move(packetHandler))
41 {
42 }
43 
48 std::string AbstractEndEffectorDriver::str() const { return "AbstractEndEffectorDriver (" + AbstractTtlDriver::str() + ")"; }
49 
54 std::string AbstractEndEffectorDriver::interpretErrorState(uint32_t hw_state) const
55 {
56  std::string hardware_message;
57 
58  if (hw_state & 1 << 0) // 0b00000001
59  {
60  hardware_message += "Input Voltage";
61  }
62  if (hw_state & 1 << 2) // 0b00000100
63  {
64  if (!hardware_message.empty())
65  hardware_message += ", ";
66  hardware_message += "OverHeating";
67  }
68  if (hw_state & 1 << 7) // 0b10000000 => added by us : disconnected error
69  {
70  if (!hardware_message.empty())
71  hardware_message += ", ";
72  hardware_message += "Disconnection";
73  }
74 
75  if (!hardware_message.empty())
76  hardware_message += " Error";
77 
78  return hardware_message;
79 }
80 
85 std::string AbstractEndEffectorDriver::interpretFirmwareVersion(uint32_t fw_version) const
86 {
87  auto v_major = static_cast<uint8_t>(fw_version >> 24);
88  auto v_minor = static_cast<uint16_t>(fw_version >> 8);
89  auto v_patch = static_cast<uint8_t>(fw_version >> 0);
90 
91  std::ostringstream ss;
92  ss << std::to_string(v_major) << "." << std::to_string(v_minor) << "." << std::to_string(v_patch);
93  std::string version = ss.str();
94 
95  return version;
96 }
97 
103 common::model::EActionType AbstractEndEffectorDriver::interpretActionValue(uint32_t value) const
104 {
105  common::model::EActionType action = common::model::EActionType::NO_ACTION;
106 
107  // HANDLE HELD en premier car c'est le seul cas ou il peut etre actif en meme temps qu'une autre action (long push)
108 
109  if (value & 1 << 0) // 0b00000001
110  {
111  action = common::model::EActionType::SINGLE_PUSH_ACTION;
112  }
113  else if (value & 1 << 1) // 0b00000010
114  {
115  action = common::model::EActionType::DOUBLE_PUSH_ACTION;
116  }
117  else if (value & 1 << 2) // 0b0000100
118  {
119  action = common::model::EActionType::LONG_PUSH_ACTION;
120  }
121  else if (value & 1 << 3) // 0b00001000
122  {
123  action = common::model::EActionType::HANDLE_HELD_ACTION;
124  }
125  return action;
126 }
127 
133 int AbstractEndEffectorDriver::writeSingleCmd(const std::unique_ptr<common::model::AbstractTtlSingleMotorCmd> &cmd)
134 {
135  if (cmd && cmd->isValid())
136  {
137  switch (common::model::EEndEffectorCommandType(cmd->getCmdType()))
138  {
139  case common::model::EEndEffectorCommandType::CMD_TYPE_DIGITAL_OUTPUT:
140  writeDigitalOutput(cmd->getId(), cmd->getParam());
141  break;
142  case common::model::EEndEffectorCommandType::CMD_TYPE_PING:
143  ping(cmd->getId());
144  break;
145  case common::model::EEndEffectorCommandType::CMD_TYPE_SET_COLLISION_THRESH:
146  writeCollisionThresh(cmd->getId(), cmd->getParam());
147  break;
148  case common::model::EEndEffectorCommandType::CMD_TYPE_SET_COLLISION_THRESH_ALGO_2:
149  writeCollisionThreshAlgo2(cmd->getId(), cmd->getParam());
150  break;
151  default:
152  std::cout << "Command not implemented" << std::endl;
153  }
154  }
155 
156  return 0;
157 }
158 
163 int AbstractEndEffectorDriver::writeSyncCmd(int /*type*/, const std::vector<uint8_t> & /*ids*/, const std::vector<uint32_t> & /*params*/)
164 {
165  std::cout << "Synchronized cmd not implemented for end effector" << std::endl;
166 
167  return 0;
168 }
169 
170 } // namespace ttl_driver
ttl_driver::AbstractEndEffectorDriver::interpretErrorState
std::string interpretErrorState(uint32_t hw_state) const override
MockEndEffectorDriver::interpretErrorState.
Definition: abstract_end_effector_driver.cpp:54
ttl_driver::AbstractTtlDriver::str
virtual std::string str() const
AbstractTtlDriver::str : build a string describing the object. For debug purpose only.
Definition: abstract_ttl_driver.cpp:98
ttl_driver::AbstractEndEffectorDriver::writeCollisionThresh
virtual int writeCollisionThresh(uint8_t id, int thresh)=0
ttl_driver::AbstractEndEffectorDriver::interpretFirmwareVersion
std::string interpretFirmwareVersion(uint32_t fw_version) const override
MockEndEffectorDriver::interpretFirmawreVersion.
Definition: abstract_end_effector_driver.cpp:85
ttl_driver::AbstractTtlDriver::ping
virtual int ping(uint8_t id)
AbstractTtlDriver::ping.
Definition: abstract_ttl_driver.cpp:48
ttl_driver::AbstractEndEffectorDriver::interpretActionValue
common::model::EActionType interpretActionValue(uint32_t value) const
MockEndEffectorDriver::interpretActionValue.
Definition: abstract_end_effector_driver.cpp:103
ttl_driver::AbstractEndEffectorDriver::str
std::string str() const override
AbstractEndEffectorDriver::str : build a string describing the object. For debug purpose only.
Definition: abstract_end_effector_driver.cpp:48
ttl_driver::AbstractEndEffectorDriver::writeCollisionThreshAlgo2
virtual int writeCollisionThreshAlgo2(uint8_t id, int thresh)=0
abstract_end_effector_driver.hpp
ttl_driver::AbstractEndEffectorDriver::AbstractEndEffectorDriver
AbstractEndEffectorDriver()=default
ttl_driver::AbstractEndEffectorDriver::writeSingleCmd
int writeSingleCmd(const std::unique_ptr< common::model::AbstractTtlSingleMotorCmd > &cmd) override
MockEndEffectorDriver::writeSingleCmd.
Definition: abstract_end_effector_driver.cpp:133
ttl_driver
Definition: abstract_dxl_driver.hpp:30
ttl_driver::AbstractEndEffectorDriver::writeSyncCmd
int writeSyncCmd(int type, const std::vector< uint8_t > &ids, const std::vector< uint32_t > &params) override
MockEndEffectorDriver::writeSyncCmd.
Definition: abstract_end_effector_driver.cpp:163
ttl_driver::AbstractEndEffectorDriver::writeDigitalOutput
virtual int writeDigitalOutput(uint8_t id, bool out)=0


ttl_driver
Author(s): Clement Cocquempot
autogenerated on Mon Aug 18 2025 15:50:40