Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Add joint limiter interface plugins to enforce limits defined in the URDF #1526

Open
wants to merge 72 commits into
base: master
Choose a base branch
from
Open
Show file tree
Hide file tree
Changes from all commits
Commits
Show all changes
72 commits
Select commit Hold shift + click to select a range
011fabe
make JointTrajectoryPoint as an input through the template argument
saikishor Apr 6, 2024
9f34da1
check for node parameter interface before declaring and getting the p…
saikishor Apr 7, 2024
cd7abd0
Added methods to check is the parameter and logging interfaces are se…
saikishor Apr 7, 2024
797076d
add an init method parsing the limits directly in the init method
saikishor Apr 7, 2024
8301b59
update the joint state limiter to use template typename in the header…
saikishor Apr 7, 2024
d80929d
check the size of the joint limits and the joint names in the init me…
saikishor Apr 7, 2024
ea9bda4
added joint range limiter library for individual joints control
saikishor Apr 7, 2024
42fb8c7
added compute_effort_limits method
saikishor Apr 7, 2024
a780465
update the velocity limits based on the position of the joint
saikishor Apr 7, 2024
088fa6d
fix the limits clamping in the methods
saikishor Apr 7, 2024
28f7e3e
Add proper acceleration limits bounding
saikishor Apr 7, 2024
0944328
remove the enforce methods of the double vector as it can be handled …
saikishor Apr 16, 2024
dfda4b2
Added comments to the has_logging_interface and has_parameter_interfa…
saikishor Apr 16, 2024
87714fb
remove the joint range limiter header and reuse it from the joint sat…
saikishor Apr 16, 2024
7a4ce74
rename the plugin names to be more consistent with the types the use …
saikishor Apr 16, 2024
98122ea
Add first version of tests into the joint range limiter
saikishor Apr 17, 2024
02796bf
fix the init check bug
saikishor Apr 17, 2024
55bb040
Apply formatting changes
saikishor Apr 17, 2024
eab6689
update the joint range limiter test with case of only desired positio…
saikishor Apr 17, 2024
7fe2336
Added some minor fixes in the joint range limiter
saikishor Apr 17, 2024
9269842
Fill the data of actual or desired fields into the previous commands
saikishor Apr 17, 2024
f94efc2
reset the prev_data_ on initialization
saikishor Apr 17, 2024
fa90bfa
add test cases of the actual and desired position cases
saikishor Apr 17, 2024
b9918e5
Add tests for the case of no position limits
saikishor Apr 18, 2024
59b697d
add initial test cases for desired velocity only cases
saikishor Apr 18, 2024
372b0d4
Enforce wrt to the position limits only when the actual position valu…
saikishor Apr 18, 2024
560d1bc
change some asserts to expects
saikishor Apr 18, 2024
5b2c0b4
Use lambdas for better testing
saikishor Apr 18, 2024
0dde6a9
If the joint is outside the position range, then don't let the joint …
saikishor Apr 18, 2024
80308b3
extend tests of acceleration limits also with and without actual posi…
saikishor Apr 18, 2024
92d153e
Add tests for the case of actuators with actual position state and ac…
saikishor Apr 18, 2024
a2d7258
remove unused test cases
saikishor Apr 18, 2024
c1e29c9
pass by const reference and parse the optional actual position and ve…
saikishor Apr 18, 2024
3746584
Added tests for the effort case
saikishor Apr 18, 2024
1eb5bad
better conditioning for the acceleration limits enforcement
saikishor Apr 18, 2024
5c86100
Added tests for the desired acceleration case
saikishor Apr 18, 2024
90cd75e
Add tests for the desired jerk test cases
saikishor Apr 18, 2024
71d311d
consider also the acceleration limits when computing the position lim…
saikishor Apr 18, 2024
ffe9aeb
Fix minor bug in the limit enforcement
saikishor Apr 18, 2024
cd60d88
better computation of the position limits
saikishor Apr 18, 2024
bde797a
better combined desired references test
saikishor Apr 18, 2024
1d2faa9
Remove LimitsType template from JointLimiterInterface
adriaroig Apr 22, 2024
4645773
Add SoftJointLimits in JointLimiterInterface
adriaroig Apr 22, 2024
3192bc6
Move joint limits computation in a separate library
adriaroig Apr 25, 2024
c9f36b0
Implement SoftJointLimiter class
adriaroig Apr 25, 2024
1e5dbf0
Export JointInterfacesSoftLimiter in the joint_limiters.xml
adriaroig Apr 25, 2024
02f5760
Fix linking problem in test_joint_range_limiter
adriaroig Apr 25, 2024
6f02f9f
Create test_soft_joint_limiter.cpp
adriaroig Apr 25, 2024
c4ea119
Fix typo in plugins definition
adriaroig Apr 29, 2024
9f31c6a
Rm soft_joint_limiter.hpp
adriaroig Apr 29, 2024
b58bd10
Derive SoiftJointLimiter from JointSaturationLimiter<JointControlInte…
adriaroig Apr 29, 2024
00eb01d
Test SofJointLimiter in position
adriaroig Apr 29, 2024
2c6d1bd
Solve issues in SoftJointLimiter when prev_command is not defined
adriaroig Apr 29, 2024
764d68b
Test SoftJointLimiter in position and effort
adriaroig Apr 29, 2024
f30ce41
Test uses cases for SoftJointLimiter in velocity interface
adriaroig Apr 30, 2024
c8d9eec
Format changes
adriaroig May 3, 2024
7d6ea96
change copyright to PAL
saikishor May 6, 2024
b828b13
add pre-comitting fixes
saikishor May 6, 2024
45328dd
Add intermediate tests to fix the transition bug
saikishor May 7, 2024
b2ee4d8
Fix the undefined behavior when lower bound is greater than upper bound
saikishor May 7, 2024
8d147a1
Add some documentation to the helpers
saikishor May 7, 2024
a4567d4
rename of SoftJointLimiter to JointSoftLimiter and some minor changes
saikishor Jul 19, 2024
a42c972
enable moving out of position limit if velocity is in "right" direction
mamueluth Jul 8, 2024
46395e3
warn everytime we reach the limit
mamueluth Jul 9, 2024
dc64739
update the loguic to check if the actual position is within bounds an…
saikishor Jul 29, 2024
415f535
Remove unnecessary debug prints
saikishor Oct 11, 2024
2a258cf
fix the soft limiting logic and add respective tests
saikishor Oct 11, 2024
226a855
Apply suggestions from code review
saikishor Dec 4, 2024
08f09eb
Rename the joint_limiter_struct.hpp to data_structures.hpp
saikishor Dec 4, 2024
296f992
improve documentation of the helper methods
saikishor Dec 4, 2024
fffd7e4
Merge branch 'master' into add/sw_joint_limiter
saikishor Jan 1, 2025
753133d
Fix other visibility macros and pre-commit fixes
saikishor Jan 1, 2025
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
33 changes: 33 additions & 0 deletions joint_limits/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -44,14 +44,28 @@ target_include_directories(joint_limiter_interface PUBLIC
)
ament_target_dependencies(joint_limiter_interface PUBLIC ${THIS_PACKAGE_INCLUDE_DEPENDS})

add_library(joint_limits_helpers SHARED
src/joint_limits_helpers.cpp
)
target_compile_features(joint_limits_helpers PUBLIC cxx_std_17)
target_include_directories(joint_limits_helpers PUBLIC
$<BUILD_INTERFACE:${PROJECT_SOURCE_DIR}/include>
$<INSTALL_INTERFACE:include/joint_limits>
)
ament_target_dependencies(joint_limits_helpers PUBLIC ${THIS_PACKAGE_INCLUDE_DEPENDS})

add_library(joint_saturation_limiter SHARED
src/joint_saturation_limiter.cpp
src/joint_range_limiter.cpp
src/joint_soft_limiter.cpp
)
target_compile_features(joint_saturation_limiter PUBLIC cxx_std_17)
target_include_directories(joint_saturation_limiter PUBLIC
$<BUILD_INTERFACE:${PROJECT_SOURCE_DIR}/include>
$<INSTALL_INTERFACE:include/joint_limits>
)
target_link_libraries(joint_saturation_limiter PUBLIC joint_limits_helpers)

ament_target_dependencies(joint_saturation_limiter PUBLIC ${THIS_PACKAGE_INCLUDE_DEPENDS})

pluginlib_export_plugin_description_file(joint_limits joint_limiters.xml)
Expand Down Expand Up @@ -91,6 +105,24 @@ if(BUILD_TESTING)
rclcpp
)

ament_add_gmock(test_joint_range_limiter test/test_joint_range_limiter.cpp)
target_include_directories(test_joint_range_limiter PRIVATE include)
target_link_libraries(test_joint_range_limiter joint_limiter_interface)
ament_target_dependencies(
test_joint_range_limiter
pluginlib
rclcpp
)

ament_add_gmock(test_joint_soft_limiter test/test_joint_soft_limiter.cpp)
target_include_directories(test_joint_soft_limiter PRIVATE include)
target_link_libraries(test_joint_soft_limiter joint_limiter_interface)
ament_target_dependencies(
test_joint_soft_limiter
pluginlib
rclcpp
)

endif()

install(
Expand All @@ -101,6 +133,7 @@ install(TARGETS
joint_limits
joint_limiter_interface
joint_saturation_limiter
joint_limits_helpers
EXPORT export_joint_limits
ARCHIVE DESTINATION lib
LIBRARY DESTINATION lib
Expand Down
66 changes: 66 additions & 0 deletions joint_limits/include/joint_limits/data_structures.hpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,66 @@
// Copyright 2024 PAL Robotics S.L.
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
// You may obtain a copy of the License at
//
// http://www.apache.org/licenses/LICENSE-2.0
//
// Unless required by applicable law or agreed to in writing, software
// distributed under the License is distributed on an "AS IS" BASIS,
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
// See the License for the specific language governing permissions and
// limitations under the License.

/// \author Sai Kishor Kothakota

#ifndef JOINT_LIMITS__DATA_STRUCTURES_HPP_
#define JOINT_LIMITS__DATA_STRUCTURES_HPP_

#include <memory>
#include <optional>
#include <string>

namespace joint_limits
{

struct JointControlInterfacesData
{
std::string joint_name;
std::optional<double> position = std::nullopt;
std::optional<double> velocity = std::nullopt;
std::optional<double> effort = std::nullopt;
std::optional<double> acceleration = std::nullopt;
std::optional<double> jerk = std::nullopt;

bool has_data() const
{
return has_position() || has_velocity() || has_effort() || has_acceleration() || has_jerk();
}

bool has_position() const { return position.has_value(); }

bool has_velocity() const { return velocity.has_value(); }

bool has_effort() const { return effort.has_value(); }

bool has_acceleration() const { return acceleration.has_value(); }

bool has_jerk() const { return jerk.has_value(); }
};

struct JointInterfacesCommandLimiterData
{
std::string joint_name;
JointControlInterfacesData actual;
JointControlInterfacesData command;
JointControlInterfacesData prev_command;
JointControlInterfacesData limited;

bool has_actual_data() const { return actual.has_data(); }

bool has_command_data() const { return command.has_data(); }
};

} // namespace joint_limits
#endif // JOINT_LIMITS__DATA_STRUCTURES_HPP_
153 changes: 88 additions & 65 deletions joint_limits/include/joint_limits/joint_limiter_interface.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -20,6 +20,7 @@
#include <string>
#include <vector>

#include "joint_limits/joint_limits.hpp"
#include "joint_limits/joint_limits_rosparam.hpp"
#include "rclcpp/node.hpp"
#include "rclcpp_lifecycle/lifecycle_node.hpp"
Expand All @@ -28,9 +29,8 @@

namespace joint_limits
{
using JointLimitsStateDataType = trajectory_msgs::msg::JointTrajectoryPoint;

template <typename LimitsType>
template <typename JointLimitsStateDataType>
class JointLimiterInterface
{
public:
Expand Down Expand Up @@ -68,55 +68,58 @@ class JointLimiterInterface
// TODO(destogl): get limits from URDF
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

I think this is not needed anymore. Am I right? Do we want to get here limits from URDF? This might make sense to parse URDF limits also in the controller if this are required.


// Initialize and get joint limits from parameter server
for (size_t i = 0; i < number_of_joints_; ++i)
if (has_parameter_interface())
{
if (!declare_parameters(joint_names[i], node_param_itf_, node_logging_itf_))
{
RCLCPP_ERROR(
node_logging_itf_->get_logger(),
"JointLimiter: Joint '%s': parameter declaration has failed", joint_names[i].c_str());
result = false;
break;
}
if (!get_joint_limits(joint_names[i], node_param_itf_, node_logging_itf_, joint_limits_[i]))
for (size_t i = 0; i < number_of_joints_; ++i)
{
RCLCPP_ERROR(
node_logging_itf_->get_logger(),
"JointLimiter: Joint '%s': getting parameters has failed", joint_names[i].c_str());
result = false;
break;
if (!declare_parameters(joint_names[i], node_param_itf_, node_logging_itf_))
{
RCLCPP_ERROR(
node_logging_itf_->get_logger(),
"JointLimiter: Joint '%s': parameter declaration has failed", joint_names[i].c_str());
result = false;
break;
}
if (!get_joint_limits(joint_names[i], node_param_itf_, node_logging_itf_, joint_limits_[i]))
{
RCLCPP_ERROR(
node_logging_itf_->get_logger(),
"JointLimiter: Joint '%s': getting parameters has failed", joint_names[i].c_str());
result = false;
break;
}
RCLCPP_INFO(
node_logging_itf_->get_logger(), "Limits for joint %zu (%s) are:\n%s", i,
joint_names[i].c_str(), joint_limits_[i].to_string().c_str());
}
RCLCPP_INFO(
node_logging_itf_->get_logger(), "Limits for joint %zu (%s) are:\n%s", i,
joint_names[i].c_str(), joint_limits_[i].to_string().c_str());
}
updated_limits_.writeFromNonRT(joint_limits_);
updated_limits_.writeFromNonRT(joint_limits_);

auto on_parameter_event_callback = [this](const std::vector<rclcpp::Parameter> & parameters)
{
rcl_interfaces::msg::SetParametersResult set_parameters_result;
set_parameters_result.successful = true;
auto on_parameter_event_callback = [this](const std::vector<rclcpp::Parameter> & parameters)
{
rcl_interfaces::msg::SetParametersResult set_parameters_result;
set_parameters_result.successful = true;

std::vector<LimitsType> updated_joint_limits = joint_limits_;
bool changed = false;
std::vector<joint_limits::JointLimits> updated_joint_limits = joint_limits_;
bool changed = false;

for (size_t i = 0; i < number_of_joints_; ++i)
{
changed |= joint_limits::check_for_limits_update(
joint_names_[i], parameters, node_logging_itf_, updated_joint_limits[i]);
}
for (size_t i = 0; i < number_of_joints_; ++i)
{
changed |= joint_limits::check_for_limits_update(
joint_names_[i], parameters, node_logging_itf_, updated_joint_limits[i]);
}

if (changed)
{
updated_limits_.writeFromNonRT(updated_joint_limits);
RCLCPP_INFO(node_logging_itf_->get_logger(), "Limits are dynamically updated!");
}
if (changed)
{
updated_limits_.writeFromNonRT(updated_joint_limits);
RCLCPP_INFO(node_logging_itf_->get_logger(), "Limits are dynamically updated!");
}

return set_parameters_result;
};
return set_parameters_result;
};

parameter_callback_ =
node_param_itf_->add_on_set_parameters_callback(on_parameter_event_callback);
parameter_callback_ =
node_param_itf_->add_on_set_parameters_callback(on_parameter_event_callback);
}

if (result)
{
Expand All @@ -128,6 +131,34 @@ class JointLimiterInterface
return result;
}

/**
* Wrapper init method that accepts the joint names and their limits directly
*/
virtual bool init(
const std::vector<std::string> & joint_names,
const std::vector<joint_limits::JointLimits> & joint_limits,
const std::vector<joint_limits::SoftJointLimits> & soft_joint_limits,
const rclcpp::node_interfaces::NodeParametersInterface::SharedPtr & param_itf,
const rclcpp::node_interfaces::NodeLoggingInterface::SharedPtr & logging_itf)
{
number_of_joints_ = joint_names.size();
joint_names_ = joint_names;
joint_limits_ = joint_limits;
soft_joint_limits_ = soft_joint_limits;
node_param_itf_ = param_itf;
node_logging_itf_ = logging_itf;
updated_limits_.writeFromNonRT(joint_limits_);

if ((number_of_joints_ != joint_limits_.size()) && has_logging_interface())
{
RCLCPP_ERROR(
node_logging_itf_->get_logger(),
"JointLimiter: Number of joint names and limits do not match: %zu != %zu",
number_of_joints_, joint_limits_.size());
}
return (number_of_joints_ == joint_limits_.size()) && on_init();
}

/**
* Wrapper init method that accepts pointer to the Node.
* For details see other init method.
Expand Down Expand Up @@ -177,19 +208,6 @@ class JointLimiterInterface
return on_enforce(current_joint_states, desired_joint_states, dt);
}

/** \brief Enforce joint limits to desired joint state for single physical quantity.
*
* Generic enforce method that calls implementation-specific `on_enforce` method.
*
* \param[in,out] desired_joint_states joint state that should be adjusted to obey the limits.
* \returns true if limits are enforced, otherwise false.
*/
virtual bool enforce(std::vector<double> & desired_joint_states)
{
joint_limits_ = *(updated_limits_.readFromRT());
return on_enforce(desired_joint_states);
}

protected:
/** \brief Method is realized by an implementation.
*
Expand Down Expand Up @@ -219,27 +237,32 @@ class JointLimiterInterface
JointLimitsStateDataType & current_joint_states,
JointLimitsStateDataType & desired_joint_states, const rclcpp::Duration & dt) = 0;

/** \brief Method is realized by an implementation.
/** \brief Checks if the logging interface is set.
* \returns true if the logging interface is available, otherwise false.
*
* Filter-specific implementation of the joint limits enforce algorithm for single physical
* quantity.
* This method might use "effort" limits since they are often used as wild-card.
* Check the documentation of the exact implementation for more details.
* \note this way of interfacing would be useful for instances where the logging interface is not
* available, for example in the ResourceManager or ResourceStorage classes.
*/
bool has_logging_interface() const { return node_logging_itf_ != nullptr; }

/** \brief Checks if the parameter interface is set.
* \returns true if the parameter interface is available, otherwise false.
*
* \param[in,out] desired_joint_states joint state that should be adjusted to obey the limits.
* \returns true if limits are enforced, otherwise false.
* * \note this way of interfacing would be useful for instances where the logging interface is
* not available, for example in the ResourceManager or ResourceStorage classes.
*/
virtual bool on_enforce(std::vector<double> & desired_joint_states) = 0;
bool has_parameter_interface() const { return node_param_itf_ != nullptr; }

size_t number_of_joints_;
std::vector<std::string> joint_names_;
std::vector<LimitsType> joint_limits_;
std::vector<joint_limits::JointLimits> joint_limits_;
std::vector<joint_limits::SoftJointLimits> soft_joint_limits_;
rclcpp::node_interfaces::NodeParametersInterface::SharedPtr node_param_itf_;
rclcpp::node_interfaces::NodeLoggingInterface::SharedPtr node_logging_itf_;

private:
rclcpp::node_interfaces::OnSetParametersCallbackHandle::SharedPtr parameter_callback_;
realtime_tools::RealtimeBuffer<std::vector<LimitsType>> updated_limits_;
realtime_tools::RealtimeBuffer<std::vector<joint_limits::JointLimits>> updated_limits_;
};

} // namespace joint_limits
Expand Down
4 changes: 2 additions & 2 deletions joint_limits/include/joint_limits/joint_limits.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -67,7 +67,7 @@ struct JointLimits
bool has_effort_limits;
bool angle_wraparound;

std::string to_string()
std::string to_string() const
{
std::stringstream ss_output;

Expand Down Expand Up @@ -124,7 +124,7 @@ struct SoftJointLimits
double k_position;
double k_velocity;

std::string to_string()
std::string to_string() const
{
std::stringstream ss_output;

Expand Down
Loading
Loading