Gazebo Physics

API Reference

8.3.0
Joint.hh
Go to the documentation of this file.
1/*
2 * Copyright (C) 2018 Open Source Robotics Foundation
3 *
4 * Licensed under the Apache License, Version 2.0 (the "License");
5 * you may not use this file except in compliance with the License.
6 * You may obtain a copy of the License at
7 *
8 * http://www.apache.org/licenses/LICENSE-2.0
9 *
10 * Unless required by applicable law or agreed to in writing, software
11 * distributed under the License is distributed on an "AS IS" BASIS,
12 * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
13 * See the License for the specific language governing permissions and
14 * limitations under the License.
15 *
16*/
17
18#ifndef GZ_PHYSICS_JOINT_HH_
19#define GZ_PHYSICS_JOINT_HH_
20
21#include <cstddef>
25
26#include <string>
27
28namespace gz
29{
30 namespace physics
31 {
37 class GZ_PHYSICS_VISIBLE GetBasicJointState : public virtual Feature
38 {
40 public: template <typename PolicyT, typename FeaturesT>
41 class Joint : public virtual Feature::Joint<PolicyT, FeaturesT>
42 {
43 public: using Scalar = typename PolicyT::Scalar;
44 public: using Pose = typename FromPolicy<PolicyT>::template Use<Pose>;
45
52 public: Scalar GetPosition(const std::size_t _dof) const;
53
60 public: Scalar GetVelocity(const std::size_t _dof) const;
61
68 public: Scalar GetAcceleration(const std::size_t _dof) const;
69
76 public: Scalar GetForce(const std::size_t _dof) const;
77
82 public: Pose GetTransform() const;
83 };
84
86 public: template <typename PolicyT>
87 class Implementation : public virtual Feature::Implementation<PolicyT>
88 {
89 public: using Scalar = typename PolicyT::Scalar;
90 public: using Pose = typename FromPolicy<PolicyT>::template Use<Pose>;
91
92 // see Joint::GetPosition above
93 public: virtual Scalar GetJointPosition(
94 const Identity &_id, std::size_t _dof) const = 0;
95
96 // see Joint::GetVelocity above
97 public: virtual Scalar GetJointVelocity(
98 const Identity &_id, std::size_t _dof) const = 0;
99
100 // see Joint::GetAcceleration above
102 const Identity &_id, std::size_t _dof) const = 0;
103
104 // see Joint::GetForce above
105 public: virtual Scalar GetJointForce(
106 const Identity &_id, std::size_t _dof) const = 0;
107
108 // see Joint::GetTransform above
109 public: virtual Pose GetJointTransform(const Identity &_id) const = 0;
110 };
111 };
112
117 class GZ_PHYSICS_VISIBLE SetBasicJointState : public virtual Feature
118 {
120 public: template <typename PolicyT, typename FeaturesT>
121 class Joint : public virtual Feature::Joint<PolicyT, FeaturesT>
122 {
123 public: using Scalar = typename PolicyT::Scalar;
124
133 public: void SetPosition(const std::size_t _dof, const Scalar _value);
134
143 public: void SetVelocity(const std::size_t _dof, const Scalar _value);
144
153 public: void SetAcceleration(
154 const std::size_t _dof, const Scalar _value);
155
164 public: void SetForce(const std::size_t _dof, const Scalar _value);
165 };
166
168 public: template <typename PolicyT>
169 class Implementation : public virtual Feature::Implementation<PolicyT>
170 {
171 public: using Scalar = typename PolicyT::Scalar;
172
173 // see Joint::SetPosition above
174 public: virtual void SetJointPosition(
175 const Identity &_id, std::size_t _dof, Scalar _value) = 0;
176
177 // See Joint::SetVelocity above
178 public: virtual void SetJointVelocity(
179 const Identity &_id, std::size_t _dof, Scalar _value) = 0;
180
181 // See Joint::SetAcceleration above
182 public: virtual void SetJointAcceleration(
183 const Identity &_id, std::size_t _dof, Scalar _value) = 0;
184
185 // See Joint::SetForce above
186 public: virtual void SetJointForce(
187 const Identity &_id, std::size_t _dof, Scalar _value) = 0;
188 };
189 };
190
196 class GZ_PHYSICS_VISIBLE GetBasicJointProperties
197 : public virtual Feature
198 {
200 public: template <typename PolicyT, typename FeaturesT>
201 class Joint : public virtual Feature::Joint<PolicyT, FeaturesT>
202 {
203 public: using Pose = typename FromPolicy<PolicyT>::template Use<Pose>;
204
209
223
236 public: Pose GetTransformToChild() const;
237 };
238
240 public: template <typename PolicyT>
241 class Implementation : public virtual Feature::Implementation<PolicyT>
242 {
243 public: using Pose = typename FromPolicy<PolicyT>::template Use<Pose>;
244
246 const Identity &_id) const = 0;
247
249 const Identity &_id) const = 0;
250
252 const Identity &_id) const = 0;
253 };
254 };
255
257 class GZ_PHYSICS_VISIBLE SetJointTransformFromParentFeature
258 : public virtual Feature
259 {
261 public: template <typename PolicyT, typename FeaturesT>
262 class Joint : public virtual Feature::Joint<PolicyT, FeaturesT>
263 {
264 public: using Pose = typename FromPolicy<PolicyT>::template Use<Pose>;
265
279 public: void SetTransformFromParent(const Pose &_pose);
280 };
281
284 public: template <typename PolicyT>
285 class Implementation : public virtual Feature::Implementation<PolicyT>
286 {
287 public: using Pose = typename FromPolicy<PolicyT>::template Use<Pose>;
288
289 // see Joint::SetTransformFromParent above
290 public: virtual void SetJointTransformFromParent(
291 const Identity &_id, const Pose &_pose) = 0;
292 };
293 };
294
296 class GZ_PHYSICS_VISIBLE SetJointTransformToChildFeature
297 : public virtual Feature
298 {
300 public: template <typename PolicyT, typename FeaturesT>
301 class Joint : public virtual Feature::Joint<PolicyT, FeaturesT>
302 {
303 public: using Pose = typename FromPolicy<PolicyT>::template Use<Pose>;
304
318 public: void SetTransformToChild(const Pose &_pose);
319 };
320
322 public: template <typename PolicyT>
323 class Implementation : public virtual Feature::Implementation<PolicyT>
324 {
325 public: using Pose = typename FromPolicy<PolicyT>::template Use<Pose>;
326
327 // see Joint::SetTransformToChild above
328 public: virtual void SetJointTransformToChild(
329 const Identity &_id, const Pose &_pose) = 0;
330 };
331 };
332
336 class GZ_PHYSICS_VISIBLE SetJointVelocityCommandFeature
337 : public virtual Feature
338 {
344 public: template <typename PolicyT, typename FeaturesT>
345 class Joint : public virtual Feature::Joint<PolicyT, FeaturesT>
346 {
347 public: using Scalar = typename PolicyT::Scalar;
348
357 public: void SetVelocityCommand(
358 const std::size_t _dof, const Scalar _value);
359 };
360
362 public: template <typename PolicyT>
363 class Implementation : public virtual Feature::Implementation<PolicyT>
364 {
365 public: using Scalar = typename PolicyT::Scalar;
366
367 // See Joint::SetVelocityCommand above
368 public: virtual void SetJointVelocityCommand(
369 const Identity &_id, std::size_t _dof, Scalar _value) = 0;
370 };
371 };
372
376 class GZ_PHYSICS_VISIBLE SetJointPositionLimitsFeature
377 : public virtual Feature
378 {
380 public: template <typename PolicyT, typename FeaturesT>
381 class Joint : public virtual Feature::Joint<PolicyT, FeaturesT>
382 {
383 public: using Scalar = typename PolicyT::Scalar;
384
393 public: void SetMinPosition(
394 const std::size_t _dof, const Scalar _value);
395
404 public: void SetMaxPosition(
405 const std::size_t _dof, const Scalar _value);
406 };
407
409 public: template <typename PolicyT>
410 class Implementation : public virtual Feature::Implementation<PolicyT>
411 {
412 public: using Scalar = typename PolicyT::Scalar;
413
414 // See Joint::SetMinPositionCommand above
415 public: virtual void SetJointMinPosition(
416 const Identity &_id, std::size_t _dof, Scalar _value) = 0;
417
418 // See Joint::SetMaxPositionCommand above
419 public: virtual void SetJointMaxPosition(
420 const Identity &_id, std::size_t _dof, Scalar _value) = 0;
421 };
422 };
423
427 class GZ_PHYSICS_VISIBLE SetJointVelocityLimitsFeature
428 : public virtual Feature
429 {
432 public: template <typename PolicyT, typename FeaturesT>
433 class Joint : public virtual Feature::Joint<PolicyT, FeaturesT>
434 {
435 public: using Scalar = typename PolicyT::Scalar;
436
445 public: void SetMinVelocity(
446 const std::size_t _dof, const Scalar _value);
447
456 public: void SetMaxVelocity(
457 const std::size_t _dof, const Scalar _value);
458 };
459
461 public: template <typename PolicyT>
462 class Implementation : public virtual Feature::Implementation<PolicyT>
463 {
464 public: using Scalar = typename PolicyT::Scalar;
465
466 // See Joint::SetMinVelocityCommand above
467 public: virtual void SetJointMinVelocity(
468 const Identity &_id, std::size_t _dof, Scalar _value) = 0;
469
470 // See Joint::SetMaxVelocityCommand above
471 public: virtual void SetJointMaxVelocity(
472 const Identity &_id, std::size_t _dof, Scalar _value) = 0;
473 };
474 };
475
478 class GZ_PHYSICS_VISIBLE SetJointEffortLimitsFeature
479 : public virtual Feature
480 {
484 public: template <typename PolicyT, typename FeaturesT>
485 class Joint : public virtual Feature::Joint<PolicyT, FeaturesT>
486 {
487 public: using Scalar = typename PolicyT::Scalar;
488
496 public: void SetMinEffort(const std::size_t _dof, const Scalar _value);
497
505 public: void SetMaxEffort(const std::size_t _dof, const Scalar _value);
506 };
507
509 public: template <typename PolicyT>
510 class Implementation : public virtual Feature::Implementation<PolicyT>
511 {
512 public: using Scalar = typename PolicyT::Scalar;
513
514 // See Joint::SetMinEffortCommand above
515 public: virtual void SetJointMinEffort(
516 const Identity &_id, std::size_t _dof, Scalar _value) = 0;
517
518 // See Joint::SetMaxEffortCommand above
519 public: virtual void SetJointMaxEffort(
520 const Identity &_id, std::size_t _dof, Scalar _value) = 0;
521 };
522 };
523
527 class GZ_PHYSICS_VISIBLE SetJointFrictionFeature
528 : public virtual Feature
529 {
531 public: template <typename PolicyT, typename FeaturesT>
532 class Joint : public virtual Feature::Joint<PolicyT, FeaturesT>
533 {
534 public: using Scalar = typename PolicyT::Scalar;
535
542 public: void SetFriction(
543 const std::size_t _dof, const Scalar _value);
544 };
545
547 public: template <typename PolicyT>
548 class Implementation : public virtual Feature::Implementation<PolicyT>
549 {
550 public: using Scalar = typename PolicyT::Scalar;
551
552 // See Joint::SetFriction above
553 public: virtual void SetJointFriction(
554 const Identity &_id, std::size_t _dof, Scalar _value) = 0;
555 };
556 };
557
561 class GZ_PHYSICS_VISIBLE SetJointDampingCoefficientFeature
562 : public virtual Feature
563 {
565 public: template <typename PolicyT, typename FeaturesT>
566 class Joint : public virtual Feature::Joint<PolicyT, FeaturesT>
567 {
568 public: using Scalar = typename PolicyT::Scalar;
569
577 const std::size_t _dof, const Scalar _value);
578 };
579
581 public: template <typename PolicyT>
582 class Implementation : public virtual Feature::Implementation<PolicyT>
583 {
584 public: using Scalar = typename PolicyT::Scalar;
585
586 // See Joint::SetDampingCoefficient above
587 public: virtual void SetJointDampingCoefficient(
588 const Identity &_id, std::size_t _dof, Scalar _value) = 0;
589 };
590 };
591
595 class GZ_PHYSICS_VISIBLE SetJointSpringStiffnessFeature
596 : public virtual Feature
597 {
599 public: template <typename PolicyT, typename FeaturesT>
600 class Joint : public virtual Feature::Joint<PolicyT, FeaturesT>
601 {
602 public: using Scalar = typename PolicyT::Scalar;
603
610 public: void SetSpringStiffness(
611 const std::size_t _dof, const Scalar _value);
612 };
613
615 public: template <typename PolicyT>
616 class Implementation : public virtual Feature::Implementation<PolicyT>
617 {
618 public: using Scalar = typename PolicyT::Scalar;
619
620 // See Joint::SetSpringStiffness above
621 public: virtual void SetJointSpringStiffness(
622 const Identity &_id, std::size_t _dof, Scalar _value) = 0;
623 };
624 };
625
629 class GZ_PHYSICS_VISIBLE SetJointSpringReferenceFeature
630 : public virtual Feature
631 {
633 public: template <typename PolicyT, typename FeaturesT>
634 class Joint : public virtual Feature::Joint<PolicyT, FeaturesT>
635 {
636 public: using Scalar = typename PolicyT::Scalar;
637
644 public: void SetSpringReference(
645 const std::size_t _dof, const Scalar _value);
646 };
647
649 public: template <typename PolicyT>
650 class Implementation : public virtual Feature::Implementation<PolicyT>
651 {
652 public: using Scalar = typename PolicyT::Scalar;
653
654 // See Joint::SetRestPosition above
655 public: virtual void SetJointSpringReference(
656 const Identity &_id, std::size_t _dof, Scalar _value) = 0;
657 };
658 };
659
660 class GZ_PHYSICS_VISIBLE DetachJointFeature
661 : public virtual Feature
662 {
663 public: template <typename PolicyT, typename FeaturesT>
664 class Joint : public virtual Feature::Joint<PolicyT, FeaturesT>
665 {
667 public: void Detach();
668 };
669
670 public: template <typename PolicyT>
671 class Implementation : public virtual Feature::Implementation<PolicyT>
672 {
673 public: virtual void DetachJoint(const Identity &_jointID) = 0;
674 };
675 };
676
677 class GZ_PHYSICS_VISIBLE GetJointTransmittedWrench
678 : public virtual FeatureWithRequirements<JointFrameSemantics>
679 {
680 public: template <typename PolicyT, typename FeaturesT>
681 class Joint
682 : public virtual JointFrameSemantics::Joint<PolicyT, FeaturesT>
683 {
684 public: using Wrench = typename FromPolicy<
685 PolicyT>::template Use<Wrench>;
686
696
712 const FrameID &_relativeTo,
713 const FrameID &_inCoordinatesOf) const;
714 };
715
716 public: template <typename PolicyT>
717 class Implementation : public virtual Feature::Implementation<PolicyT>
718 {
719 public: using Wrench = typename FromPolicy<
720 PolicyT>::template Use<Wrench>;
722 const Identity &_jointID) const = 0;
723 };
724 };
725
735 class GZ_PHYSICS_VISIBLE SetMimicConstraintFeature
736 : public virtual Feature
737 {
738 public: template <typename PolicyT, typename FeaturesT>
739 class Joint : public virtual Feature::Joint<PolicyT, FeaturesT>
740 {
741 public: using Scalar = typename PolicyT::Scalar;
742
766 public: bool SetMimicConstraint(
767 std::size_t _dof,
768 const BaseJointPtr<PolicyT> &_leaderJoint,
769 std::size_t _leaderAxisDof,
770 Scalar _multiplier,
771 Scalar _offset,
772 Scalar _reference);
773 };
774
776 public: template <typename PolicyT>
777 class Implementation : public virtual Feature::Implementation<PolicyT>
778 {
779 public: using Scalar = typename PolicyT::Scalar;
780
781 // See Joint::MimicConstraint above
782 public: virtual bool SetJointMimicConstraint(
783 const Identity &_id,
784 std::size_t _dof,
785 const BaseJointPtr<PolicyT> &_leaderJoint,
786 std::size_t _leaderAxisDof,
787 Scalar _multiplier,
788 Scalar _offset,
789 Scalar _reference) = 0;
790 };
791 };
792
795 : public virtual Feature
796 {
799 public: template <typename PolicyT, typename FeaturesT>
800 class Joint : public virtual Feature::Joint<PolicyT, FeaturesT>
801 {
811 public: void SetWeldChildToParent(bool _weldChildToParent);
812 };
813
816 public: template <typename PolicyT>
817 class Implementation : public virtual Feature::Implementation<PolicyT>
818 {
819 // see Joint::SetWeldChildToParent above
820 public: virtual void SetFixedJointWeldChildToParent(
821 const Identity &_id, bool _weldChildToParent) = 0;
822 };
823 };
824 }
825}
826
827#include <gz/physics/detail/Joint.hh>
828
829#endif