@@ -39,7 +39,7 @@ namespace velocity_controllers
39
39
namespace
40
40
{
41
41
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
43
43
{
44
44
msg->linear .x = std::numeric_limits<double >::quiet_NaN ();
45
45
msg->linear .y = std::numeric_limits<double >::quiet_NaN ();
@@ -62,6 +62,12 @@ auto IntegralSlidingModeController::on_init() -> controller_interface::CallbackR
62
62
return controller_interface::CallbackReturn::ERROR;
63
63
}
64
64
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
+
65
71
return controller_interface::CallbackReturn::SUCCESS;
66
72
}
67
73
@@ -177,11 +183,8 @@ auto IntegralSlidingModeController::on_configure(const rclcpp_lifecycle::State &
177
183
return ret;
178
184
}
179
185
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 ());
185
188
186
189
command_interfaces_.reserve (DOF);
187
190
@@ -191,16 +194,16 @@ auto IntegralSlidingModeController::on_configure(const rclcpp_lifecycle::State &
191
194
" ~/reference" ,
192
195
rclcpp::SystemDefaultsQoS (),
193
196
[this ](const std::shared_ptr<geometry_msgs::msg::Twist> msg) { // NOLINT
194
- reference_.writeFromNonRT (msg);
197
+ reference_.writeFromNonRT (* msg);
195
198
}); // NOLINT
196
199
197
200
// If we aren't reading from the state interfaces, subscribe to the system state topic
198
201
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 >(
200
203
" ~/system_state" ,
201
204
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 );
204
207
});
205
208
}
206
209
@@ -235,8 +238,8 @@ auto IntegralSlidingModeController::on_activate(const rclcpp_lifecycle::State &
235
238
236
239
system_rotation_.writeFromNonRT (Eigen::Quaterniond::Identity ());
237
240
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 ());
240
243
241
244
reference_interfaces_.assign (reference_interfaces_.size (), std::numeric_limits<double >::quiet_NaN ());
242
245
system_state_values_.assign (system_state_values_.size (), std::numeric_limits<double >::quiet_NaN ());
@@ -257,20 +260,20 @@ auto IntegralSlidingModeController::update_reference_from_subscribers() -> contr
257
260
auto * current_reference = reference_.readFromNonRT ();
258
261
259
262
const std::vector<double > reference = {
260
- (* current_reference) ->linear .x ,
261
- (* current_reference) ->linear .y ,
262
- (* current_reference) ->linear .z ,
263
- (* current_reference) ->angular .x ,
264
- (* current_reference) ->angular .y ,
265
- (* current_reference) ->angular .z };
263
+ current_reference->linear .x ,
264
+ current_reference->linear .y ,
265
+ current_reference->linear .z ,
266
+ current_reference->angular .x ,
267
+ current_reference->angular .y ,
268
+ current_reference->angular .z };
266
269
267
270
for (std::size_t i = 0 ; i < reference.size (); ++i) {
268
271
if (!std::isnan (reference[i])) {
269
272
reference_interfaces_[i] = reference[i];
270
273
}
271
274
}
272
275
273
- reset_twist_msg (* current_reference);
276
+ reset_twist_msg (current_reference);
274
277
275
278
return controller_interface::return_type::OK;
276
279
}
@@ -281,20 +284,20 @@ auto IntegralSlidingModeController::update_system_state_values() -> controller_i
281
284
auto * current_system_state = system_state_.readFromRT ();
282
285
283
286
const std::vector<double > state = {
284
- (* current_system_state) ->linear .x ,
285
- (* current_system_state) ->linear .y ,
286
- (* current_system_state) ->linear .z ,
287
- (* current_system_state) ->angular .x ,
288
- (* current_system_state) ->angular .y ,
289
- (* current_system_state) ->angular .z };
287
+ current_system_state->linear .x ,
288
+ current_system_state->linear .y ,
289
+ current_system_state->linear .z ,
290
+ current_system_state->angular .x ,
291
+ current_system_state->angular .y ,
292
+ current_system_state->angular .z };
290
293
291
294
for (std::size_t i = 0 ; i < state.size (); ++i) {
292
295
if (!std::isnan (state[i])) {
293
296
system_state_values_[i] = state[i];
294
297
}
295
298
}
296
299
297
- reset_twist_msg (* current_system_state);
300
+ reset_twist_msg (current_system_state);
298
301
} else {
299
302
for (std::size_t i = 0 ; i < system_state_values_.size (); ++i) {
300
303
system_state_values_[i] = state_interfaces_[i].get_value ();
@@ -332,7 +335,7 @@ auto IntegralSlidingModeController::update_and_write_commands(
332
335
auto all_nan =
333
336
std ::all_of (velocity_error_values.begin (), velocity_error_values.end (), [&](double i) { return std::isnan (i); });
334
337
if (all_nan) {
335
- RCLCPP_DEBUG (get_node ()->get_logger (), " All reference and system state values are NaN. Skipping control update." );
338
+ RCLCPP_DEBUG (get_node ()->get_logger (), " All velocity error values are NaN. Skipping control update." );
336
339
return controller_interface::return_type::OK;
337
340
}
338
341
@@ -377,7 +380,6 @@ auto IntegralSlidingModeController::update_and_write_commands(
377
380
378
381
// Apply the sign function to the surface
379
382
// Right now, we use the tanh function to reduce the chattering effect.
380
- // TODO(evan-palmer): Implement the super twisting algorithm to improve this further
381
383
surface = surface.unaryExpr ([this ](double x) { return std::tanh (x / boundary_thickness_); });
382
384
383
385
// Calculate the disturbance rejection torque
0 commit comments