|
| 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