17#ifndef JOINT_LIMITS__JOINT_LIMITER_INTERFACE_HPP_
18#define JOINT_LIMITS__JOINT_LIMITER_INTERFACE_HPP_
23#include "joint_limits/joint_limits.hpp"
24#include "joint_limits/joint_limits_rosparam.hpp"
25#include "rclcpp/node.hpp"
26#include "rclcpp_lifecycle/lifecycle_node.hpp"
27#include "realtime_tools/realtime_buffer.hpp"
28#include "trajectory_msgs/msg/joint_trajectory_point.hpp"
33template <
typename Jo
intLimitsStateDataType>
55 const std::vector<std::string> & joint_names,
56 const rclcpp::node_interfaces::NodeParametersInterface::SharedPtr & param_itf,
57 const rclcpp::node_interfaces::NodeLoggingInterface::SharedPtr & logging_itf,
58 const std::string & robot_description_topic =
"/robot_description")
60 number_of_joints_ = joint_names.size();
61 joint_names_ = joint_names;
62 joint_limits_.resize(number_of_joints_);
63 node_param_itf_ = param_itf;
64 node_logging_itf_ = logging_itf;
73 for (
size_t i = 0; i < number_of_joints_; ++i)
78 node_logging_itf_->get_logger(),
79 "JointLimiter: Joint '%s': parameter declaration has failed", joint_names[i].c_str());
83 if (!
get_joint_limits(joint_names[i], node_param_itf_, node_logging_itf_, joint_limits_[i]))
86 node_logging_itf_->get_logger(),
87 "JointLimiter: Joint '%s': getting parameters has failed", joint_names[i].c_str());
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());
95 updated_limits_.writeFromNonRT(joint_limits_);
97 auto on_parameter_event_callback = [
this](
const std::vector<rclcpp::Parameter> & parameters)
99 rcl_interfaces::msg::SetParametersResult set_parameters_result;
100 set_parameters_result.successful =
true;
102 std::vector<joint_limits::JointLimits> updated_joint_limits = joint_limits_;
103 bool changed =
false;
105 for (
size_t i = 0; i < number_of_joints_; ++i)
108 joint_names_[i], parameters, node_logging_itf_, updated_joint_limits[i]);
113 updated_limits_.writeFromNonRT(updated_joint_limits);
114 RCLCPP_INFO(node_logging_itf_->get_logger(),
"Limits are dynamically updated!");
117 return set_parameters_result;
120 parameter_callback_ =
121 node_param_itf_->add_on_set_parameters_callback(on_parameter_event_callback);
129 (void)robot_description_topic;
138 const std::vector<std::string> & joint_names,
139 const std::vector<joint_limits::JointLimits> &
joint_limits,
140 const std::vector<joint_limits::SoftJointLimits> & soft_joint_limits,
141 const rclcpp::node_interfaces::NodeParametersInterface::SharedPtr & param_itf,
142 const rclcpp::node_interfaces::NodeLoggingInterface::SharedPtr & logging_itf)
144 number_of_joints_ = joint_names.size();
145 joint_names_ = joint_names;
147 soft_joint_limits_ = soft_joint_limits;
148 node_param_itf_ = param_itf;
149 node_logging_itf_ = logging_itf;
150 updated_limits_.writeFromNonRT(joint_limits_);
155 node_logging_itf_->get_logger(),
156 "JointLimiter: Number of joint names and limits do not match: %zu != %zu",
157 number_of_joints_, joint_limits_.size());
159 return (number_of_joints_ == joint_limits_.size()) &&
on_init();
167 const std::vector<std::string> & joint_names,
const rclcpp::Node::SharedPtr & node,
168 const std::string & robot_description_topic =
"/robot_description")
171 joint_names, node->get_node_parameters_interface(), node->get_node_logging_interface(),
172 robot_description_topic);
180 const std::vector<std::string> & joint_names,
181 const rclcpp_lifecycle::LifecycleNode::SharedPtr & lifecycle_node,
182 const std::string & robot_description_topic =
"/robot_description")
185 joint_names, lifecycle_node->get_node_parameters_interface(),
186 lifecycle_node->get_node_logging_interface(), robot_description_topic);
189 virtual bool configure(
const JointLimitsStateDataType & current_joint_states)
204 const JointLimitsStateDataType & current_joint_states,
205 JointLimitsStateDataType & desired_joint_states,
const rclcpp::Duration & dt)
207 joint_limits_ = *(updated_limits_.readFromRT());
208 return on_enforce(current_joint_states, desired_joint_states, dt);
224 virtual bool on_configure(
const JointLimitsStateDataType & current_joint_states) = 0;
237 const JointLimitsStateDataType & current_joint_states,
238 JointLimitsStateDataType & desired_joint_states,
const rclcpp::Duration & dt) = 0;
256 size_t number_of_joints_;
257 std::vector<std::string> joint_names_;
258 std::vector<joint_limits::JointLimits> joint_limits_;
259 std::vector<joint_limits::SoftJointLimits> soft_joint_limits_;
260 rclcpp::node_interfaces::NodeParametersInterface::SharedPtr node_param_itf_;
261 rclcpp::node_interfaces::NodeLoggingInterface::SharedPtr node_logging_itf_;
264 rclcpp::node_interfaces::OnSetParametersCallbackHandle::SharedPtr parameter_callback_;
Definition joint_limiter_interface.hpp:35
virtual bool on_init()=0
Method is realized by an implementation.
virtual bool init(const std::vector< std::string > &joint_names, const rclcpp::node_interfaces::NodeParametersInterface::SharedPtr ¶m_itf, const rclcpp::node_interfaces::NodeLoggingInterface::SharedPtr &logging_itf, const std::string &robot_description_topic="/robot_description")
Initialization of every JointLimiter.
Definition joint_limiter_interface.hpp:54
bool has_logging_interface() const
Checks if the logging interface is set.
Definition joint_limiter_interface.hpp:246
bool has_parameter_interface() const
Checks if the parameter interface is set.
Definition joint_limiter_interface.hpp:254
virtual bool on_enforce(const JointLimitsStateDataType ¤t_joint_states, JointLimitsStateDataType &desired_joint_states, const rclcpp::Duration &dt)=0
Method is realized by an implementation.
virtual bool enforce(const JointLimitsStateDataType ¤t_joint_states, JointLimitsStateDataType &desired_joint_states, const rclcpp::Duration &dt)
Enforce joint limits to desired joint state for multiple physical quantities.
Definition joint_limiter_interface.hpp:203
virtual bool on_configure(const JointLimitsStateDataType ¤t_joint_states)=0
Method is realized by an implementation.
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")
Definition joint_limiter_interface.hpp:179
virtual bool init(const std::vector< std::string > &joint_names, const rclcpp::Node::SharedPtr &node, const std::string &robot_description_topic="/robot_description")
Definition joint_limiter_interface.hpp:166
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 ¶m_itf, const rclcpp::node_interfaces::NodeLoggingInterface::SharedPtr &logging_itf)
Definition joint_limiter_interface.hpp:137
Definition data_structures.hpp:37
bool check_for_limits_update(const std::string &joint_name, const std::vector< rclcpp::Parameter > ¶meters, const rclcpp::node_interfaces::NodeLoggingInterface::SharedPtr &logging_itf, JointLimits &updated_limits)
Definition joint_limits_rosparam.hpp:431
bool declare_parameters(const std::string &joint_name, const rclcpp::node_interfaces::NodeParametersInterface::SharedPtr ¶m_itf, const rclcpp::node_interfaces::NodeLoggingInterface::SharedPtr &logging_itf)
Definition joint_limits_rosparam.hpp:86
bool get_joint_limits(const std::string &joint_name, const rclcpp::node_interfaces::NodeParametersInterface::SharedPtr ¶m_itf, const rclcpp::node_interfaces::NodeLoggingInterface::SharedPtr &logging_itf, JointLimits &limits)
Populate a JointLimits instance from the node parameters.
Definition joint_limits_rosparam.hpp:225