ros2_control - rolling
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
168
175
176protected:
177 std::vector<double> actuator_reduction_;
178 std::vector<double> joint_reduction_;
179 std::vector<double> joint_offset_;
180
181 std::vector<JointHandle> joint_position_;
182 std::vector<JointHandle> joint_velocity_;
183 std::vector<JointHandle> joint_effort_;
184 std::vector<JointHandle> joint_torque_;
185 std::vector<JointHandle> joint_force_;
186 std::vector<JointHandle> joint_absolute_position_;
187
188 std::vector<ActuatorHandle> actuator_position_;
189 std::vector<ActuatorHandle> actuator_velocity_;
190 std::vector<ActuatorHandle> actuator_effort_;
191 std::vector<ActuatorHandle> actuator_torque_;
192 std::vector<ActuatorHandle> actuator_force_;
193 std::vector<ActuatorHandle> actuator_absolute_position_;
194};
195
197 const std::vector<double> & actuator_reduction, const std::vector<double> & joint_reduction,
198 const std::vector<double> & joint_offset)
199: actuator_reduction_(actuator_reduction),
200 joint_reduction_(joint_reduction),
201 joint_offset_(joint_offset)
202{
203 if (
204 num_actuators() != actuator_reduction_.size() || num_joints() != joint_reduction_.size() ||
205 num_joints() != joint_offset_.size())
206 {
207 throw Exception("Reduction and offset vectors must have size 2.");
208 }
209
210 if (
211 0.0 == actuator_reduction_[0] || 0.0 == actuator_reduction_[1] || 0.0 == joint_reduction_[0] ||
212 0.0 == joint_reduction_[1])
213 {
214 throw Exception("Transmission reduction ratios cannot be zero.");
215 }
216}
217
219 const std::vector<JointHandle> & joint_handles,
220 const std::vector<ActuatorHandle> & actuator_handles)
221{
222 if (joint_handles.empty())
223 {
224 throw Exception("No joint handles were passed in");
225 }
226
227 if (actuator_handles.empty())
228 {
229 throw Exception("No actuator handles were passed in");
230 }
231
232 const auto joint_names = get_names(joint_handles);
233 if (joint_names.size() != 2)
234 {
235 throw Exception(
236 fmt::format(
237 FMT_COMPILE("There should be exactly two unique joint names but was given '{}'."),
238 to_string(joint_names)));
239 }
240 const auto actuator_names = get_names(actuator_handles);
241 if (actuator_names.size() != 2)
242 {
243 throw Exception(
244 fmt::format(
245 FMT_COMPILE("There should be exactly two unique actuator names but was given '{}'."),
246 to_string(actuator_names)));
247 }
248
249 joint_position_ =
250 get_ordered_handles(joint_handles, joint_names, hardware_interface::HW_IF_POSITION);
251 joint_velocity_ =
252 get_ordered_handles(joint_handles, joint_names, hardware_interface::HW_IF_VELOCITY);
253 joint_effort_ = get_ordered_handles(joint_handles, joint_names, hardware_interface::HW_IF_EFFORT);
254 joint_torque_ = get_ordered_handles(joint_handles, joint_names, hardware_interface::HW_IF_TORQUE);
255 joint_force_ = get_ordered_handles(joint_handles, joint_names, hardware_interface::HW_IF_FORCE);
256 joint_absolute_position_ =
257 get_ordered_handles(joint_handles, joint_names, HW_IF_ABSOLUTE_POSITION);
258
259 if (!joint_position_.empty() && joint_position_.size() != 2)
260 {
261 throw Exception(
262 fmt::format(
263 FMT_COMPILE("Not enough valid or required joint position handles were present. \n{}"),
265 }
266 if (!joint_velocity_.empty() && joint_velocity_.size() != 2)
267 {
268 throw Exception(
269 fmt::format(
270 FMT_COMPILE("Not enough valid or required joint velocity handles were present. \n{}"),
272 }
273 if (!joint_effort_.empty() && joint_effort_.size() != 2)
274 {
275 throw Exception(
276 fmt::format(
277 FMT_COMPILE("Not enough valid or required joint effort handles were present. \n{}"),
279 }
280 if (!joint_torque_.empty() && joint_torque_.size() != 2)
281 {
282 throw Exception(
283 fmt::format(
284 FMT_COMPILE("Not enough valid or required joint torque handles were present. \n{}"),
286 }
287 if (!joint_force_.empty() && joint_force_.size() != 2)
288 {
289 throw Exception(
290 fmt::format(
291 FMT_COMPILE("Not enough valid or required joint force handles were present. \n{}"),
293 }
294 if (!joint_absolute_position_.empty() && joint_absolute_position_.size() != 2)
295 {
296 throw Exception(
297 fmt::format(
298 FMT_COMPILE(
299 "Not enough valid or required joint absolute position handles were present. \n{}"),
301 }
302
303 actuator_position_ =
304 get_ordered_handles(actuator_handles, actuator_names, hardware_interface::HW_IF_POSITION);
305 actuator_velocity_ =
306 get_ordered_handles(actuator_handles, actuator_names, hardware_interface::HW_IF_VELOCITY);
307 actuator_effort_ =
308 get_ordered_handles(actuator_handles, actuator_names, hardware_interface::HW_IF_EFFORT);
309 actuator_torque_ =
310 get_ordered_handles(actuator_handles, actuator_names, hardware_interface::HW_IF_TORQUE);
311 actuator_force_ =
312 get_ordered_handles(actuator_handles, actuator_names, hardware_interface::HW_IF_FORCE);
313 actuator_absolute_position_ =
314 get_ordered_handles(actuator_handles, actuator_names, HW_IF_ABSOLUTE_POSITION);
315
316 if (!actuator_position_.empty() && actuator_position_.size() != 2)
317 {
318 throw Exception(
319 fmt::format(
320 FMT_COMPILE("Not enough valid or required actuator position handles were present. \n{}"),
322 }
323 if (!actuator_velocity_.empty() && actuator_velocity_.size() != 2)
324 {
325 throw Exception(
326 fmt::format(
327 FMT_COMPILE("Not enough valid or required actuator velocity handles were present. \n{}"),
329 }
330 if (!actuator_effort_.empty() && actuator_effort_.size() != 2)
331 {
332 throw Exception(
333 fmt::format(
334 FMT_COMPILE("Not enough valid or required actuator effort handles were present. \n{}"),
336 }
337 if (!actuator_torque_.empty() && actuator_torque_.size() != 2)
338 {
339 throw Exception(
340 fmt::format(
341 FMT_COMPILE("Not enough valid or required actuator torque handles were present. \n{}"),
343 }
344 if (!actuator_force_.empty() && actuator_force_.size() != 2)
345 {
346 throw Exception(
347 fmt::format(
348 FMT_COMPILE("Not enough valid or required actuator force handles were present. \n{}"),
350 }
351 if (!actuator_absolute_position_.empty() && actuator_absolute_position_.size() != 2)
352 {
353 throw Exception(
354 fmt::format(
355 FMT_COMPILE(
356 "Not enough valid or required actuator absolute position handles were "
357 "present. \n{}"),
359 }
360
361 if (
362 !joint_position_.empty() && !actuator_position_.empty() &&
363 joint_position_.size() != actuator_position_.size())
364 {
365 throw Exception(
366 fmt::format(
367 FMT_COMPILE("Pair-wise mismatch on position interfaces. \n{}"), get_handles_info()));
368 }
369 if (
370 !joint_velocity_.empty() && !actuator_velocity_.empty() &&
371 joint_velocity_.size() != actuator_velocity_.size())
372 {
373 throw Exception(
374 fmt::format(
375 FMT_COMPILE("Pair-wise mismatch on velocity interfaces. \n{}"), get_handles_info()));
376 }
377 if (
378 !joint_effort_.empty() && !actuator_effort_.empty() &&
379 joint_effort_.size() != actuator_effort_.size())
380 {
381 throw Exception(
382 fmt::format(
383 FMT_COMPILE("Pair-wise mismatch on effort interfaces. \n{}"), get_handles_info()));
384 }
385 if (
386 !joint_torque_.empty() && !actuator_torque_.empty() &&
387 joint_torque_.size() != actuator_torque_.size())
388 {
389 throw Exception(
390 fmt::format(
391 FMT_COMPILE("Pair-wise mismatch on torque interfaces. \n{}"), get_handles_info()));
392 }
393 if (
394 !joint_force_.empty() && !actuator_force_.empty() &&
395 joint_force_.size() != actuator_force_.size())
396 {
397 throw Exception(
398 fmt::format(FMT_COMPILE("Pair-wise mismatch on force interfaces. \n{}"), get_handles_info()));
399 }
400 if (
401 !joint_absolute_position_.empty() && !actuator_absolute_position_.empty() &&
402 joint_absolute_position_.size() != actuator_absolute_position_.size())
403 {
404 throw Exception(
405 fmt::format(
406 FMT_COMPILE("Pair-wise mismatch on absolute position interfaces. \n{}"),
408 }
409
410 // Check at least one pair-wise interface is available
411 if (!((!joint_position_.empty() && !actuator_position_.empty() &&
412 joint_position_.size() == actuator_position_.size()) ||
413 (!joint_velocity_.empty() && !actuator_velocity_.empty() &&
414 joint_velocity_.size() == actuator_velocity_.size()) ||
415 (!joint_effort_.empty() && !actuator_effort_.empty() &&
416 joint_effort_.size() == actuator_effort_.size()) ||
417 (!joint_torque_.empty() && !actuator_torque_.empty() &&
418 joint_torque_.size() == actuator_torque_.size()) ||
419 (!joint_force_.empty() && !actuator_force_.empty() &&
420 joint_force_.size() == actuator_force_.size()) ||
421 (!joint_absolute_position_.empty() && !actuator_absolute_position_.empty() &&
422 joint_absolute_position_.size() == actuator_absolute_position_.size())))
423 {
424 throw Exception(
425 fmt::format(
426 FMT_COMPILE("No pair-wise interface available between joints and actuators. \n{}"),
428 }
429}
430
432{
433 const auto & ar = actuator_reduction_;
434 const auto & jr = joint_reduction_;
435
436 auto & act_pos = actuator_position_;
437 auto & joint_pos = joint_position_;
438 if (act_pos.size() == num_actuators() && joint_pos.size() == num_joints())
439 {
440 assert(act_pos[0] && act_pos[1] && joint_pos[0] && joint_pos[1]);
441
442 joint_pos[0].set_value(
443 (act_pos[0].get_value() / ar[0] + act_pos[1].get_value() / ar[1]) / (2.0 * jr[0]) +
444 joint_offset_[0]);
445 joint_pos[1].set_value(
446 (act_pos[0].get_value() / ar[0] - act_pos[1].get_value() / ar[1]) / (2.0 * jr[1]) +
447 joint_offset_[1]);
448 }
449
450 auto & act_vel = actuator_velocity_;
451 auto & joint_vel = joint_velocity_;
452 if (act_vel.size() == num_actuators() && joint_vel.size() == num_joints())
453 {
454 assert(act_vel[0] && act_vel[1] && joint_vel[0] && joint_vel[1]);
455
456 joint_vel[0].set_value(
457 (act_vel[0].get_value() / ar[0] + act_vel[1].get_value() / ar[1]) / (2.0 * jr[0]));
458 joint_vel[1].set_value(
459 (act_vel[0].get_value() / ar[0] - act_vel[1].get_value() / ar[1]) / (2.0 * jr[1]));
460 }
461
462 auto & act_eff = actuator_effort_;
463 auto & joint_eff = joint_effort_;
464 if (act_eff.size() == num_actuators() && joint_eff.size() == num_joints())
465 {
466 assert(act_eff[0] && act_eff[1] && joint_eff[0] && joint_eff[1]);
467
468 joint_eff[0].set_value(
469 jr[0] * (act_eff[0].get_value() * ar[0] + act_eff[1].get_value() * ar[1]));
470 joint_eff[1].set_value(
471 jr[1] * (act_eff[0].get_value() * ar[0] - act_eff[1].get_value() * ar[1]));
472 }
473
474 auto & act_tor = actuator_torque_;
475 auto & joint_tor = joint_torque_;
476 if (act_tor.size() == num_actuators() && joint_tor.size() == num_joints())
477 {
478 assert(act_tor[0] && act_tor[1] && joint_tor[0] && joint_tor[1]);
479
480 joint_tor[0].set_value(
481 jr[0] * (act_tor[0].get_value() * ar[0] + act_tor[1].get_value() * ar[1]));
482 joint_tor[1].set_value(
483 jr[1] * (act_tor[0].get_value() * ar[0] - act_tor[1].get_value() * ar[1]));
484 }
485
486 auto & act_for = actuator_force_;
487 auto & joint_for = joint_force_;
488 if (act_for.size() == num_actuators() && joint_for.size() == num_joints())
489 {
490 assert(act_for[0] && act_for[1] && joint_for[0] && joint_for[1]);
491
492 joint_for[0].set_value(
493 jr[0] * (act_for[0].get_value() * ar[0] + act_for[1].get_value() * ar[1]));
494 joint_for[1].set_value(
495 jr[1] * (act_for[0].get_value() * ar[0] - act_for[1].get_value() * ar[1]));
496 }
497
498 auto & act_abs_pos = actuator_absolute_position_;
499 auto & joint_abs_pos = joint_absolute_position_;
500 if (act_abs_pos.size() == num_actuators() && joint_abs_pos.size() == num_joints())
501 {
502 assert(act_abs_pos[0] && act_abs_pos[1] && joint_abs_pos[0] && joint_abs_pos[1]);
503
504 joint_abs_pos[0].set_value(
505 (act_abs_pos[0].get_value() / ar[0] + act_abs_pos[1].get_value() / ar[1]) / (2.0 * jr[0]) +
506 joint_offset_[0]);
507 joint_abs_pos[1].set_value(
508 (act_abs_pos[0].get_value() / ar[0] - act_abs_pos[1].get_value() / ar[1]) / (2.0 * jr[1]) +
509 joint_offset_[1]);
510 }
511}
512
514{
515 const auto & ar = actuator_reduction_;
516 const auto & jr = joint_reduction_;
517
518 auto & act_pos = actuator_position_;
519 auto & joint_pos = joint_position_;
520 if (act_pos.size() == num_actuators() && joint_pos.size() == num_joints())
521 {
522 assert(act_pos[0] && act_pos[1] && joint_pos[0] && joint_pos[1]);
523
524 double joints_offset_applied[2] = {
525 joint_pos[0].get_value() - joint_offset_[0], joint_pos[1].get_value() - joint_offset_[1]};
526 act_pos[0].set_value(
527 (joints_offset_applied[0] * jr[0] + joints_offset_applied[1] * jr[1]) * ar[0]);
528 act_pos[1].set_value(
529 (joints_offset_applied[0] * jr[0] - joints_offset_applied[1] * jr[1]) * ar[1]);
530 }
531
532 auto & act_vel = actuator_velocity_;
533 auto & joint_vel = joint_velocity_;
534 if (act_vel.size() == num_actuators() && joint_vel.size() == num_joints())
535 {
536 assert(act_vel[0] && act_vel[1] && joint_vel[0] && joint_vel[1]);
537
538 act_vel[0].set_value(
539 (joint_vel[0].get_value() * jr[0] + joint_vel[1].get_value() * jr[1]) * ar[0]);
540 act_vel[1].set_value(
541 (joint_vel[0].get_value() * jr[0] - joint_vel[1].get_value() * jr[1]) * ar[1]);
542 }
543
544 auto & act_eff = actuator_effort_;
545 auto & joint_eff = joint_effort_;
546 if (act_eff.size() == num_actuators() && joint_eff.size() == num_joints())
547 {
548 assert(act_eff[0] && act_eff[1] && joint_eff[0] && joint_eff[1]);
549
550 act_eff[0].set_value(
551 (joint_eff[0].get_value() / jr[0] + joint_eff[1].get_value() / jr[1]) / (2.0 * ar[0]));
552 act_eff[1].set_value(
553 (joint_eff[0].get_value() / jr[0] - joint_eff[1].get_value() / jr[1]) / (2.0 * ar[1]));
554 }
555
556 auto & act_tor = actuator_torque_;
557 auto & joint_tor = joint_torque_;
558 if (act_tor.size() == num_actuators() && joint_tor.size() == num_joints())
559 {
560 assert(act_tor[0] && act_tor[1] && joint_tor[0] && joint_tor[1]);
561
562 act_tor[0].set_value(
563 (joint_tor[0].get_value() / jr[0] + joint_tor[1].get_value() / jr[1]) / (2.0 * ar[0]));
564 act_tor[1].set_value(
565 (joint_tor[0].get_value() / jr[0] - joint_tor[1].get_value() / jr[1]) / (2.0 * ar[1]));
566 }
567
568 auto & act_for = actuator_force_;
569 auto & joint_for = joint_force_;
570 if (act_for.size() == num_actuators() && joint_for.size() == num_joints())
571 {
572 assert(act_for[0] && act_for[1] && joint_for[0] && joint_for[1]);
573
574 act_for[0].set_value(
575 (joint_for[0].get_value() / jr[0] + joint_for[1].get_value() / jr[1]) / (2.0 * ar[0]));
576 act_for[1].set_value(
577 (joint_for[0].get_value() / jr[0] - joint_for[1].get_value() / jr[1]) / (2.0 * ar[1]));
578 }
579}
580
582{
583 return fmt::format(
584 FMT_COMPILE(
585 "Got the following handles:\n"
586 "Joint position: {}, Actuator position: {}\n"
587 "Joint velocity: {}, Actuator velocity: {}\n"
588 "Joint effort: {}, Actuator effort: {}\n"
589 "Joint torque: {}, Actuator torque: {}\n"
590 "Joint force: {}, Actuator force: {}\n"
591 "Joint absolute position: {}, Actuator absolute position: {}"),
592 to_string(get_names(joint_position_)), to_string(get_names(actuator_position_)),
593 to_string(get_names(joint_velocity_)), to_string(get_names(actuator_velocity_)),
594 to_string(get_names(joint_effort_)), to_string(get_names(actuator_effort_)),
595 to_string(get_names(joint_torque_)), to_string(get_names(actuator_torque_)),
596 to_string(get_names(joint_force_)), to_string(get_names(actuator_force_)),
597 to_string(get_names(joint_absolute_position_)),
598 to_string(get_names(actuator_absolute_position_)));
599}
600
601} // namespace transmission_interface
602
603#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:196
std::vector< std::string > get_supported_actuator_interfaces() const override
Definition differential_transmission.hpp:162
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:513
void actuator_to_joint() override
Transform variables from actuator to joint space.
Definition differential_transmission.hpp:431
std::string get_handles_info() const
Get human-friendly report of handles.
Definition differential_transmission.hpp:581
std::vector< std::string > get_supported_joint_interfaces() const override
Definition differential_transmission.hpp:169
void configure(const std::vector< JointHandle > &joint_handles, const std::vector< ActuatorHandle > &actuator_handles) override
Definition differential_transmission.hpp:218
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: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