ros2_control - jazzy
Loading...
Searching...
No Matches
differential_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__DIFFERENTIAL_TRANSMISSION_HPP_
16#define TRANSMISSION_INTERFACE__DIFFERENTIAL_TRANSMISSION_HPP_
17
18#include <fmt/compile.h>
19
20#include <cassert>
21#include <string>
22#include <vector>
23
24#include "hardware_interface/types/hardware_interface_type_values.hpp"
25#include "transmission_interface/accessor.hpp"
26#include "transmission_interface/exception.hpp"
27#include "transmission_interface/transmission.hpp"
28
30{
32
112constexpr auto HW_IF_ABSOLUTE_POSITION = "absolute_position";
113
115{
116public:
124 const std::vector<double> & actuator_reduction, const std::vector<double> & joint_reduction,
125 const std::vector<double> & joint_offset = {0.0, 0.0});
126
132 void configure(
133 const std::vector<JointHandle> & joint_handles,
134 const std::vector<ActuatorHandle> & actuator_handles) override;
135
137
142 void actuator_to_joint() override;
143
145
150 void joint_to_actuator() override;
151
152 std::size_t num_actuators() const override { return 2; }
153 std::size_t num_joints() const override { return 2; }
154
155 const std::vector<double> & get_actuator_reduction() const { return actuator_reduction_; }
156 const std::vector<double> & get_joint_reduction() const { return joint_reduction_; }
157 const std::vector<double> & get_joint_offset() const { return joint_offset_; }
158
160 std::string get_handles_info() const;
161
162protected:
163 std::vector<double> actuator_reduction_;
164 std::vector<double> joint_reduction_;
165 std::vector<double> joint_offset_;
166
167 std::vector<JointHandle> joint_position_;
168 std::vector<JointHandle> joint_velocity_;
169 std::vector<JointHandle> joint_effort_;
170 std::vector<JointHandle> joint_torque_;
171 std::vector<JointHandle> joint_absolute_position_;
172
173 std::vector<ActuatorHandle> actuator_position_;
174 std::vector<ActuatorHandle> actuator_velocity_;
175 std::vector<ActuatorHandle> actuator_effort_;
176 std::vector<ActuatorHandle> actuator_torque_;
177 std::vector<ActuatorHandle> actuator_absolute_position_;
178};
179
181 const std::vector<double> & actuator_reduction, const std::vector<double> & joint_reduction,
182 const std::vector<double> & joint_offset)
183: actuator_reduction_(actuator_reduction),
184 joint_reduction_(joint_reduction),
185 joint_offset_(joint_offset)
186{
187 if (
188 num_actuators() != actuator_reduction_.size() || num_joints() != joint_reduction_.size() ||
189 num_joints() != joint_offset_.size())
190 {
191 throw Exception("Reduction and offset vectors must have size 2.");
192 }
193
194 if (
195 0.0 == actuator_reduction_[0] || 0.0 == actuator_reduction_[1] || 0.0 == joint_reduction_[0] ||
196 0.0 == joint_reduction_[1])
197 {
198 throw Exception("Transmission reduction ratios cannot be zero.");
199 }
200}
201
203 const std::vector<JointHandle> & joint_handles,
204 const std::vector<ActuatorHandle> & actuator_handles)
205{
206 if (joint_handles.empty())
207 {
208 throw Exception("No joint handles were passed in");
209 }
210
211 if (actuator_handles.empty())
212 {
213 throw Exception("No actuator handles were passed in");
214 }
215
216 const auto joint_names = get_names(joint_handles);
217 if (joint_names.size() != 2)
218 {
219 throw Exception(
220 fmt::format(
221 FMT_COMPILE("There should be exactly two unique joint names but was given '{}'."),
222 to_string(joint_names)));
223 }
224 const auto actuator_names = get_names(actuator_handles);
225 if (actuator_names.size() != 2)
226 {
227 throw Exception(
228 fmt::format(
229 FMT_COMPILE("There should be exactly two unique actuator names but was given '{}'."),
230 to_string(actuator_names)));
231 }
232
233 joint_position_ =
234 get_ordered_handles(joint_handles, joint_names, hardware_interface::HW_IF_POSITION);
235 joint_velocity_ =
236 get_ordered_handles(joint_handles, joint_names, hardware_interface::HW_IF_VELOCITY);
237 joint_effort_ = get_ordered_handles(joint_handles, joint_names, hardware_interface::HW_IF_EFFORT);
238 joint_torque_ = get_ordered_handles(joint_handles, joint_names, hardware_interface::HW_IF_TORQUE);
239 joint_absolute_position_ =
240 get_ordered_handles(joint_handles, joint_names, HW_IF_ABSOLUTE_POSITION);
241
242 if (
243 joint_position_.size() != 2 && joint_velocity_.size() != 2 && joint_effort_.size() != 2 &&
244 joint_torque_.size() != 2 && joint_absolute_position_.size() != 2)
245 {
246 throw Exception("Not enough valid or required joint handles were presented.");
247 }
248
249 actuator_position_ =
250 get_ordered_handles(actuator_handles, actuator_names, hardware_interface::HW_IF_POSITION);
251 actuator_velocity_ =
252 get_ordered_handles(actuator_handles, actuator_names, hardware_interface::HW_IF_VELOCITY);
253 actuator_effort_ =
254 get_ordered_handles(actuator_handles, actuator_names, hardware_interface::HW_IF_EFFORT);
255 actuator_torque_ =
256 get_ordered_handles(actuator_handles, actuator_names, hardware_interface::HW_IF_TORQUE);
257 actuator_absolute_position_ =
258 get_ordered_handles(actuator_handles, actuator_names, HW_IF_ABSOLUTE_POSITION);
259
260 if (
261 actuator_position_.size() != 2 && actuator_velocity_.size() != 2 &&
262 actuator_effort_.size() != 2 && actuator_torque_.size() != 2 &&
263 actuator_absolute_position_.size() != 2)
264 {
265 throw Exception(
266 fmt::format(
267 FMT_COMPILE("Not enough valid or required actuator handles were presented. \n{}"),
269 }
270
271 if (
272 joint_position_.size() != actuator_position_.size() &&
273 joint_velocity_.size() != actuator_velocity_.size() &&
274 joint_effort_.size() != actuator_effort_.size() &&
275 joint_torque_.size() != actuator_torque_.size() &&
276 joint_absolute_position_.size() != actuator_absolute_position_.size())
277 {
278 throw Exception(
279 fmt::format(FMT_COMPILE("Pair-wise mismatch on interfaces. \n{}"), get_handles_info()));
280 }
281}
282
284{
285 const auto & ar = actuator_reduction_;
286 const auto & jr = joint_reduction_;
287
288 auto & act_pos = actuator_position_;
289 auto & joint_pos = joint_position_;
290 if (act_pos.size() == num_actuators() && joint_pos.size() == num_joints())
291 {
292 assert(act_pos[0] && act_pos[1] && joint_pos[0] && joint_pos[1]);
293
294 joint_pos[0].set_value(
295 (act_pos[0].get_value() / ar[0] + act_pos[1].get_value() / ar[1]) / (2.0 * jr[0]) +
296 joint_offset_[0]);
297 joint_pos[1].set_value(
298 (act_pos[0].get_value() / ar[0] - act_pos[1].get_value() / ar[1]) / (2.0 * jr[1]) +
299 joint_offset_[1]);
300 }
301
302 auto & act_vel = actuator_velocity_;
303 auto & joint_vel = joint_velocity_;
304 if (act_vel.size() == num_actuators() && joint_vel.size() == num_joints())
305 {
306 assert(act_vel[0] && act_vel[1] && joint_vel[0] && joint_vel[1]);
307
308 joint_vel[0].set_value(
309 (act_vel[0].get_value() / ar[0] + act_vel[1].get_value() / ar[1]) / (2.0 * jr[0]));
310 joint_vel[1].set_value(
311 (act_vel[0].get_value() / ar[0] - act_vel[1].get_value() / ar[1]) / (2.0 * jr[1]));
312 }
313
314 auto & act_eff = actuator_effort_;
315 auto & joint_eff = joint_effort_;
316 if (act_eff.size() == num_actuators() && joint_eff.size() == num_joints())
317 {
318 assert(act_eff[0] && act_eff[1] && joint_eff[0] && joint_eff[1]);
319
320 joint_eff[0].set_value(
321 jr[0] * (act_eff[0].get_value() * ar[0] + act_eff[1].get_value() * ar[1]));
322 joint_eff[1].set_value(
323 jr[1] * (act_eff[0].get_value() * ar[0] - act_eff[1].get_value() * ar[1]));
324 }
325
326 auto & act_tor = actuator_torque_;
327 auto & joint_tor = joint_torque_;
328 if (act_tor.size() == num_actuators() && joint_tor.size() == num_joints())
329 {
330 assert(act_tor[0] && act_tor[1] && joint_tor[0] && joint_tor[1]);
331
332 joint_tor[0].set_value(
333 jr[0] * (act_tor[0].get_value() * ar[0] + act_tor[1].get_value() * ar[1]));
334 joint_tor[1].set_value(
335 jr[1] * (act_tor[0].get_value() * ar[0] - act_tor[1].get_value() * ar[1]));
336 }
337
338 auto & act_abs_pos = actuator_absolute_position_;
339 auto & joint_abs_pos = joint_absolute_position_;
340 if (act_abs_pos.size() == num_actuators() && joint_abs_pos.size() == num_joints())
341 {
342 assert(act_abs_pos[0] && act_abs_pos[1] && joint_abs_pos[0] && joint_abs_pos[1]);
343
344 joint_abs_pos[0].set_value(
345 (act_abs_pos[0].get_value() / ar[0] + act_abs_pos[1].get_value() / ar[1]) / (2.0 * jr[0]) +
346 joint_offset_[0]);
347 joint_abs_pos[1].set_value(
348 (act_abs_pos[0].get_value() / ar[0] - act_abs_pos[1].get_value() / ar[1]) / (2.0 * jr[1]) +
349 joint_offset_[1]);
350 }
351}
352
354{
355 const auto & ar = actuator_reduction_;
356 const auto & jr = joint_reduction_;
357
358 auto & act_pos = actuator_position_;
359 auto & joint_pos = joint_position_;
360 if (act_pos.size() == num_actuators() && joint_pos.size() == num_joints())
361 {
362 assert(act_pos[0] && act_pos[1] && joint_pos[0] && joint_pos[1]);
363
364 double joints_offset_applied[2] = {
365 joint_pos[0].get_value() - joint_offset_[0], joint_pos[1].get_value() - joint_offset_[1]};
366 act_pos[0].set_value(
367 (joints_offset_applied[0] * jr[0] + joints_offset_applied[1] * jr[1]) * ar[0]);
368 act_pos[1].set_value(
369 (joints_offset_applied[0] * jr[0] - joints_offset_applied[1] * jr[1]) * ar[1]);
370 }
371
372 auto & act_vel = actuator_velocity_;
373 auto & joint_vel = joint_velocity_;
374 if (act_vel.size() == num_actuators() && joint_vel.size() == num_joints())
375 {
376 assert(act_vel[0] && act_vel[1] && joint_vel[0] && joint_vel[1]);
377
378 act_vel[0].set_value(
379 (joint_vel[0].get_value() * jr[0] + joint_vel[1].get_value() * jr[1]) * ar[0]);
380 act_vel[1].set_value(
381 (joint_vel[0].get_value() * jr[0] - joint_vel[1].get_value() * jr[1]) * ar[1]);
382 }
383
384 auto & act_eff = actuator_effort_;
385 auto & joint_eff = joint_effort_;
386 if (act_eff.size() == num_actuators() && joint_eff.size() == num_joints())
387 {
388 assert(act_eff[0] && act_eff[1] && joint_eff[0] && joint_eff[1]);
389
390 act_eff[0].set_value(
391 (joint_eff[0].get_value() / jr[0] + joint_eff[1].get_value() / jr[1]) / (2.0 * ar[0]));
392 act_eff[1].set_value(
393 (joint_eff[0].get_value() / jr[0] - joint_eff[1].get_value() / jr[1]) / (2.0 * ar[1]));
394 }
395
396 auto & act_tor = actuator_torque_;
397 auto & joint_tor = joint_torque_;
398 if (act_tor.size() == num_actuators() && joint_tor.size() == num_joints())
399 {
400 assert(act_tor[0] && act_tor[1] && joint_tor[0] && joint_tor[1]);
401
402 act_tor[0].set_value(
403 (joint_tor[0].get_value() / jr[0] + joint_tor[1].get_value() / jr[1]) / (2.0 * ar[0]));
404 act_tor[1].set_value(
405 (joint_tor[0].get_value() / jr[0] - joint_tor[1].get_value() / jr[1]) / (2.0 * ar[1]));
406 }
407}
408
410{
411 return fmt::format(
412 FMT_COMPILE(
413 "Got the following handles:\n"
414 "Joint position: {}, Actuator position: {}\n"
415 "Joint velocity: {}, Actuator velocity: {}\n"
416 "Joint effort: {}, Actuator effort: {}\n"
417 "Joint torque: {}, Actuator torque: {}\n"
418 "Joint absolute position: {}, Actuator absolute position: {}"),
419 to_string(get_names(joint_position_)), to_string(get_names(actuator_position_)),
420 to_string(get_names(joint_velocity_)), to_string(get_names(actuator_velocity_)),
421 to_string(get_names(joint_effort_)), to_string(get_names(actuator_effort_)),
422 to_string(get_names(joint_torque_)), to_string(get_names(actuator_torque_)),
423 to_string(get_names(joint_absolute_position_)),
424 to_string(get_names(actuator_absolute_position_)));
425}
426
427} // namespace transmission_interface
428
429#endif // TRANSMISSION_INTERFACE__DIFFERENTIAL_TRANSMISSION_HPP_
Definition differential_transmission.hpp:115
DifferentialTransmission(const std::vector< double > &actuator_reduction, const std::vector< double > &joint_reduction, const std::vector< double > &joint_offset={0.0, 0.0})
Definition differential_transmission.hpp:180
std::size_t num_joints() const override
Definition differential_transmission.hpp:153
void joint_to_actuator() override
Transform variables from joint to actuator space.
Definition differential_transmission.hpp:353
void actuator_to_joint() override
Transform variables from actuator to joint space.
Definition differential_transmission.hpp:283
std::string get_handles_info() const
Get human-friendly report of handles.
Definition differential_transmission.hpp:409
void configure(const std::vector< JointHandle > &joint_handles, const std::vector< ActuatorHandle > &actuator_handles) override
Definition differential_transmission.hpp:202
std::size_t num_actuators() const override
Definition differential_transmission.hpp:152
Definition exception.hpp:23
Abstract base class for representing mechanical transmissions.
Definition transmission.hpp:46
constexpr char HW_IF_EFFORT[]
Constant defining effort interface name.
Definition hardware_interface_type_values.hpp:27
constexpr char HW_IF_TORQUE[]
Constant defining torque interface name.
Definition hardware_interface_type_values.hpp:29
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