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