Skip to content

Commit d8a21c4

Browse files
authored
Add joint limiter interface plugins to enforce limits defined in the URDF (#1526)
1 parent ecfdfc7 commit d8a21c4

17 files changed

+2883
-183
lines changed

joint_limits/CMakeLists.txt

Lines changed: 33 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -44,14 +44,28 @@ target_include_directories(joint_limiter_interface PUBLIC
4444
)
4545
ament_target_dependencies(joint_limiter_interface PUBLIC ${THIS_PACKAGE_INCLUDE_DEPENDS})
4646

47+
add_library(joint_limits_helpers SHARED
48+
src/joint_limits_helpers.cpp
49+
)
50+
target_compile_features(joint_limits_helpers PUBLIC cxx_std_17)
51+
target_include_directories(joint_limits_helpers PUBLIC
52+
$<BUILD_INTERFACE:${PROJECT_SOURCE_DIR}/include>
53+
$<INSTALL_INTERFACE:include/joint_limits>
54+
)
55+
ament_target_dependencies(joint_limits_helpers PUBLIC ${THIS_PACKAGE_INCLUDE_DEPENDS})
56+
4757
add_library(joint_saturation_limiter SHARED
4858
src/joint_saturation_limiter.cpp
59+
src/joint_range_limiter.cpp
60+
src/joint_soft_limiter.cpp
4961
)
5062
target_compile_features(joint_saturation_limiter PUBLIC cxx_std_17)
5163
target_include_directories(joint_saturation_limiter PUBLIC
5264
$<BUILD_INTERFACE:${PROJECT_SOURCE_DIR}/include>
5365
$<INSTALL_INTERFACE:include/joint_limits>
5466
)
67+
target_link_libraries(joint_saturation_limiter PUBLIC joint_limits_helpers)
68+
5569
ament_target_dependencies(joint_saturation_limiter PUBLIC ${THIS_PACKAGE_INCLUDE_DEPENDS})
5670

5771
pluginlib_export_plugin_description_file(joint_limits joint_limiters.xml)
@@ -91,6 +105,24 @@ if(BUILD_TESTING)
91105
rclcpp
92106
)
93107

108+
ament_add_gmock(test_joint_range_limiter test/test_joint_range_limiter.cpp)
109+
target_include_directories(test_joint_range_limiter PRIVATE include)
110+
target_link_libraries(test_joint_range_limiter joint_limiter_interface)
111+
ament_target_dependencies(
112+
test_joint_range_limiter
113+
pluginlib
114+
rclcpp
115+
)
116+
117+
ament_add_gmock(test_joint_soft_limiter test/test_joint_soft_limiter.cpp)
118+
target_include_directories(test_joint_soft_limiter PRIVATE include)
119+
target_link_libraries(test_joint_soft_limiter joint_limiter_interface)
120+
ament_target_dependencies(
121+
test_joint_soft_limiter
122+
pluginlib
123+
rclcpp
124+
)
125+
94126
endif()
95127

96128
install(
@@ -101,6 +133,7 @@ install(TARGETS
101133
joint_limits
102134
joint_limiter_interface
103135
joint_saturation_limiter
136+
joint_limits_helpers
104137
EXPORT export_joint_limits
105138
ARCHIVE DESTINATION lib
106139
LIBRARY DESTINATION lib
Lines changed: 66 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,66 @@
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+
15+
/// \author Sai Kishor Kothakota
16+
17+
#ifndef JOINT_LIMITS__DATA_STRUCTURES_HPP_
18+
#define JOINT_LIMITS__DATA_STRUCTURES_HPP_
19+
20+
#include <memory>
21+
#include <optional>
22+
#include <string>
23+
24+
namespace joint_limits
25+
{
26+
27+
struct JointControlInterfacesData
28+
{
29+
std::string joint_name;
30+
std::optional<double> position = std::nullopt;
31+
std::optional<double> velocity = std::nullopt;
32+
std::optional<double> effort = std::nullopt;
33+
std::optional<double> acceleration = std::nullopt;
34+
std::optional<double> jerk = std::nullopt;
35+
36+
bool has_data() const
37+
{
38+
return has_position() || has_velocity() || has_effort() || has_acceleration() || has_jerk();
39+
}
40+
41+
bool has_position() const { return position.has_value(); }
42+
43+
bool has_velocity() const { return velocity.has_value(); }
44+
45+
bool has_effort() const { return effort.has_value(); }
46+
47+
bool has_acceleration() const { return acceleration.has_value(); }
48+
49+
bool has_jerk() const { return jerk.has_value(); }
50+
};
51+
52+
struct JointInterfacesCommandLimiterData
53+
{
54+
std::string joint_name;
55+
JointControlInterfacesData actual;
56+
JointControlInterfacesData command;
57+
JointControlInterfacesData prev_command;
58+
JointControlInterfacesData limited;
59+
60+
bool has_actual_data() const { return actual.has_data(); }
61+
62+
bool has_command_data() const { return command.has_data(); }
63+
};
64+
65+
} // namespace joint_limits
66+
#endif // JOINT_LIMITS__DATA_STRUCTURES_HPP_

joint_limits/include/joint_limits/joint_limiter_interface.hpp

Lines changed: 88 additions & 65 deletions
Original file line numberDiff line numberDiff line change
@@ -20,6 +20,7 @@
2020
#include <string>
2121
#include <vector>
2222

23+
#include "joint_limits/joint_limits.hpp"
2324
#include "joint_limits/joint_limits_rosparam.hpp"
2425
#include "rclcpp/node.hpp"
2526
#include "rclcpp_lifecycle/lifecycle_node.hpp"
@@ -28,9 +29,8 @@
2829

2930
namespace joint_limits
3031
{
31-
using JointLimitsStateDataType = trajectory_msgs::msg::JointTrajectoryPoint;
3232

33-
template <typename LimitsType>
33+
template <typename JointLimitsStateDataType>
3434
class JointLimiterInterface
3535
{
3636
public:
@@ -68,55 +68,58 @@ class JointLimiterInterface
6868
// TODO(destogl): get limits from URDF
6969

7070
// Initialize and get joint limits from parameter server
71-
for (size_t i = 0; i < number_of_joints_; ++i)
71+
if (has_parameter_interface())
7272
{
73-
if (!declare_parameters(joint_names[i], node_param_itf_, node_logging_itf_))
74-
{
75-
RCLCPP_ERROR(
76-
node_logging_itf_->get_logger(),
77-
"JointLimiter: Joint '%s': parameter declaration has failed", joint_names[i].c_str());
78-
result = false;
79-
break;
80-
}
81-
if (!get_joint_limits(joint_names[i], node_param_itf_, node_logging_itf_, joint_limits_[i]))
73+
for (size_t i = 0; i < number_of_joints_; ++i)
8274
{
83-
RCLCPP_ERROR(
84-
node_logging_itf_->get_logger(),
85-
"JointLimiter: Joint '%s': getting parameters has failed", joint_names[i].c_str());
86-
result = false;
87-
break;
75+
if (!declare_parameters(joint_names[i], node_param_itf_, node_logging_itf_))
76+
{
77+
RCLCPP_ERROR(
78+
node_logging_itf_->get_logger(),
79+
"JointLimiter: Joint '%s': parameter declaration has failed", joint_names[i].c_str());
80+
result = false;
81+
break;
82+
}
83+
if (!get_joint_limits(joint_names[i], node_param_itf_, node_logging_itf_, joint_limits_[i]))
84+
{
85+
RCLCPP_ERROR(
86+
node_logging_itf_->get_logger(),
87+
"JointLimiter: Joint '%s': getting parameters has failed", joint_names[i].c_str());
88+
result = false;
89+
break;
90+
}
91+
RCLCPP_INFO(
92+
node_logging_itf_->get_logger(), "Limits for joint %zu (%s) are:\n%s", i,
93+
joint_names[i].c_str(), joint_limits_[i].to_string().c_str());
8894
}
89-
RCLCPP_INFO(
90-
node_logging_itf_->get_logger(), "Limits for joint %zu (%s) are:\n%s", i,
91-
joint_names[i].c_str(), joint_limits_[i].to_string().c_str());
92-
}
93-
updated_limits_.writeFromNonRT(joint_limits_);
95+
updated_limits_.writeFromNonRT(joint_limits_);
9496

95-
auto on_parameter_event_callback = [this](const std::vector<rclcpp::Parameter> & parameters)
96-
{
97-
rcl_interfaces::msg::SetParametersResult set_parameters_result;
98-
set_parameters_result.successful = true;
97+
auto on_parameter_event_callback = [this](const std::vector<rclcpp::Parameter> & parameters)
98+
{
99+
rcl_interfaces::msg::SetParametersResult set_parameters_result;
100+
set_parameters_result.successful = true;
99101

100-
std::vector<LimitsType> updated_joint_limits = joint_limits_;
101-
bool changed = false;
102+
std::vector<joint_limits::JointLimits> updated_joint_limits = joint_limits_;
103+
bool changed = false;
102104

103-
for (size_t i = 0; i < number_of_joints_; ++i)
104-
{
105-
changed |= joint_limits::check_for_limits_update(
106-
joint_names_[i], parameters, node_logging_itf_, updated_joint_limits[i]);
107-
}
105+
for (size_t i = 0; i < number_of_joints_; ++i)
106+
{
107+
changed |= joint_limits::check_for_limits_update(
108+
joint_names_[i], parameters, node_logging_itf_, updated_joint_limits[i]);
109+
}
108110

109-
if (changed)
110-
{
111-
updated_limits_.writeFromNonRT(updated_joint_limits);
112-
RCLCPP_INFO(node_logging_itf_->get_logger(), "Limits are dynamically updated!");
113-
}
111+
if (changed)
112+
{
113+
updated_limits_.writeFromNonRT(updated_joint_limits);
114+
RCLCPP_INFO(node_logging_itf_->get_logger(), "Limits are dynamically updated!");
115+
}
114116

115-
return set_parameters_result;
116-
};
117+
return set_parameters_result;
118+
};
117119

118-
parameter_callback_ =
119-
node_param_itf_->add_on_set_parameters_callback(on_parameter_event_callback);
120+
parameter_callback_ =
121+
node_param_itf_->add_on_set_parameters_callback(on_parameter_event_callback);
122+
}
120123

121124
if (result)
122125
{
@@ -128,6 +131,34 @@ class JointLimiterInterface
128131
return result;
129132
}
130133

134+
/**
135+
* Wrapper init method that accepts the joint names and their limits directly
136+
*/
137+
virtual bool init(
138+
const std::vector<std::string> & joint_names,
139+
const std::vector<joint_limits::JointLimits> & joint_limits,
140+
const std::vector<joint_limits::SoftJointLimits> & soft_joint_limits,
141+
const rclcpp::node_interfaces::NodeParametersInterface::SharedPtr & param_itf,
142+
const rclcpp::node_interfaces::NodeLoggingInterface::SharedPtr & logging_itf)
143+
{
144+
number_of_joints_ = joint_names.size();
145+
joint_names_ = joint_names;
146+
joint_limits_ = joint_limits;
147+
soft_joint_limits_ = soft_joint_limits;
148+
node_param_itf_ = param_itf;
149+
node_logging_itf_ = logging_itf;
150+
updated_limits_.writeFromNonRT(joint_limits_);
151+
152+
if ((number_of_joints_ != joint_limits_.size()) && has_logging_interface())
153+
{
154+
RCLCPP_ERROR(
155+
node_logging_itf_->get_logger(),
156+
"JointLimiter: Number of joint names and limits do not match: %zu != %zu",
157+
number_of_joints_, joint_limits_.size());
158+
}
159+
return (number_of_joints_ == joint_limits_.size()) && on_init();
160+
}
161+
131162
/**
132163
* Wrapper init method that accepts pointer to the Node.
133164
* For details see other init method.
@@ -177,19 +208,6 @@ class JointLimiterInterface
177208
return on_enforce(current_joint_states, desired_joint_states, dt);
178209
}
179210

180-
/** \brief Enforce joint limits to desired joint state for single physical quantity.
181-
*
182-
* Generic enforce method that calls implementation-specific `on_enforce` method.
183-
*
184-
* \param[in,out] desired_joint_states joint state that should be adjusted to obey the limits.
185-
* \returns true if limits are enforced, otherwise false.
186-
*/
187-
virtual bool enforce(std::vector<double> & desired_joint_states)
188-
{
189-
joint_limits_ = *(updated_limits_.readFromRT());
190-
return on_enforce(desired_joint_states);
191-
}
192-
193211
protected:
194212
/** \brief Method is realized by an implementation.
195213
*
@@ -219,27 +237,32 @@ class JointLimiterInterface
219237
JointLimitsStateDataType & current_joint_states,
220238
JointLimitsStateDataType & desired_joint_states, const rclcpp::Duration & dt) = 0;
221239

222-
/** \brief Method is realized by an implementation.
240+
/** \brief Checks if the logging interface is set.
241+
* \returns true if the logging interface is available, otherwise false.
223242
*
224-
* Filter-specific implementation of the joint limits enforce algorithm for single physical
225-
* quantity.
226-
* This method might use "effort" limits since they are often used as wild-card.
227-
* Check the documentation of the exact implementation for more details.
243+
* \note this way of interfacing would be useful for instances where the logging interface is not
244+
* available, for example in the ResourceManager or ResourceStorage classes.
245+
*/
246+
bool has_logging_interface() const { return node_logging_itf_ != nullptr; }
247+
248+
/** \brief Checks if the parameter interface is set.
249+
* \returns true if the parameter interface is available, otherwise false.
228250
*
229-
* \param[in,out] desired_joint_states joint state that should be adjusted to obey the limits.
230-
* \returns true if limits are enforced, otherwise false.
251+
* * \note this way of interfacing would be useful for instances where the logging interface is
252+
* not available, for example in the ResourceManager or ResourceStorage classes.
231253
*/
232-
virtual bool on_enforce(std::vector<double> & desired_joint_states) = 0;
254+
bool has_parameter_interface() const { return node_param_itf_ != nullptr; }
233255

234256
size_t number_of_joints_;
235257
std::vector<std::string> joint_names_;
236-
std::vector<LimitsType> joint_limits_;
258+
std::vector<joint_limits::JointLimits> joint_limits_;
259+
std::vector<joint_limits::SoftJointLimits> soft_joint_limits_;
237260
rclcpp::node_interfaces::NodeParametersInterface::SharedPtr node_param_itf_;
238261
rclcpp::node_interfaces::NodeLoggingInterface::SharedPtr node_logging_itf_;
239262

240263
private:
241264
rclcpp::node_interfaces::OnSetParametersCallbackHandle::SharedPtr parameter_callback_;
242-
realtime_tools::RealtimeBuffer<std::vector<LimitsType>> updated_limits_;
265+
realtime_tools::RealtimeBuffer<std::vector<joint_limits::JointLimits>> updated_limits_;
243266
};
244267

245268
} // namespace joint_limits

joint_limits/include/joint_limits/joint_limits.hpp

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -67,7 +67,7 @@ struct JointLimits
6767
bool has_effort_limits;
6868
bool angle_wraparound;
6969

70-
std::string to_string()
70+
std::string to_string() const
7171
{
7272
std::stringstream ss_output;
7373

@@ -124,7 +124,7 @@ struct SoftJointLimits
124124
double k_position;
125125
double k_velocity;
126126

127-
std::string to_string()
127+
std::string to_string() const
128128
{
129129
std::stringstream ss_output;
130130

0 commit comments

Comments
 (0)