Skip to content

Commit 9301aec

Browse files
Updated ISMC to use twist stamped state message and refactored realtime buffers to copy message instead of pointer (#45) (#47)
(cherry picked from commit 0a29970) Co-authored-by: Evan Palmer <[email protected]>
1 parent c218b69 commit 9301aec

File tree

6 files changed

+52
-52
lines changed

6 files changed

+52
-52
lines changed

thruster_allocation_matrix_controller/include/thruster_allocation_matrix_controller/thruster_allocation_matrix_controller.hpp

+1-1
Original file line numberDiff line numberDiff line change
@@ -74,7 +74,7 @@ class ThrusterAllocationMatrixController : public controller_interface::Chainabl
7474

7575
auto configure_parameters() -> controller_interface::CallbackReturn;
7676

77-
realtime_tools::RealtimeBuffer<std::shared_ptr<geometry_msgs::msg::Wrench>> reference_;
77+
realtime_tools::RealtimeBuffer<geometry_msgs::msg::Wrench> reference_;
7878
std::shared_ptr<rclcpp::Subscription<geometry_msgs::msg::Wrench>> reference_sub_;
7979

8080
std::shared_ptr<rclcpp::Publisher<auv_control_msgs::msg::MultiActuatorStateStamped>> controller_state_pub_;

thruster_allocation_matrix_controller/src/thruster_allocation_matrix_controller.cpp

+11-12
Original file line numberDiff line numberDiff line change
@@ -31,7 +31,7 @@ namespace thruster_allocation_matrix_controller
3131
namespace
3232
{
3333

34-
auto reset_wrench_msg(std::shared_ptr<geometry_msgs::msg::Wrench> wrench_msg) -> void // NOLINT
34+
auto reset_wrench_msg(geometry_msgs::msg::Wrench * wrench_msg) -> void // NOLINT
3535
{
3636
wrench_msg->force.x = std::numeric_limits<double>::quiet_NaN();
3737
wrench_msg->force.y = std::numeric_limits<double>::quiet_NaN();
@@ -122,16 +122,15 @@ auto ThrusterAllocationMatrixController::on_configure(const rclcpp_lifecycle::St
122122
return ret;
123123
}
124124

125-
const auto reference_msg = std::make_shared<geometry_msgs::msg::Wrench>();
126-
reference_.writeFromNonRT(reference_msg);
125+
reference_.writeFromNonRT(geometry_msgs::msg::Wrench());
127126

128127
command_interfaces_.reserve(num_thrusters_);
129128

130129
reference_sub_ = get_node()->create_subscription<geometry_msgs::msg::Wrench>(
131130
"~/reference",
132131
rclcpp::SystemDefaultsQoS(),
133132
[this](const std::shared_ptr<geometry_msgs::msg::Wrench> msg) { // NOLINT
134-
reference_.writeFromNonRT(msg);
133+
reference_.writeFromNonRT(*msg);
135134
});
136135

137136
controller_state_pub_ = get_node()->create_publisher<auv_control_msgs::msg::MultiActuatorStateStamped>(
@@ -153,7 +152,7 @@ auto ThrusterAllocationMatrixController::on_configure(const rclcpp_lifecycle::St
153152
auto ThrusterAllocationMatrixController::on_activate(const rclcpp_lifecycle::State & /*previous_state*/)
154153
-> controller_interface::CallbackReturn
155154
{
156-
reset_wrench_msg(*(reference_.readFromNonRT()));
155+
reset_wrench_msg(reference_.readFromNonRT());
157156
reference_interfaces_.assign(reference_interfaces_.size(), std::numeric_limits<double>::quiet_NaN());
158157
return controller_interface::CallbackReturn::SUCCESS;
159158
}
@@ -209,20 +208,20 @@ auto ThrusterAllocationMatrixController::update_reference_from_subscribers() ->
209208
auto * current_reference = reference_.readFromNonRT();
210209

211210
const std::vector<double> wrench = {
212-
(*current_reference)->force.x,
213-
(*current_reference)->force.y,
214-
(*current_reference)->force.z,
215-
(*current_reference)->torque.x,
216-
(*current_reference)->torque.y,
217-
(*current_reference)->torque.z};
211+
current_reference->force.x,
212+
current_reference->force.y,
213+
current_reference->force.z,
214+
current_reference->torque.x,
215+
current_reference->torque.y,
216+
current_reference->torque.z};
218217

219218
for (std::size_t i = 0; i < wrench.size(); ++i) {
220219
if (!std::isnan(wrench[i])) {
221220
reference_interfaces_[i] = wrench[i];
222221
}
223222
}
224223

225-
reset_wrench_msg(*current_reference);
224+
reset_wrench_msg(current_reference);
226225

227226
return controller_interface::return_type::OK;
228227
}

thruster_controllers/include/thruster_controllers/polynomial_thrust_curve_controller.hpp

+1-1
Original file line numberDiff line numberDiff line change
@@ -70,7 +70,7 @@ class PolynomialThrustCurveController : public controller_interface::ChainableCo
7070

7171
auto configure_parameters() -> controller_interface::CallbackReturn;
7272

73-
realtime_tools::RealtimeBuffer<std::shared_ptr<std_msgs::msg::Float64>> reference_;
73+
realtime_tools::RealtimeBuffer<std_msgs::msg::Float64> reference_;
7474
std::shared_ptr<rclcpp::Subscription<std_msgs::msg::Float64>> reference_sub_;
7575

7676
std::shared_ptr<rclcpp::Publisher<control_msgs::msg::SingleDOFStateStamped>> controller_state_pub_;

thruster_controllers/src/polynomial_thrust_curve_controller.cpp

+5-6
Original file line numberDiff line numberDiff line change
@@ -81,14 +81,13 @@ auto PolynomialThrustCurveController::on_configure(const rclcpp_lifecycle::State
8181
return ret;
8282
}
8383

84-
const auto reference_msg = std::make_shared<std_msgs::msg::Float64>();
85-
reference_.writeFromNonRT(reference_msg);
84+
reference_.writeFromNonRT(std_msgs::msg::Float64());
8685

8786
command_interfaces_.reserve(1);
8887

8988
reference_sub_ = get_node()->create_subscription<std_msgs::msg::Float64>(
9089
"~/reference", rclcpp::SystemDefaultsQoS(), [this](const std::shared_ptr<std_msgs::msg::Float64> msg) { // NOLINT
91-
reference_.writeFromNonRT(msg);
90+
reference_.writeFromNonRT(*msg);
9291
});
9392

9493
controller_state_pub_ =
@@ -107,7 +106,7 @@ auto PolynomialThrustCurveController::on_configure(const rclcpp_lifecycle::State
107106
auto PolynomialThrustCurveController::on_activate(const rclcpp_lifecycle::State & /*previous_state*/)
108107
-> controller_interface::CallbackReturn
109108
{
110-
(*reference_.readFromNonRT())->data = std::numeric_limits<double>::quiet_NaN();
109+
reference_.readFromNonRT()->data = std::numeric_limits<double>::quiet_NaN();
111110
reference_interfaces_.assign(reference_interfaces_.size(), std::numeric_limits<double>::quiet_NaN());
112111
return controller_interface::CallbackReturn::SUCCESS;
113112
}
@@ -153,8 +152,8 @@ auto PolynomialThrustCurveController::on_export_reference_interfaces()
153152
auto PolynomialThrustCurveController::update_reference_from_subscribers() -> controller_interface::return_type
154153
{
155154
auto * current_reference = reference_.readFromNonRT();
156-
reference_interfaces_[0] = (*current_reference)->data;
157-
(*current_reference)->data = std::numeric_limits<double>::quiet_NaN();
155+
reference_interfaces_[0] = current_reference->data;
156+
current_reference->data = std::numeric_limits<double>::quiet_NaN();
158157

159158
return controller_interface::return_type::OK;
160159
}

velocity_controllers/include/velocity_controllers/integral_sliding_mode_controller.hpp

+4-4
Original file line numberDiff line numberDiff line change
@@ -30,7 +30,7 @@
3030
#include "control_msgs/msg/multi_dof_state_stamped.hpp"
3131
#include "controller_interface/chainable_controller_interface.hpp"
3232
#include "controller_interface/controller_interface.hpp"
33-
#include "geometry_msgs/msg/twist.hpp"
33+
#include "geometry_msgs/msg/twist_stamped.hpp"
3434
#include "hydrodynamics/eigen.hpp"
3535
#include "hydrodynamics/hydrodynamics.hpp"
3636
#include "rclcpp/rclcpp.hpp"
@@ -83,11 +83,11 @@ class IntegralSlidingModeController : public controller_interface::ChainableCont
8383

8484
auto configure_parameters() -> controller_interface::CallbackReturn;
8585

86-
realtime_tools::RealtimeBuffer<std::shared_ptr<geometry_msgs::msg::Twist>> reference_;
86+
realtime_tools::RealtimeBuffer<geometry_msgs::msg::Twist> reference_;
8787
std::shared_ptr<rclcpp::Subscription<geometry_msgs::msg::Twist>> reference_sub_;
8888

89-
realtime_tools::RealtimeBuffer<std::shared_ptr<geometry_msgs::msg::Twist>> system_state_;
90-
std::shared_ptr<rclcpp::Subscription<geometry_msgs::msg::Twist>> system_state_sub_;
89+
realtime_tools::RealtimeBuffer<geometry_msgs::msg::Twist> system_state_;
90+
std::shared_ptr<rclcpp::Subscription<geometry_msgs::msg::TwistStamped>> system_state_sub_;
9191
std::vector<double> system_state_values_;
9292

9393
// We need the system rotation from the inertial frame to the vehicle frame for the hydrodynamic model.

velocity_controllers/src/integral_sliding_mode_controller.cpp

+30-28
Original file line numberDiff line numberDiff line change
@@ -39,7 +39,7 @@ namespace velocity_controllers
3939
namespace
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());
@@ -257,20 +260,20 @@ auto IntegralSlidingModeController::update_reference_from_subscribers() -> contr
257260
auto * current_reference = reference_.readFromNonRT();
258261

259262
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};
266269

267270
for (std::size_t i = 0; i < reference.size(); ++i) {
268271
if (!std::isnan(reference[i])) {
269272
reference_interfaces_[i] = reference[i];
270273
}
271274
}
272275

273-
reset_twist_msg(*current_reference);
276+
reset_twist_msg(current_reference);
274277

275278
return controller_interface::return_type::OK;
276279
}
@@ -281,20 +284,20 @@ auto IntegralSlidingModeController::update_system_state_values() -> controller_i
281284
auto * current_system_state = system_state_.readFromRT();
282285

283286
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};
290293

291294
for (std::size_t i = 0; i < state.size(); ++i) {
292295
if (!std::isnan(state[i])) {
293296
system_state_values_[i] = state[i];
294297
}
295298
}
296299

297-
reset_twist_msg(*current_system_state);
300+
reset_twist_msg(current_system_state);
298301
} else {
299302
for (std::size_t i = 0; i < system_state_values_.size(); ++i) {
300303
system_state_values_[i] = state_interfaces_[i].get_value();
@@ -332,7 +335,7 @@ auto IntegralSlidingModeController::update_and_write_commands(
332335
auto all_nan =
333336
std ::all_of(velocity_error_values.begin(), velocity_error_values.end(), [&](double i) { return std::isnan(i); });
334337
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.");
336339
return controller_interface::return_type::OK;
337340
}
338341

@@ -377,7 +380,6 @@ auto IntegralSlidingModeController::update_and_write_commands(
377380

378381
// Apply the sign function to the surface
379382
// 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
381383
surface = surface.unaryExpr([this](double x) { return std::tanh(x / boundary_thickness_); });
382384

383385
// Calculate the disturbance rejection torque

0 commit comments

Comments
 (0)