ros2_control - rolling
Loading...
Searching...
No Matches
simple_transmission.hpp
1// Copyright 2020 PAL Robotics S.L.
2//
3// Licensed under the Apache License, Version 2.0 (the "License");
4// you may not use this file except in compliance with the License.
5// You may obtain a copy of the License at
6//
7// http://www.apache.org/licenses/LICENSE-2.0
8//
9// Unless required by applicable law or agreed to in writing, software
10// distributed under the License is distributed on an "AS IS" BASIS,
11// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12// See the License for the specific language governing permissions and
13// limitations under the License.
14
15#ifndef TRANSMISSION_INTERFACE__SIMPLE_TRANSMISSION_HPP_
16#define TRANSMISSION_INTERFACE__SIMPLE_TRANSMISSION_HPP_
17
18#include <algorithm>
19#include <cassert>
20#include <string>
21#include <vector>
22
23#include "hardware_interface/types/hardware_interface_type_values.hpp"
24#include "transmission_interface/exception.hpp"
25#include "transmission_interface/transmission.hpp"
26
28{
30
84constexpr auto HW_IF_ABSOLUTE_POSITION = "absolute_position";
85
87{
88public:
94 explicit SimpleTransmission(
95 const double joint_to_actuator_reduction, const double joint_offset = 0.0);
96
98
104 void configure(
105 const std::vector<JointHandle> & joint_handles,
106 const std::vector<ActuatorHandle> & actuator_handles) override;
107
109
114 void actuator_to_joint() override;
115
117
122 void joint_to_actuator() override;
123
124 std::size_t num_actuators() const override { return 1; }
125 std::size_t num_joints() const override { return 1; }
126
127 double get_actuator_reduction() const { return reduction_; }
128 double get_joint_offset() const { return jnt_offset_; }
129
136
143
144protected:
145 double reduction_;
146 double jnt_offset_;
147
148 JointHandle joint_position_ = {"", "", nullptr};
149 JointHandle joint_velocity_ = {"", "", nullptr};
150 JointHandle joint_effort_ = {"", "", nullptr};
151 JointHandle joint_torque_ = {"", "", nullptr};
152 JointHandle joint_force_ = {"", "", nullptr};
153 JointHandle joint_absolute_position_ = {"", "", nullptr};
154
155 ActuatorHandle actuator_position_ = {"", "", nullptr};
156 ActuatorHandle actuator_velocity_ = {"", "", nullptr};
157 ActuatorHandle actuator_effort_ = {"", "", nullptr};
158 ActuatorHandle actuator_torque_ = {"", "", nullptr};
159 ActuatorHandle actuator_force_ = {"", "", nullptr};
160 ActuatorHandle actuator_absolute_position_ = {"", "", nullptr};
161};
162
164 const double joint_to_actuator_reduction, const double joint_offset)
165: reduction_(joint_to_actuator_reduction), jnt_offset_(joint_offset)
166{
167 if (reduction_ == 0.0)
168 {
169 throw Exception("Transmission reduction ratio cannot be zero.");
170 }
171}
172
173template <class HandleType>
174HandleType get_by_interface(
175 const std::vector<HandleType> & handles, const std::string & interface_name)
176{
177 const auto result = std::find_if(
178 handles.cbegin(), handles.cend(),
179 [&interface_name](const auto handle) { return handle.get_interface_name() == interface_name; });
180 if (result == handles.cend())
181 {
182 return HandleType(handles.cbegin()->get_prefix_name(), interface_name, nullptr);
183 }
184 return *result;
185}
186
187template <class T>
188bool are_names_identical(const std::vector<T> & handles)
189{
190 std::vector<std::string> names;
191 std::transform(
192 handles.cbegin(), handles.cend(), std::back_inserter(names),
193 [](const auto & handle) { return handle.get_prefix_name(); });
194 return std::equal(names.cbegin() + 1, names.cend(), names.cbegin());
195}
196
198 const std::vector<JointHandle> & joint_handles,
199 const std::vector<ActuatorHandle> & actuator_handles)
200{
201 if (joint_handles.empty())
202 {
203 throw Exception("No joint handles were passed in");
204 }
205
206 if (actuator_handles.empty())
207 {
208 throw Exception("No actuator handles were passed in");
209 }
210
211 if (!are_names_identical(joint_handles))
212 {
213 throw Exception("Joint names given to transmissions should be identical");
214 }
215
216 if (!are_names_identical(actuator_handles))
217 {
218 throw Exception("Actuator names given to transmissions should be identical");
219 }
220
221 joint_position_ = get_by_interface(joint_handles, hardware_interface::HW_IF_POSITION);
222 joint_velocity_ = get_by_interface(joint_handles, hardware_interface::HW_IF_VELOCITY);
223 joint_effort_ = get_by_interface(joint_handles, hardware_interface::HW_IF_EFFORT);
224 joint_torque_ = get_by_interface(joint_handles, hardware_interface::HW_IF_TORQUE);
225 joint_force_ = get_by_interface(joint_handles, hardware_interface::HW_IF_FORCE);
226 joint_absolute_position_ = get_by_interface(joint_handles, HW_IF_ABSOLUTE_POSITION);
227
228 if (
229 !joint_position_ && !joint_velocity_ && !joint_effort_ && !joint_torque_ && !joint_force_ &&
230 !joint_absolute_position_)
231 {
232 throw Exception("None of the provided joint handles are valid or from the required interfaces");
233 }
234
235 actuator_position_ = get_by_interface(actuator_handles, hardware_interface::HW_IF_POSITION);
236 actuator_velocity_ = get_by_interface(actuator_handles, hardware_interface::HW_IF_VELOCITY);
237 actuator_effort_ = get_by_interface(actuator_handles, hardware_interface::HW_IF_EFFORT);
238 actuator_torque_ = get_by_interface(actuator_handles, hardware_interface::HW_IF_TORQUE);
239 actuator_force_ = get_by_interface(actuator_handles, hardware_interface::HW_IF_FORCE);
240 actuator_absolute_position_ = get_by_interface(actuator_handles, HW_IF_ABSOLUTE_POSITION);
241
242 if (
243 !actuator_position_ && !actuator_velocity_ && !actuator_effort_ && !actuator_torque_ &&
244 !actuator_force_ && !actuator_absolute_position_)
245 {
246 throw Exception(
247 "None of the provided actuator handles are valid or from the required interfaces");
248 }
249}
250
252{
253 if (joint_effort_ && actuator_effort_)
254 {
255 joint_effort_.set_value(actuator_effort_.get_value() * reduction_);
256 }
257
258 if (joint_velocity_ && actuator_velocity_)
259 {
260 joint_velocity_.set_value(actuator_velocity_.get_value() / reduction_);
261 }
262
263 if (joint_position_ && actuator_position_)
264 {
265 joint_position_.set_value(actuator_position_.get_value() / reduction_ + jnt_offset_);
266 }
267
268 if (joint_torque_ && actuator_torque_)
269 {
270 joint_torque_.set_value(actuator_torque_.get_value() * reduction_);
271 }
272
273 if (joint_force_ && actuator_force_)
274 {
275 joint_force_.set_value(actuator_force_.get_value() * reduction_);
276 }
277
278 if (joint_absolute_position_ && actuator_absolute_position_)
279 {
280 joint_absolute_position_.set_value(
281 actuator_absolute_position_.get_value() / reduction_ + jnt_offset_);
282 }
283}
284
286{
287 if (joint_effort_ && actuator_effort_)
288 {
289 actuator_effort_.set_value(joint_effort_.get_value() / reduction_);
290 }
291
292 if (joint_velocity_ && actuator_velocity_)
293 {
294 actuator_velocity_.set_value(joint_velocity_.get_value() * reduction_);
295 }
296
297 if (joint_position_ && actuator_position_)
298 {
299 actuator_position_.set_value((joint_position_.get_value() - jnt_offset_) * reduction_);
300 }
301
302 if (joint_torque_ && actuator_torque_)
303 {
304 actuator_torque_.set_value(joint_torque_.get_value() / reduction_);
305 }
306
307 if (joint_force_ && actuator_force_)
308 {
309 actuator_force_.set_value(joint_force_.get_value() / reduction_);
310 }
311}
312
313} // namespace transmission_interface
314
315#endif // TRANSMISSION_INTERFACE__SIMPLE_TRANSMISSION_HPP_
Definition exception.hpp:23
Definition handle.hpp:79
Definition simple_transmission.hpp:87
SimpleTransmission(const double joint_to_actuator_reduction, const double joint_offset=0.0)
Definition simple_transmission.hpp:163
std::size_t num_actuators() const override
Definition simple_transmission.hpp:124
void actuator_to_joint() override
Transform variables from actuator to joint space.
Definition simple_transmission.hpp:251
void joint_to_actuator() override
Transform variables from joint to actuator space.
Definition simple_transmission.hpp:285
std::vector< std::string > get_supported_joint_interfaces() const override
Definition simple_transmission.hpp:137
void configure(const std::vector< JointHandle > &joint_handles, const std::vector< ActuatorHandle > &actuator_handles) override
Set up the data the transmission operates on.
Definition simple_transmission.hpp:197
std::vector< std::string > get_supported_actuator_interfaces() const override
Definition simple_transmission.hpp:130
std::size_t num_joints() const override
Definition simple_transmission.hpp:125
Abstract base class for representing mechanical transmissions.
Definition transmission.hpp:48
constexpr char HW_IF_EFFORT[]
Constant defining effort interface name.
Definition hardware_interface_type_values.hpp:27
constexpr char HW_IF_FORCE[]
Constant defining force interface name.
Definition mujoco_system_interface.hpp:73
constexpr char HW_IF_TORQUE[]
Constant defining torque interface name.
Definition mujoco_system_interface.hpp:71
constexpr char HW_IF_VELOCITY[]
Constant defining velocity interface name.
Definition hardware_interface_type_values.hpp:23
constexpr char HW_IF_POSITION[]
Constant defining position interface name.
Definition hardware_interface_type_values.hpp:21
Definition accessor.hpp:25
constexpr auto HW_IF_ABSOLUTE_POSITION
Implementation of a differential transmission.
Definition differential_transmission.hpp:112