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 67 commits into
base: master
Choose a base branch
from
Open
Show file tree
Hide file tree
Changes from all commits
Commits
Show all changes
67 commits
Select commit Hold shift + click to select a range
ff13549
make JointTrajectoryPoint as an input through the template argument
saikishor Apr 6, 2024
ad50d3c
check for node parameter interface before declaring and getting the p…
saikishor Apr 7, 2024
560b1f4
Added methods to check is the parameter and logging interfaces are se…
saikishor Apr 7, 2024
82f368a
add an init method parsing the limits directly in the init method
saikishor Apr 7, 2024
e7425d9
update the joint state limiter to use template typename in the header…
saikishor Apr 7, 2024
097004b
check the size of the joint limits and the joint names in the init me…
saikishor Apr 7, 2024
2340866
added joint range limiter library for individual joints control
saikishor Apr 7, 2024
a6f9e74
added compute_effort_limits method
saikishor Apr 7, 2024
a8e8fdd
update the velocity limits based on the position of the joint
saikishor Apr 7, 2024
c462fb6
fix the limits clamping in the methods
saikishor Apr 7, 2024
19b2fcc
Add proper acceleration limits bounding
saikishor Apr 7, 2024
47ddcfb
remove the enforce methods of the double vector as it can be handled …
saikishor Apr 16, 2024
f70a63d
Added comments to the has_logging_interface and has_parameter_interfa…
saikishor Apr 16, 2024
1822da5
remove the joint range limiter header and reuse it from the joint sat…
saikishor Apr 16, 2024
9706cf7
rename the plugin names to be more consistent with the types the use …
saikishor Apr 16, 2024
0a99d3a
Add first version of tests into the joint range limiter
saikishor Apr 17, 2024
e29ecab
fix the init check bug
saikishor Apr 17, 2024
b2197da
Apply formatting changes
saikishor Apr 17, 2024
6d7f4a5
update the joint range limiter test with case of only desired positio…
saikishor Apr 17, 2024
1dfb3b6
Added some minor fixes in the joint range limiter
saikishor Apr 17, 2024
ee0dbb7
Fill the data of actual or desired fields into the previous commands
saikishor Apr 17, 2024
f4cf1e0
reset the prev_data_ on initialization
saikishor Apr 17, 2024
9368deb
add test cases of the actual and desired position cases
saikishor Apr 17, 2024
a8f4538
Add tests for the case of no position limits
saikishor Apr 18, 2024
099f72d
add initial test cases for desired velocity only cases
saikishor Apr 18, 2024
1e0c4ee
Enforce wrt to the position limits only when the actual position valu…
saikishor Apr 18, 2024
b311570
change some asserts to expects
saikishor Apr 18, 2024
a5ae76b
Use lambdas for better testing
saikishor Apr 18, 2024
edaf362
If the joint is outside the position range, then don't let the joint …
saikishor Apr 18, 2024
11badf6
extend tests of acceleration limits also with and without actual posi…
saikishor Apr 18, 2024
526fcff
Add tests for the case of actuators with actual position state and ac…
saikishor Apr 18, 2024
3ffe034
remove unused test cases
saikishor Apr 18, 2024
ecbc1dd
pass by const reference and parse the optional actual position and ve…
saikishor Apr 18, 2024
06f9a21
Added tests for the effort case
saikishor Apr 18, 2024
75b1164
better conditioning for the acceleration limits enforcement
saikishor Apr 18, 2024
da8466f
Added tests for the desired acceleration case
saikishor Apr 18, 2024
48fcf8e
Add tests for the desired jerk test cases
saikishor Apr 18, 2024
66fa5b1
consider also the acceleration limits when computing the position lim…
saikishor Apr 18, 2024
834a9f6
Fix minor bug in the limit enforcement
saikishor Apr 18, 2024
9e58d61
better computation of the position limits
saikishor Apr 18, 2024
6471d5b
better combined desired references test
saikishor Apr 18, 2024
770820f
Remove LimitsType template from JointLimiterInterface
adriaroig Apr 22, 2024
9b8dbd4
Add SoftJointLimits in JointLimiterInterface
adriaroig Apr 22, 2024
e88ff9b
Move joint limits computation in a separate library
adriaroig Apr 25, 2024
eb0680e
Implement SoftJointLimiter class
adriaroig Apr 25, 2024
4bbdd48
Export JointInterfacesSoftLimiter in the joint_limiters.xml
adriaroig Apr 25, 2024
9948adb
Fix linking problem in test_joint_range_limiter
adriaroig Apr 25, 2024
3e17275
Create test_soft_joint_limiter.cpp
adriaroig Apr 25, 2024
ab2b9b2
Fix typo in plugins definition
adriaroig Apr 29, 2024
4459577
Rm soft_joint_limiter.hpp
adriaroig Apr 29, 2024
572a9a5
Derive SoiftJointLimiter from JointSaturationLimiter<JointControlInte…
adriaroig Apr 29, 2024
05d414f
Test SofJointLimiter in position
adriaroig Apr 29, 2024
b86fafa
Solve issues in SoftJointLimiter when prev_command is not defined
adriaroig Apr 29, 2024
91d3bfb
Test SoftJointLimiter in position and effort
adriaroig Apr 29, 2024
474ff5a
Test uses cases for SoftJointLimiter in velocity interface
adriaroig Apr 30, 2024
901381d
Format changes
adriaroig May 3, 2024
339e4d1
change copyright to PAL
saikishor May 6, 2024
58e5de8
add pre-comitting fixes
saikishor May 6, 2024
872c7ef
Add intermediate tests to fix the transition bug
saikishor May 7, 2024
b22ac9e
Fix the undefined behavior when lower bound is greater than upper bound
saikishor May 7, 2024
cdd0ef9
Add some documentation to the helpers
saikishor May 7, 2024
4c71c32
rename of SoftJointLimiter to JointSoftLimiter and some minor changes
saikishor Jul 19, 2024
80e7418
enable moving out of position limit if velocity is in "right" direction
mamueluth Jul 8, 2024
2977f57
warn everytime we reach the limit
mamueluth Jul 9, 2024
b724528
update the loguic to check if the actual position is within bounds an…
saikishor Jul 29, 2024
2a346b8
Remove unnecessary debug prints
saikishor Oct 11, 2024
2f91440
fix the soft limiting logic and add respective tests
saikishor Oct 11, 2024
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 @@ -43,15 +43,29 @@ ament_target_dependencies(joint_limiter_interface PUBLIC ${THIS_PACKAGE_INCLUDE_
# which is appropriate when building the dll but not consuming it.
target_compile_definitions(joint_limiter_interface PRIVATE "JOINT_LIMITS_BUILDING_DLL")

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})
# Causes the visibility macros to use dllexport rather than dllimport,
# which is appropriate when building the dll but not consuming it.
Expand Down Expand Up @@ -94,6 +108,24 @@ if(BUILD_TESTING)
rclcpp
)

ament_add_gtest(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_gtest(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 @@ -104,6 +136,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
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 "joint_limits/visibility_control.h"
#include "rclcpp/node.hpp"
Expand All @@ -29,9 +30,8 @@

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

template <typename LimitsType>
template <typename JointLimitsStateDataType>
class JointLimiterInterface
{
public:
Expand Down Expand Up @@ -69,55 +69,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 @@ -129,6 +132,34 @@ class JointLimiterInterface
return result;
}

/**
* Wrapper init method that accepts the joint names and their limits directly
*/
JOINT_LIMITS_PUBLIC 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 @@ -178,19 +209,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.
*/
JOINT_LIMITS_PUBLIC 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 @@ -221,27 +239,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.
*/
JOINT_LIMITS_PUBLIC 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
66 changes: 66 additions & 0 deletions joint_limits/include/joint_limits/joint_limiter_struct.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__JOINT_LIMITER_STRUCT_HPP_
#define JOINT_LIMITS__JOINT_LIMITER_STRUCT_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__JOINT_LIMITER_STRUCT_HPP_
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