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 Ruckig-based joint limiter that limits jerk. #970

Draft
wants to merge 43 commits into
base: master
Choose a base branch
from
Draft
Show file tree
Hide file tree
Changes from all commits
Commits
Show all changes
43 commits
Select commit Hold shift + click to select a range
5d81a98
Added controller parameters structures and movement interfaces.
destogl Sep 17, 2021
aa004a3
Added joint limiter plugins.
destogl Sep 18, 2021
bbd9d59
Debug Ruckig JointLimiter.
destogl Sep 24, 2021
ee7faf2
Modify simple joint limiting plugin (same as changes to moveit2 filte…
destogl Feb 9, 2023
a07c7ac
Remove all Ruckig-limiter files.
destogl Mar 16, 2023
5260724
Merge branch 'master' into add-simple-joint-limiter
destogl Mar 16, 2023
6675e7d
Merge branch 'master' into add-simple-joint-limiter
destogl Mar 23, 2023
ceb3beb
Merge branch 'master' into add-simple-joint-limiter
destogl Apr 13, 2023
f939193
Apply suggestions from code review
destogl Apr 13, 2023
d7db070
Remove definition of movement interface because the concept is not us…
destogl Apr 13, 2023
4054b04
Polish out some stuff using "GH Programming"
destogl Apr 13, 2023
456c715
Polish out some stuff using "GH Programming"
destogl Apr 13, 2023
8b33153
Add SimpleJointLimiter as plugin into controllers.
destogl Apr 24, 2023
cbfc06a
Version with deceleration for simple joint limiter.
destogl May 4, 2023
2777c61
Merge branch 'master' into add-simple-joint-limiter
destogl May 9, 2023
b401169
Formatting and comment to check.
destogl May 12, 2023
e6f52d7
Added test of joint_limiter
gwalck Jun 7, 2023
7bfc94e
Fixed deceleration limit application
gwalck Jun 7, 2023
c338b8c
Updated authorship
gwalck Jun 9, 2023
6e0e6c5
Split test, apply review changes, add future tests
gwalck Jun 9, 2023
cfc8fe5
Applied review comment, added 2 tests & fixed typo
gwalck Jun 12, 2023
186c66e
Improved close to limit trigger
gwalck Jun 12, 2023
d6db2a1
Merge branch 'master' into add-simple-joint-limiter
destogl Jun 13, 2023
1e393f3
Merge branch 'master' into add-simple-joint-limiter
destogl Jun 27, 2023
1749f6d
Update joint_limits/src/simple_joint_limiter.cpp
destogl Jun 27, 2023
e254294
Fix formatting.
destogl Jun 29, 2023
7186e9e
Restore Rucking Limiter.
destogl Jun 29, 2023
2cb1cdf
Fixed ruckig linking
gwalck Jul 3, 2023
8a46d4c
Fixed max_jerk initialization
gwalck Jul 3, 2023
79b7579
Added protection from invalid desired_positions
gwalck Jul 3, 2023
1352e30
Removed misleading comment
gwalck Jul 3, 2023
1ff2bfe
Fixed return value to allow working results
gwalck Jul 3, 2023
e3085af
Added tests (some fail for unknown reason)
gwalck Jul 3, 2023
817a379
Added limitation for max vel and max acc
gwalck Jul 3, 2023
3d273ef
Added a warning for deceleration limits
gwalck Jul 3, 2023
e642569
Activated pos test which expect no limits
gwalck Jul 3, 2023
1239e14
Removed deceleration test (not supported)
gwalck Jul 3, 2023
156d590
Fixed negative velocity test
gwalck Jul 4, 2023
bd5d01c
Removed brake test which cannot be triggered
gwalck Jul 4, 2023
6f47cf9
Fixed acceleration test
gwalck Jul 4, 2023
3714343
Avoid failures due to double precision errors
gwalck Jul 4, 2023
a04788b
Fixed enforce in case ruckig fails
gwalck Jul 4, 2023
2a8525f
Added and fixed tests
gwalck Jul 4, 2023
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
Original file line number Diff line number Diff line change
Expand Up @@ -15,15 +15,17 @@
#ifndef HARDWARE_INTERFACE__TYPES__HARDWARE_INTERFACE_TYPE_VALUES_HPP_
#define HARDWARE_INTERFACE__TYPES__HARDWARE_INTERFACE_TYPE_VALUES_HPP_

#include <vector>

namespace hardware_interface
{
/// Constant defining position interface
/// Constant defining position interface name
constexpr char HW_IF_POSITION[] = "position";
/// Constant defining velocity interface
/// Constant defining velocity interface name
constexpr char HW_IF_VELOCITY[] = "velocity";
/// Constant defining acceleration interface
/// Constant defining acceleration interface name
constexpr char HW_IF_ACCELERATION[] = "acceleration";
/// Constant defining effort interface
/// Constant defining effort interface name
constexpr char HW_IF_EFFORT[] = "effort";
} // namespace hardware_interface

Expand Down
54 changes: 52 additions & 2 deletions joint_limits/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -6,11 +6,14 @@ if(CMAKE_CXX_COMPILER_ID MATCHES "(GNU|Clang)")
endif()

set(THIS_PACKAGE_INCLUDE_DEPENDS
pluginlib
rclcpp
rclcpp_lifecycle
trajectory_msgs
)

find_package(ament_cmake REQUIRED)
find_package(backward_ros REQUIRED)
foreach(Dependency IN ITEMS ${THIS_PACKAGE_INCLUDE_DEPENDS})
find_package(${Dependency} REQUIRED)
endforeach()
Expand All @@ -23,10 +26,42 @@ target_include_directories(joint_limits INTERFACE
)
ament_target_dependencies(joint_limits INTERFACE ${THIS_PACKAGE_INCLUDE_DEPENDS})

add_library(joint_limiter_interface SHARED
src/joint_limiter_interface.cpp
)
target_compile_features(joint_limiter_interface PUBLIC cxx_std_17)
target_include_directories(joint_limiter_interface PUBLIC
$<BUILD_INTERFACE:${PROJECT_SOURCE_DIR}/include>
$<INSTALL_INTERFACE:include/joint_limits>
)
ament_target_dependencies(joint_limiter_interface 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.
target_compile_definitions(joint_limiter_interface PRIVATE "JOINT_LIMITS_BUILDING_DLL")


add_library(simple_joint_limiter SHARED
src/simple_joint_limiter.cpp
)
target_compile_features(simple_joint_limiter PUBLIC cxx_std_17)
target_include_directories(simple_joint_limiter PUBLIC
$<BUILD_INTERFACE:${PROJECT_SOURCE_DIR}/include>
$<INSTALL_INTERFACE:include/joint_limits>
)
ament_target_dependencies(simple_joint_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.
target_compile_definitions(simple_joint_limiter PRIVATE "JOINT_LIMITS_BUILDING_DLL")

pluginlib_export_plugin_description_file(joint_limits joint_limiters.xml)

if(BUILD_TESTING)
find_package(ament_cmake_gtest REQUIRED)
find_package(ament_cmake_gmock REQUIRED)
find_package(generate_parameter_library REQUIRED)
find_package(launch_testing_ament_cmake REQUIRED)
find_package(pluginlib REQUIRED)
find_package(rclcpp REQUIRED)

ament_add_gtest_executable(joint_limits_rosparam_test test/joint_limits_rosparam_test.cpp)
target_link_libraries(joint_limits_rosparam_test joint_limits)
Expand All @@ -37,16 +72,31 @@ if(BUILD_TESTING)
DESTINATION lib/joint_limits
)
install(
FILES test/joint_limits_rosparam.yaml
FILES test/joint_limits_rosparam.yaml test/simple_joint_limiter_param.yaml
DESTINATION share/joint_limits/test
)

add_rostest_with_parameters_gmock(test_simple_joint_limiter test/test_simple_joint_limiter.cpp
${CMAKE_CURRENT_SOURCE_DIR}/test/simple_joint_limiter_param.yaml
)
target_include_directories(test_simple_joint_limiter PRIVATE include)
target_link_libraries(test_simple_joint_limiter joint_limiter_interface)
ament_target_dependencies(
test_simple_joint_limiter
pluginlib
rclcpp
)

endif()

install(
DIRECTORY include/
DESTINATION include/joint_limits
)
install(TARGETS joint_limits
install(TARGETS
joint_limits
joint_limiter_interface
simple_joint_limiter
EXPORT export_joint_limits
ARCHIVE DESTINATION lib
LIBRARY DESTINATION lib
Expand Down
181 changes: 181 additions & 0 deletions joint_limits/include/joint_limits/joint_limiter_interface.hpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,181 @@
// Copyright (c) 2023, Stogl Robotics Consulting UG (haftungsbeschränkt)
//
// 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 Denis Stogl

#ifndef JOINT_LIMITS__JOINT_LIMITER_INTERFACE_HPP_
#define JOINT_LIMITS__JOINT_LIMITER_INTERFACE_HPP_

#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"
#include "rclcpp_lifecycle/lifecycle_node.hpp"
#include "trajectory_msgs/msg/joint_trajectory_point.hpp"

namespace joint_limits
{
template <typename LimitsType>
class JointLimiterInterface
{
public:
JOINT_LIMITS_PUBLIC JointLimiterInterface() = default;

JOINT_LIMITS_PUBLIC virtual ~JointLimiterInterface() = default;

/// Initialization of every JointLimiter.
/**
* Initialization of JointLimiter for defined joints with their names.
* Robot description topic provides a topic name where URDF of the robot can be found.
* This is needed to use joint limits from URDF (not implemented yet!).
* Override this method only if Initialization and reading joint limits should be adapted.
* Otherwise, initialize your custom limiter in `on_limit` method.
*
* \param[in] joint_names names of joints where limits should be applied.
* \param[in] param_itf node parameters interface object to access parameters.
* \param[in] logging_itf node logging interface to log if error happens.
* \param[in] robot_description_topic string of a topic where robot description is accessible.
*/
JOINT_LIMITS_PUBLIC virtual bool init(
const std::vector<std::string> & joint_names,
const rclcpp::node_interfaces::NodeParametersInterface::SharedPtr & param_itf,
const rclcpp::node_interfaces::NodeLoggingInterface::SharedPtr & logging_itf,
const std::string & robot_description_topic = "/robot_description")
{
number_of_joints_ = joint_names.size();
joint_names_ = joint_names;
joint_limits_.resize(number_of_joints_);
node_param_itf_ = param_itf;
node_logging_itf_ = logging_itf;

bool result = true;

// TODO(destogl): get limits from URDF

// Initialize and get joint limits from parameter server
for (size_t i = 0; i < number_of_joints_; ++i)
{
// FIXME?(destogl): this seems to be a bit unclear because we use the same namespace for
// limiters interface and rosparam helper functions - should we use here another namespace?
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());
}

if (result)
{
result = on_init();
}

// avoid linters output
(void)robot_description_topic;

return result;
}

/**
* Wrapper init method that accepts pointer to the Node.
* For details see other init method.
*/
JOINT_LIMITS_PUBLIC virtual bool init(
const std::vector<std::string> & joint_names, const rclcpp::Node::SharedPtr & node,
const std::string & robot_description_topic = "/robot_description")
{
return init(
joint_names, node->get_node_parameters_interface(), node->get_node_logging_interface(),
robot_description_topic);
}

/**
* Wrapper init method that accepts pointer to the LifecycleNode.
* For details see other init method.
*/
JOINT_LIMITS_PUBLIC virtual bool init(
const std::vector<std::string> & joint_names,
const rclcpp_lifecycle::LifecycleNode::SharedPtr & lifecycle_node,
const std::string & robot_description_topic = "/robot_description")
{
return init(
joint_names, lifecycle_node->get_node_parameters_interface(),
lifecycle_node->get_node_logging_interface(), robot_description_topic);
}

JOINT_LIMITS_PUBLIC virtual bool configure(
const trajectory_msgs::msg::JointTrajectoryPoint & current_joint_states)
{
// TODO(destogl): add checks for position
return on_configure(current_joint_states);
}

JOINT_LIMITS_PUBLIC virtual bool enforce(
trajectory_msgs::msg::JointTrajectoryPoint & current_joint_states,
trajectory_msgs::msg::JointTrajectoryPoint & desired_joint_states, const rclcpp::Duration & dt)
{
// TODO(destogl): add checks if sizes of vectors and number of limits correspond.
return on_enforce(current_joint_states, desired_joint_states, dt);
}

protected:
// Methods that each limiter implementation has to implement
JOINT_LIMITS_PUBLIC virtual bool on_init() { return true; }

JOINT_LIMITS_PUBLIC virtual bool on_configure(
const trajectory_msgs::msg::JointTrajectoryPoint & /*current_joint_states*/)
{
return true;
}

/** \brief Enforce joint limits to desired joint state.
*
* Filter-specific implementation of the joint limits enforce algorithm.
*
* \param[in] current_joint_states current joint states a robot is in.
* \param[out] desired_joint_states joint state that should be adjusted to obey the limits.
* \param[in] dt time delta to calculate missing integrals and derivation in joint limits.
*/
JOINT_LIMITS_PUBLIC virtual bool on_enforce(
trajectory_msgs::msg::JointTrajectoryPoint & current_joint_states,
trajectory_msgs::msg::JointTrajectoryPoint & desired_joint_states,
const rclcpp::Duration & dt) = 0;

size_t number_of_joints_;
std::vector<std::string> joint_names_;
std::vector<LimitsType> joint_limits_;
rclcpp::Node::SharedPtr node_;
rclcpp::node_interfaces::NodeParametersInterface::SharedPtr node_param_itf_;
rclcpp::node_interfaces::NodeLoggingInterface::SharedPtr node_logging_itf_;
};

} // namespace joint_limits

#endif // JOINT_LIMITS__JOINT_LIMITER_INTERFACE_HPP_
61 changes: 61 additions & 0 deletions joint_limits/include/joint_limits/simple_joint_limiter.hpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,61 @@
// Copyright (c) 2023, PickNik Inc.
//
// 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 Dr. Denis Stogl

#ifndef JOINT_LIMITS__SIMPLE_JOINT_LIMITER_HPP_
#define JOINT_LIMITS__SIMPLE_JOINT_LIMITER_HPP_

#include <memory>
#include <string>

#include "joint_limits/joint_limiter_interface.hpp"
#include "joint_limits/joint_limits.hpp"
#include "rclcpp/rclcpp.hpp"

namespace joint_limits
{
template <typename LimitsType>
class SimpleJointLimiter : public JointLimiterInterface<LimitsType>
{
public:
/** \brief Constructor */
JOINT_LIMITS_PUBLIC SimpleJointLimiter();

/** \brief Destructor */
JOINT_LIMITS_PUBLIC ~SimpleJointLimiter();

JOINT_LIMITS_PUBLIC bool on_enforce(
trajectory_msgs::msg::JointTrajectoryPoint & current_joint_states,
trajectory_msgs::msg::JointTrajectoryPoint & desired_joint_states,
const rclcpp::Duration & dt) override;

private:
rclcpp::Clock::SharedPtr clock_;
};

template <typename LimitsType>
SimpleJointLimiter<LimitsType>::SimpleJointLimiter() : JointLimiterInterface<LimitsType>()
{
clock_ = std::make_shared<rclcpp::Clock>(rclcpp::Clock(RCL_ROS_TIME));
}

template <typename LimitsType>
SimpleJointLimiter<LimitsType>::~SimpleJointLimiter()
{
}

} // namespace joint_limits

#endif // JOINT_LIMITS__SIMPLE_JOINT_LIMITER_HPP_
Loading