ros2_control - rolling
Loading...
Searching...
No Matches
joint_limits_urdf.hpp
1// Copyright 2024 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
16
17#ifndef JOINT_LIMITS__JOINT_LIMITS_URDF_HPP_
18#define JOINT_LIMITS__JOINT_LIMITS_URDF_HPP_
19
20#include "joint_limits/joint_limits.hpp"
21#include "urdf_model/joint.h"
22
23namespace joint_limits
24{
25
33inline bool getJointLimits(urdf::JointConstSharedPtr urdf_joint, JointLimits & limits)
34{
35 if (!urdf_joint || !urdf_joint->limits)
36 {
37 return false;
38 }
39
40 limits.has_position_limits =
41 urdf_joint->type == urdf::Joint::REVOLUTE || urdf_joint->type == urdf::Joint::PRISMATIC;
42 if (limits.has_position_limits)
43 {
44 limits.min_position = urdf_joint->limits->lower;
45 limits.max_position = urdf_joint->limits->upper;
46 }
47
48 if (!limits.has_position_limits && urdf_joint->type == urdf::Joint::CONTINUOUS)
49 {
50 limits.angle_wraparound = true;
51 }
52
53 limits.has_velocity_limits = true;
54 limits.max_velocity = std::abs(urdf_joint->limits->velocity);
55
56 limits.has_acceleration_limits = false;
57
58 limits.has_effort_limits = true;
59 limits.max_effort = std::abs(urdf_joint->limits->effort);
60
61 return true;
62}
63
70inline bool getSoftJointLimits(urdf::JointConstSharedPtr urdf_joint, SoftJointLimits & soft_limits)
71{
72 if (!urdf_joint || !urdf_joint->safety)
73 {
74 return false;
75 }
76
77 soft_limits.min_position = urdf_joint->safety->soft_lower_limit;
78 soft_limits.max_position = urdf_joint->safety->soft_upper_limit;
79 soft_limits.k_position = urdf_joint->safety->k_position;
80 soft_limits.k_velocity = urdf_joint->safety->k_velocity;
81
82 return true;
83}
84} // namespace joint_limits
85#endif // JOINT_LIMITS__JOINT_LIMITS_URDF_HPP_
Definition data_structures.hpp:37
bool getSoftJointLimits(urdf::JointConstSharedPtr urdf_joint, SoftJointLimits &soft_limits)
Populate a SoftJointLimits instance from URDF joint data.
Definition joint_limits_urdf.hpp:70
bool getJointLimits(urdf::JointConstSharedPtr urdf_joint, JointLimits &limits)
Populate a JointLimits instance from URDF joint data.
Definition joint_limits_urdf.hpp:33
Definition joint_limits.hpp:35
Definition joint_limits.hpp:113