2020#include < string>
2121#include < vector>
2222
23+ #include " joint_limits/joint_limits.hpp"
2324#include " joint_limits/joint_limits_rosparam.hpp"
2425#include " rclcpp/node.hpp"
2526#include " rclcpp_lifecycle/lifecycle_node.hpp"
2829
2930namespace joint_limits
3031{
31- using JointLimitsStateDataType = trajectory_msgs::msg::JointTrajectoryPoint;
3232
33- template <typename LimitsType >
33+ template <typename JointLimitsStateDataType >
3434class JointLimiterInterface
3535{
3636public:
@@ -68,55 +68,58 @@ class JointLimiterInterface
6868 // TODO(destogl): get limits from URDF
6969
7070 // Initialize and get joint limits from parameter server
71- for ( size_t i = 0 ; i < number_of_joints_; ++i )
71+ if ( has_parameter_interface () )
7272 {
73- if (!declare_parameters (joint_names[i], node_param_itf_, node_logging_itf_))
74- {
75- RCLCPP_ERROR (
76- node_logging_itf_->get_logger (),
77- " JointLimiter: Joint '%s': parameter declaration has failed" , joint_names[i].c_str ());
78- result = false ;
79- break ;
80- }
81- if (!get_joint_limits (joint_names[i], node_param_itf_, node_logging_itf_, joint_limits_[i]))
73+ for (size_t i = 0 ; i < number_of_joints_; ++i)
8274 {
83- RCLCPP_ERROR (
84- node_logging_itf_->get_logger (),
85- " JointLimiter: Joint '%s': getting parameters has failed" , joint_names[i].c_str ());
86- result = false ;
87- break ;
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 ());
8894 }
89- RCLCPP_INFO (
90- node_logging_itf_->get_logger (), " Limits for joint %zu (%s) are:\n %s" , i,
91- joint_names[i].c_str (), joint_limits_[i].to_string ().c_str ());
92- }
93- updated_limits_.writeFromNonRT (joint_limits_);
95+ updated_limits_.writeFromNonRT (joint_limits_);
9496
95- auto on_parameter_event_callback = [this ](const std::vector<rclcpp::Parameter> & parameters)
96- {
97- rcl_interfaces::msg::SetParametersResult set_parameters_result;
98- set_parameters_result.successful = true ;
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 ;
99101
100- std::vector<LimitsType > updated_joint_limits = joint_limits_;
101- bool changed = false ;
102+ std::vector<joint_limits::JointLimits > updated_joint_limits = joint_limits_;
103+ bool changed = false ;
102104
103- for (size_t i = 0 ; i < number_of_joints_; ++i)
104- {
105- changed |= joint_limits::check_for_limits_update (
106- joint_names_[i], parameters, node_logging_itf_, updated_joint_limits[i]);
107- }
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+ }
108110
109- if (changed)
110- {
111- updated_limits_.writeFromNonRT (updated_joint_limits);
112- RCLCPP_INFO (node_logging_itf_->get_logger (), " Limits are dynamically updated!" );
113- }
111+ if (changed)
112+ {
113+ updated_limits_.writeFromNonRT (updated_joint_limits);
114+ RCLCPP_INFO (node_logging_itf_->get_logger (), " Limits are dynamically updated!" );
115+ }
114116
115- return set_parameters_result;
116- };
117+ return set_parameters_result;
118+ };
117119
118- parameter_callback_ =
119- node_param_itf_->add_on_set_parameters_callback (on_parameter_event_callback);
120+ parameter_callback_ =
121+ node_param_itf_->add_on_set_parameters_callback (on_parameter_event_callback);
122+ }
120123
121124 if (result)
122125 {
@@ -128,6 +131,34 @@ class JointLimiterInterface
128131 return result;
129132 }
130133
134+ /* *
135+ * Wrapper init method that accepts the joint names and their limits directly
136+ */
137+ virtual bool init (
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)
143+ {
144+ number_of_joints_ = joint_names.size ();
145+ joint_names_ = joint_names;
146+ joint_limits_ = joint_limits;
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_);
151+
152+ if ((number_of_joints_ != joint_limits_.size ()) && has_logging_interface ())
153+ {
154+ RCLCPP_ERROR (
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 ());
158+ }
159+ return (number_of_joints_ == joint_limits_.size ()) && on_init ();
160+ }
161+
131162 /* *
132163 * Wrapper init method that accepts pointer to the Node.
133164 * For details see other init method.
@@ -177,19 +208,6 @@ class JointLimiterInterface
177208 return on_enforce (current_joint_states, desired_joint_states, dt);
178209 }
179210
180- /* * \brief Enforce joint limits to desired joint state for single physical quantity.
181- *
182- * Generic enforce method that calls implementation-specific `on_enforce` method.
183- *
184- * \param[in,out] desired_joint_states joint state that should be adjusted to obey the limits.
185- * \returns true if limits are enforced, otherwise false.
186- */
187- virtual bool enforce (std::vector<double > & desired_joint_states)
188- {
189- joint_limits_ = *(updated_limits_.readFromRT ());
190- return on_enforce (desired_joint_states);
191- }
192-
193211protected:
194212 /* * \brief Method is realized by an implementation.
195213 *
@@ -219,27 +237,32 @@ class JointLimiterInterface
219237 JointLimitsStateDataType & current_joint_states,
220238 JointLimitsStateDataType & desired_joint_states, const rclcpp::Duration & dt) = 0;
221239
222- /* * \brief Method is realized by an implementation.
240+ /* * \brief Checks if the logging interface is set.
241+ * \returns true if the logging interface is available, otherwise false.
223242 *
224- * Filter-specific implementation of the joint limits enforce algorithm for single physical
225- * quantity.
226- * This method might use "effort" limits since they are often used as wild-card.
227- * Check the documentation of the exact implementation for more details.
243+ * \note this way of interfacing would be useful for instances where the logging interface is not
244+ * available, for example in the ResourceManager or ResourceStorage classes.
245+ */
246+ bool has_logging_interface () const { return node_logging_itf_ != nullptr ; }
247+
248+ /* * \brief Checks if the parameter interface is set.
249+ * \returns true if the parameter interface is available, otherwise false.
228250 *
229- * \param[in,out] desired_joint_states joint state that should be adjusted to obey the limits.
230- * \returns true if limits are enforced, otherwise false .
251+ * * \note this way of interfacing would be useful for instances where the logging interface is
252+ * not available, for example in the ResourceManager or ResourceStorage classes .
231253 */
232- virtual bool on_enforce (std::vector< double > & desired_joint_states) = 0;
254+ bool has_parameter_interface () const { return node_param_itf_ != nullptr ; }
233255
234256 size_t number_of_joints_;
235257 std::vector<std::string> joint_names_;
236- std::vector<LimitsType> joint_limits_;
258+ std::vector<joint_limits::JointLimits> joint_limits_;
259+ std::vector<joint_limits::SoftJointLimits> soft_joint_limits_;
237260 rclcpp::node_interfaces::NodeParametersInterface::SharedPtr node_param_itf_;
238261 rclcpp::node_interfaces::NodeLoggingInterface::SharedPtr node_logging_itf_;
239262
240263private:
241264 rclcpp::node_interfaces::OnSetParametersCallbackHandle::SharedPtr parameter_callback_;
242- realtime_tools::RealtimeBuffer<std::vector<LimitsType >> updated_limits_;
265+ realtime_tools::RealtimeBuffer<std::vector<joint_limits::JointLimits >> updated_limits_;
243266};
244267
245268} // namespace joint_limits
0 commit comments