Skip to content

Commit bb85eae

Browse files
destoglAndyZebijoua29gwalckchristophfroehlich
authored
[JointLimits] Add Saturation Joint Limiter that uses clamping method (#971)
--------- Co-authored-by: AndyZe <[email protected]> Co-authored-by: bijoua <[email protected]> Co-authored-by: Guillaume Walck <[email protected]> Co-authored-by: Christoph Fröhlich <[email protected]> Co-authored-by: Sai Kishor Kothakota <[email protected]> Co-authored-by: Manuel M <[email protected]>
1 parent f04443f commit bb85eae

12 files changed

+2002
-14
lines changed

joint_limits/CMakeLists.txt

Lines changed: 53 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -7,12 +7,16 @@ if(CMAKE_CXX_COMPILER_ID MATCHES "(GNU|Clang)")
77
endif()
88

99
set(THIS_PACKAGE_INCLUDE_DEPENDS
10+
pluginlib
11+
realtime_tools
1012
rclcpp
1113
rclcpp_lifecycle
14+
trajectory_msgs
1215
urdf
1316
)
1417

1518
find_package(ament_cmake REQUIRED)
19+
find_package(backward_ros REQUIRED)
1620
find_package(ament_cmake_gen_version_h REQUIRED)
1721
foreach(Dependency IN ITEMS ${THIS_PACKAGE_INCLUDE_DEPENDS})
1822
find_package(${Dependency} REQUIRED)
@@ -26,10 +30,42 @@ target_include_directories(joint_limits INTERFACE
2630
)
2731
ament_target_dependencies(joint_limits INTERFACE ${THIS_PACKAGE_INCLUDE_DEPENDS})
2832

33+
add_library(joint_limiter_interface SHARED
34+
src/joint_limiter_interface.cpp
35+
)
36+
target_compile_features(joint_limiter_interface PUBLIC cxx_std_17)
37+
target_include_directories(joint_limiter_interface PUBLIC
38+
$<BUILD_INTERFACE:${PROJECT_SOURCE_DIR}/include>
39+
$<INSTALL_INTERFACE:include/joint_limits>
40+
)
41+
ament_target_dependencies(joint_limiter_interface PUBLIC ${THIS_PACKAGE_INCLUDE_DEPENDS})
42+
# Causes the visibility macros to use dllexport rather than dllimport,
43+
# which is appropriate when building the dll but not consuming it.
44+
target_compile_definitions(joint_limiter_interface PRIVATE "JOINT_LIMITS_BUILDING_DLL")
45+
46+
47+
add_library(joint_saturation_limiter SHARED
48+
src/joint_saturation_limiter.cpp
49+
)
50+
target_compile_features(joint_saturation_limiter PUBLIC cxx_std_17)
51+
target_include_directories(joint_saturation_limiter PUBLIC
52+
$<BUILD_INTERFACE:${PROJECT_SOURCE_DIR}/include>
53+
$<INSTALL_INTERFACE:include/joint_limits>
54+
)
55+
ament_target_dependencies(joint_saturation_limiter PUBLIC ${THIS_PACKAGE_INCLUDE_DEPENDS})
56+
# Causes the visibility macros to use dllexport rather than dllimport,
57+
# which is appropriate when building the dll but not consuming it.
58+
target_compile_definitions(joint_saturation_limiter PRIVATE "JOINT_LIMITS_BUILDING_DLL")
59+
60+
pluginlib_export_plugin_description_file(joint_limits joint_limiters.xml)
2961

3062
if(BUILD_TESTING)
3163
find_package(ament_cmake_gtest REQUIRED)
64+
find_package(ament_cmake_gmock REQUIRED)
65+
find_package(generate_parameter_library REQUIRED)
3266
find_package(launch_testing_ament_cmake REQUIRED)
67+
find_package(pluginlib REQUIRED)
68+
find_package(rclcpp REQUIRED)
3369

3470
ament_add_gtest_executable(joint_limits_rosparam_test test/joint_limits_rosparam_test.cpp)
3571
target_link_libraries(joint_limits_rosparam_test joint_limits)
@@ -43,16 +79,31 @@ if(BUILD_TESTING)
4379
DESTINATION lib/joint_limits
4480
)
4581
install(
46-
FILES test/joint_limits_rosparam.yaml
82+
FILES test/joint_limits_rosparam.yaml test/joint_saturation_limiter_param.yaml
4783
DESTINATION share/joint_limits/test
4884
)
85+
86+
add_rostest_with_parameters_gmock(test_joint_saturation_limiter test/test_joint_saturation_limiter.cpp
87+
${CMAKE_CURRENT_SOURCE_DIR}/test/joint_saturation_limiter_param.yaml
88+
)
89+
target_include_directories(test_joint_saturation_limiter PRIVATE include)
90+
target_link_libraries(test_joint_saturation_limiter joint_limiter_interface)
91+
ament_target_dependencies(
92+
test_joint_saturation_limiter
93+
pluginlib
94+
rclcpp
95+
)
96+
4997
endif()
5098

5199
install(
52100
DIRECTORY include/
53101
DESTINATION include/joint_limits
54102
)
55-
install(TARGETS joint_limits
103+
install(TARGETS
104+
joint_limits
105+
joint_limiter_interface
106+
joint_saturation_limiter
56107
EXPORT export_joint_limits
57108
ARCHIVE DESTINATION lib
58109
LIBRARY DESTINATION lib
Lines changed: 250 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,250 @@
1+
// Copyright (c) 2024, Stogl Robotics Consulting UG (haftungsbeschränkt)
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 Denis Stogl
16+
17+
#ifndef JOINT_LIMITS__JOINT_LIMITER_INTERFACE_HPP_
18+
#define JOINT_LIMITS__JOINT_LIMITER_INTERFACE_HPP_
19+
20+
#include <string>
21+
#include <vector>
22+
23+
#include "joint_limits/joint_limits.hpp"
24+
#include "joint_limits/joint_limits_rosparam.hpp"
25+
#include "joint_limits/visibility_control.h"
26+
#include "rclcpp/node.hpp"
27+
#include "rclcpp_lifecycle/lifecycle_node.hpp"
28+
#include "realtime_tools/realtime_buffer.h"
29+
#include "trajectory_msgs/msg/joint_trajectory_point.hpp"
30+
31+
namespace joint_limits
32+
{
33+
using JointLimitsStateDataType = trajectory_msgs::msg::JointTrajectoryPoint;
34+
35+
template <typename LimitsType>
36+
class JointLimiterInterface
37+
{
38+
public:
39+
JOINT_LIMITS_PUBLIC JointLimiterInterface() = default;
40+
41+
JOINT_LIMITS_PUBLIC virtual ~JointLimiterInterface() = default;
42+
43+
/// Initialization of every JointLimiter.
44+
/**
45+
* Initialization of JointLimiter for defined joints with their names.
46+
* Robot description topic provides a topic name where URDF of the robot can be found.
47+
* This is needed to use joint limits from URDF (not implemented yet!).
48+
* Override this method only if initialization and reading joint limits should be adapted.
49+
* Otherwise, initialize your custom limiter in `on_limit` method.
50+
*
51+
* \param[in] joint_names names of joints where limits should be applied.
52+
* \param[in] param_itf node parameters interface object to access parameters.
53+
* \param[in] logging_itf node logging interface to log if error happens.
54+
* \param[in] robot_description_topic string of a topic where robot description is accessible.
55+
*/
56+
JOINT_LIMITS_PUBLIC virtual bool init(
57+
const std::vector<std::string> & joint_names,
58+
const rclcpp::node_interfaces::NodeParametersInterface::SharedPtr & param_itf,
59+
const rclcpp::node_interfaces::NodeLoggingInterface::SharedPtr & logging_itf,
60+
const std::string & robot_description_topic = "/robot_description")
61+
{
62+
number_of_joints_ = joint_names.size();
63+
joint_names_ = joint_names;
64+
joint_limits_.resize(number_of_joints_);
65+
node_param_itf_ = param_itf;
66+
node_logging_itf_ = logging_itf;
67+
68+
bool result = true;
69+
70+
// TODO(destogl): get limits from URDF
71+
72+
// Initialize and get joint limits from parameter server
73+
for (size_t i = 0; i < number_of_joints_; ++i)
74+
{
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());
94+
}
95+
updated_limits_.writeFromNonRT(joint_limits_);
96+
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;
101+
102+
std::vector<LimitsType> updated_joint_limits = joint_limits_;
103+
bool changed = false;
104+
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+
}
110+
111+
if (changed)
112+
{
113+
updated_limits_.writeFromNonRT(updated_joint_limits);
114+
RCLCPP_INFO(node_logging_itf_->get_logger(), "Limits are dynamically updated!");
115+
}
116+
117+
return set_parameters_result;
118+
};
119+
120+
parameter_callback_ =
121+
node_param_itf_->add_on_set_parameters_callback(on_parameter_event_callback);
122+
123+
if (result)
124+
{
125+
result = on_init();
126+
}
127+
128+
(void)robot_description_topic; // avoid linters output
129+
130+
return result;
131+
}
132+
133+
/**
134+
* Wrapper init method that accepts pointer to the Node.
135+
* For details see other init method.
136+
*/
137+
JOINT_LIMITS_PUBLIC virtual bool init(
138+
const std::vector<std::string> & joint_names, const rclcpp::Node::SharedPtr & node,
139+
const std::string & robot_description_topic = "/robot_description")
140+
{
141+
return init(
142+
joint_names, node->get_node_parameters_interface(), node->get_node_logging_interface(),
143+
robot_description_topic);
144+
}
145+
146+
/**
147+
* Wrapper init method that accepts pointer to the LifecycleNode.
148+
* For details see other init method.
149+
*/
150+
JOINT_LIMITS_PUBLIC virtual bool init(
151+
const std::vector<std::string> & joint_names,
152+
const rclcpp_lifecycle::LifecycleNode::SharedPtr & lifecycle_node,
153+
const std::string & robot_description_topic = "/robot_description")
154+
{
155+
return init(
156+
joint_names, lifecycle_node->get_node_parameters_interface(),
157+
lifecycle_node->get_node_logging_interface(), robot_description_topic);
158+
}
159+
160+
JOINT_LIMITS_PUBLIC virtual bool configure(const JointLimitsStateDataType & current_joint_states)
161+
{
162+
return on_configure(current_joint_states);
163+
}
164+
165+
/** \brief Enforce joint limits to desired joint state for multiple physical quantities.
166+
*
167+
* Generic enforce method that calls implementation-specific `on_enforce` method.
168+
*
169+
* \param[in] current_joint_states current joint states a robot is in.
170+
* \param[in,out] desired_joint_states joint state that should be adjusted to obey the limits.
171+
* \param[in] dt time delta to calculate missing integrals and derivation in joint limits.
172+
* \returns true if limits are enforced, otherwise false.
173+
*/
174+
JOINT_LIMITS_PUBLIC virtual bool enforce(
175+
JointLimitsStateDataType & current_joint_states,
176+
JointLimitsStateDataType & desired_joint_states, const rclcpp::Duration & dt)
177+
{
178+
joint_limits_ = *(updated_limits_.readFromRT());
179+
return on_enforce(current_joint_states, desired_joint_states, dt);
180+
}
181+
182+
/** \brief Enforce joint limits to desired joint state for single physical quantity.
183+
*
184+
* Generic enforce method that calls implementation-specific `on_enforce` method.
185+
*
186+
* \param[in,out] desired_joint_states joint state that should be adjusted to obey the limits.
187+
* \returns true if limits are enforced, otherwise false.
188+
*/
189+
JOINT_LIMITS_PUBLIC virtual bool enforce(std::vector<double> & desired_joint_states)
190+
{
191+
joint_limits_ = *(updated_limits_.readFromRT());
192+
return on_enforce(desired_joint_states);
193+
}
194+
195+
protected:
196+
/** \brief Method is realized by an implementation.
197+
*
198+
* Implementation-specific initialization of limiter's internal states and libraries.
199+
* \returns true if initialization was successful, otherwise false.
200+
*/
201+
JOINT_LIMITS_PUBLIC virtual bool on_init() = 0;
202+
203+
/** \brief Method is realized by an implementation.
204+
*
205+
* Implementation-specific configuration of limiter's internal states and libraries.
206+
* \returns true if initialization was successful, otherwise false.
207+
*/
208+
JOINT_LIMITS_PUBLIC virtual bool on_configure(
209+
const JointLimitsStateDataType & current_joint_states) = 0;
210+
211+
/** \brief Method is realized by an implementation.
212+
*
213+
* Filter-specific implementation of the joint limits enforce algorithm for multiple dependent
214+
* physical quantities.
215+
*
216+
* \param[in] current_joint_states current joint states a robot is in.
217+
* \param[in,out] desired_joint_states joint state that should be adjusted to obey the limits.
218+
* \param[in] dt time delta to calculate missing integrals and derivation in joint limits.
219+
* \returns true if limits are enforced, otherwise false.
220+
*/
221+
JOINT_LIMITS_PUBLIC virtual bool on_enforce(
222+
JointLimitsStateDataType & current_joint_states,
223+
JointLimitsStateDataType & desired_joint_states, const rclcpp::Duration & dt) = 0;
224+
225+
/** \brief Method is realized by an implementation.
226+
*
227+
* Filter-specific implementation of the joint limits enforce algorithm for single physical
228+
* quantity.
229+
* This method might use "effort" limits since they are often used as wild-card.
230+
* Check the documentation of the exact implementation for more details.
231+
*
232+
* \param[in,out] desired_joint_states joint state that should be adjusted to obey the limits.
233+
* \returns true if limits are enforced, otherwise false.
234+
*/
235+
JOINT_LIMITS_PUBLIC virtual bool on_enforce(std::vector<double> & desired_joint_states) = 0;
236+
237+
size_t number_of_joints_;
238+
std::vector<std::string> joint_names_;
239+
std::vector<LimitsType> joint_limits_;
240+
rclcpp::node_interfaces::NodeParametersInterface::SharedPtr node_param_itf_;
241+
rclcpp::node_interfaces::NodeLoggingInterface::SharedPtr node_logging_itf_;
242+
243+
private:
244+
rclcpp::node_interfaces::OnSetParametersCallbackHandle::SharedPtr parameter_callback_;
245+
realtime_tools::RealtimeBuffer<std::vector<LimitsType>> updated_limits_;
246+
};
247+
248+
} // namespace joint_limits
249+
250+
#endif // JOINT_LIMITS__JOINT_LIMITER_INTERFACE_HPP_

0 commit comments

Comments
 (0)