@@ -39,7 +39,7 @@ namespace velocity_controllers
3939namespace
4040{
4141
42- void reset_twist_msg (std::shared_ptr< geometry_msgs::msg::Twist> msg) // NOLINT
42+ void reset_twist_msg (geometry_msgs::msg::Twist * msg) // NOLINT
4343{
4444 msg->linear .x = std::numeric_limits<double >::quiet_NaN ();
4545 msg->linear .y = std::numeric_limits<double >::quiet_NaN ();
@@ -62,6 +62,12 @@ auto IntegralSlidingModeController::on_init() -> controller_interface::CallbackR
6262 return controller_interface::CallbackReturn::ERROR;
6363 }
6464
65+ // Notify users about this. This can be confusing for folks that expect the controller to work without a reference
66+ // or state message.
67+ RCLCPP_INFO (
68+ get_node ()->get_logger (),
69+ " Reference and state messages are required for operation - commands will not be sent until both are received." );
70+
6571 return controller_interface::CallbackReturn::SUCCESS;
6672}
6773
@@ -177,11 +183,8 @@ auto IntegralSlidingModeController::on_configure(const rclcpp_lifecycle::State &
177183 return ret;
178184 }
179185
180- const auto reference_msg = std::make_shared<geometry_msgs::msg::Twist>();
181- reference_.writeFromNonRT (reference_msg);
182-
183- const auto system_state_msg = std::make_shared<geometry_msgs::msg::Twist>();
184- system_state_.writeFromNonRT (system_state_msg);
186+ reference_.writeFromNonRT (geometry_msgs::msg::Twist ());
187+ system_state_.writeFromNonRT (geometry_msgs::msg::Twist ());
185188
186189 command_interfaces_.reserve (DOF);
187190
@@ -191,16 +194,16 @@ auto IntegralSlidingModeController::on_configure(const rclcpp_lifecycle::State &
191194 " ~/reference" ,
192195 rclcpp::SystemDefaultsQoS (),
193196 [this ](const std::shared_ptr<geometry_msgs::msg::Twist> msg) { // NOLINT
194- reference_.writeFromNonRT (msg);
197+ reference_.writeFromNonRT (* msg);
195198 }); // NOLINT
196199
197200 // If we aren't reading from the state interfaces, subscribe to the system state topic
198201 if (params_.use_external_measured_states ) {
199- system_state_sub_ = get_node ()->create_subscription <geometry_msgs::msg::Twist >(
202+ system_state_sub_ = get_node ()->create_subscription <geometry_msgs::msg::TwistStamped >(
200203 " ~/system_state" ,
201204 rclcpp::SystemDefaultsQoS (),
202- [this ](const std::shared_ptr<geometry_msgs::msg::Twist > msg) { // NOLINT
203- system_state_.writeFromNonRT (msg);
205+ [this ](const std::shared_ptr<geometry_msgs::msg::TwistStamped > msg) { // NOLINT
206+ system_state_.writeFromNonRT (msg-> twist );
204207 });
205208 }
206209
@@ -235,8 +238,8 @@ auto IntegralSlidingModeController::on_activate(const rclcpp_lifecycle::State &
235238
236239 system_rotation_.writeFromNonRT (Eigen::Quaterniond::Identity ());
237240
238- reset_twist_msg (*( reference_.readFromNonRT () ));
239- reset_twist_msg (*( system_state_.readFromNonRT () ));
241+ reset_twist_msg (reference_.readFromNonRT ());
242+ reset_twist_msg (system_state_.readFromNonRT ());
240243
241244 reference_interfaces_.assign (reference_interfaces_.size (), std::numeric_limits<double >::quiet_NaN ());
242245 system_state_values_.assign (system_state_values_.size (), std::numeric_limits<double >::quiet_NaN ());
@@ -259,20 +262,20 @@ auto IntegralSlidingModeController::update_reference_from_subscribers(
259262 auto * current_reference = reference_.readFromNonRT ();
260263
261264 const std::vector<double > reference = {
262- (* current_reference) ->linear .x ,
263- (* current_reference) ->linear .y ,
264- (* current_reference) ->linear .z ,
265- (* current_reference) ->angular .x ,
266- (* current_reference) ->angular .y ,
267- (* current_reference) ->angular .z };
265+ current_reference->linear .x ,
266+ current_reference->linear .y ,
267+ current_reference->linear .z ,
268+ current_reference->angular .x ,
269+ current_reference->angular .y ,
270+ current_reference->angular .z };
268271
269272 for (std::size_t i = 0 ; i < reference.size (); ++i) {
270273 if (!std::isnan (reference[i])) {
271274 reference_interfaces_[i] = reference[i];
272275 }
273276 }
274277
275- reset_twist_msg (* current_reference);
278+ reset_twist_msg (current_reference);
276279
277280 return controller_interface::return_type::OK;
278281}
@@ -283,20 +286,20 @@ auto IntegralSlidingModeController::update_system_state_values() -> controller_i
283286 auto * current_system_state = system_state_.readFromRT ();
284287
285288 const std::vector<double > state = {
286- (* current_system_state) ->linear .x ,
287- (* current_system_state) ->linear .y ,
288- (* current_system_state) ->linear .z ,
289- (* current_system_state) ->angular .x ,
290- (* current_system_state) ->angular .y ,
291- (* current_system_state) ->angular .z };
289+ current_system_state->linear .x ,
290+ current_system_state->linear .y ,
291+ current_system_state->linear .z ,
292+ current_system_state->angular .x ,
293+ current_system_state->angular .y ,
294+ current_system_state->angular .z };
292295
293296 for (std::size_t i = 0 ; i < state.size (); ++i) {
294297 if (!std::isnan (state[i])) {
295298 system_state_values_[i] = state[i];
296299 }
297300 }
298301
299- reset_twist_msg (* current_system_state);
302+ reset_twist_msg (current_system_state);
300303 } else {
301304 for (std::size_t i = 0 ; i < system_state_values_.size (); ++i) {
302305 system_state_values_[i] = state_interfaces_[i].get_value ();
@@ -334,7 +337,7 @@ auto IntegralSlidingModeController::update_and_write_commands(
334337 auto all_nan =
335338 std ::all_of (velocity_error_values.begin (), velocity_error_values.end (), [&](double i) { return std::isnan (i); });
336339 if (all_nan) {
337- RCLCPP_DEBUG (get_node ()->get_logger (), " All reference and system state values are NaN. Skipping control update." );
340+ RCLCPP_DEBUG (get_node ()->get_logger (), " All velocity error values are NaN. Skipping control update." );
338341 return controller_interface::return_type::OK;
339342 }
340343
@@ -379,7 +382,6 @@ auto IntegralSlidingModeController::update_and_write_commands(
379382
380383 // Apply the sign function to the surface
381384 // Right now, we use the tanh function to reduce the chattering effect.
382- // TODO(evan-palmer): Implement the super twisting algorithm to improve this further
383385 surface = surface.unaryExpr ([this ](double x) { return std::tanh (x / boundary_thickness_); });
384386
385387 // Calculate the disturbance rejection torque
0 commit comments