controls  3.0.0
ControlsROS2Wrapper.h
Go to the documentation of this file.
1 #ifndef CONTROLS_NODES_CONTROLSROS2WRAPPER_H
2 #define CONTROLS_NODES_CONTROLSROS2WRAPPER_H
3 
5 #include <utils/Types.h>
6 #include <utils/concurrentqueue.h>
7 #include <vehicle/Vehicle.h>
8 #include <yaml-cpp/yaml.h>
9 
10 #include <atomic>
11 #include <bb_controls_msgs/action/locomotion.hpp>
12 #include <bb_controls_msgs/msg/controller_status.hpp>
13 #include <bb_controls_msgs/msg/thrusters.hpp>
14 #include <bb_controls_msgs/srv/controller.hpp>
15 #include <bb_controls_msgs/srv/encircle_traj.hpp>
16 #include <bb_controls_msgs/srv/spline_traj.hpp>
17 #include <bb_planner_msgs/srv/get_plan_through_poses.hpp>
18 #include <bb_sensor_msgs/msg/batteries_with_id.hpp>
19 #include <boost/uuid/uuid.hpp>
20 #include <boost/uuid/uuid_generators.hpp>
21 #include <boost/uuid/uuid_io.hpp>
22 #include <memory>
23 #include <mutex>
24 #include <rclcpp_action/rclcpp_action.hpp>
25 #include <rclcpp_action/server.hpp>
26 #include <std_msgs/msg/bool.hpp>
27 #include <string>
28 #include <string_view>
29 #include <thread>
30 #include <unordered_map>
31 
61 class ControlsROS2Wrapper : public rclcpp::Node {
62 public:
71  explicit ControlsROS2Wrapper(const std::string& name, std::unique_ptr<Vehicle> robot,
72  std::string body_frame_tf_name = "base_link", std::string world_frame_tf_name = "map");
73 
74  ~ControlsROS2Wrapper() override;
75 
76  // Non-copyable and non-movable: mutex, atomic, unique_ptr, and thread members
81 
82  using Locomotion = bb_controls_msgs::action::Locomotion;
83  using GoalHandleLocomotion = rclcpp_action::ServerGoalHandle<Locomotion>;
84 
92  struct Params {
93  double ff_gain = 0.0;
94  double fb_gain = 1.0;
95  double buoyancy_gain = 0.0;
97  double surface_threshold = 0.1;
98  double axis_gain_x = 1.0;
99  double axis_gain_y = 1.0;
100  double axis_gain_z = 0.0;
101  double axis_gain_roll = 0.0;
102  double axis_gain_pitch = 0.0;
103  double axis_gain_yaw = 1.0;
104  double kp_x = 1491.433;
105  double ki_x = 35.628;
106  double kd_x = 21.098;
107  double kp_y = 600.345;
108  double ki_y = 9.834;
109  double kd_y = 330.864;
110  double kp_z = 969.781;
111  double ki_z = 474.207;
112  double kd_z = 180.169;
113  double kp_roll = 79.701;
114  double ki_roll = 91.516;
115  double kd_roll = 10.975;
116  double kp_pitch = 117.765;
117  double ki_pitch = 135.223;
118  double kd_pitch = 16.209;
119  double kp_yaw = 150.113;
120  double ki_yaw = 10.038;
121  double kd_yaw = 54.212;
122  double kp_x_surface = 226.595;
123  double ki_x_surface = 4.124;
124  double kd_x_surface = 1643.310;
125  double kp_y_surface = 334.345;
126  double ki_y_surface = 9.834;
127  double kd_y_surface = 1589.864;
128  double kp_z_surface = 969.781;
129  double ki_z_surface = 474.207;
130  double kd_z_surface = 180.169;
131  double kp_roll_surface = 79.701;
132  double ki_roll_surface = 91.516;
133  double kd_roll_surface = 10.975;
134  double kp_pitch_surface = 117.765;
135  double ki_pitch_surface = 135.223;
136  double kd_pitch_surface = 16.209;
137  double kp_yaw_surface = 29.113;
138  double ki_yaw_surface = 1.038;
139  double kd_yaw_surface = 54.212;
140  double slow_down_gain = 0.0;
141  double max_xy_vel = 10.0;
142  double max_xy_acc = 5.0;
143  double max_xy_jerk = 0.8;
144  double max_z_vel = 0.0;
145  double max_z_acc = 0.0;
146  double max_z_jerk = 0.0;
147  double max_yaw_vel = 3.0;
148  double max_yaw_acc = 0.4;
149  double max_yaw_jerk = 0.3;
150 
151  // Adaptive buoyancy bias estimation (heave)
152  bool buoyancy_adaptive_z = false;
157 
158  // Adaptive buoyancy bias estimation (roll/pitch); thresholds in deg, deg/s
159  bool buoyancy_adaptive_rp = false;
163 
164  // System dynamics parameters
165  double mass = 36.10;
166  double buoyancy_factor = 1.0;
167  double i_xx = 0.7699579;
168  double i_yy = 0.7699579;
169  double i_zz = 1.38624;
170  double i_xy = 0.0;
171  double i_xz = 0.0;
172  double i_yz = 0.0;
173  double ma_x = 12.19;
174  double ma_y = 17.44;
175  double ma_z = 26.47;
176  double ma_roll = 0.15;
177  double ma_pitch = 0.26;
178  double ma_yaw = 0.19;
179  double dl_x = 3.8;
180  double dl_y = 4.4;
181  double dl_z = 34.8;
182  double dl_roll = 0.131;
183  double dl_pitch = 0.201;
184  double dl_yaw = 0.077;
185  double dnl_x = 38.7;
186  double dnl_y = 54.6;
187  double dnl_z = 78.9;
188  double dnl_roll = 0.342;
189  double dnl_pitch = 0.465;
190  double dnl_yaw = 0.451;
191  double rbb_x = 0.0;
192  double rbb_y = 0.0;
193  double rbb_z = -0.05593619792;
194  double rgb_x = 0.0;
195  double rgb_y = 0.0;
196  double rgb_z = 0.0;
197  double cg_offset_x = 0.0;
198  double cg_offset_y = 0.0;
199  double cg_offset_z = 0.0;
200  };
201 
202  // clang-format off
204  static inline const std::unordered_map<std::string_view, double Params::*> DOUBLE_PARAM_MAP = {
205  {"ff_gain", &Params::ff_gain},
206  {"fb_gain", &Params::fb_gain},
207  {"buoyancy_gain", &Params::buoyancy_gain},
208  {"surface_threshold", &Params::surface_threshold},
209  {"axis_gain_x", &Params::axis_gain_x},
210  {"axis_gain_y", &Params::axis_gain_y},
211  {"axis_gain_z", &Params::axis_gain_z},
212  {"axis_gain_roll", &Params::axis_gain_roll},
213  {"axis_gain_pitch", &Params::axis_gain_pitch},
214  {"axis_gain_yaw", &Params::axis_gain_yaw},
215  {"kp_x", &Params::kp_x},
216  {"ki_x", &Params::ki_x},
217  {"kd_x", &Params::kd_x},
218  {"kp_y", &Params::kp_y},
219  {"ki_y", &Params::ki_y},
220  {"kd_y", &Params::kd_y},
221  {"kp_z", &Params::kp_z},
222  {"ki_z", &Params::ki_z},
223  {"kd_z", &Params::kd_z},
224  {"kp_roll", &Params::kp_roll},
225  {"ki_roll", &Params::ki_roll},
226  {"kd_roll", &Params::kd_roll},
227  {"kp_pitch", &Params::kp_pitch},
228  {"ki_pitch", &Params::ki_pitch},
229  {"kd_pitch", &Params::kd_pitch},
230  {"kp_yaw", &Params::kp_yaw},
231  {"ki_yaw", &Params::ki_yaw},
232  {"kd_yaw", &Params::kd_yaw},
233  {"kp_x_surface", &Params::kp_x_surface},
234  {"ki_x_surface", &Params::ki_x_surface},
235  {"kd_x_surface", &Params::kd_x_surface},
236  {"kp_y_surface", &Params::kp_y_surface},
237  {"ki_y_surface", &Params::ki_y_surface},
238  {"kd_y_surface", &Params::kd_y_surface},
239  {"kp_z_surface", &Params::kp_z_surface},
240  {"ki_z_surface", &Params::ki_z_surface},
241  {"kd_z_surface", &Params::kd_z_surface},
242  {"kp_roll_surface", &Params::kp_roll_surface},
243  {"ki_roll_surface", &Params::ki_roll_surface},
244  {"kd_roll_surface", &Params::kd_roll_surface},
245  {"kp_pitch_surface", &Params::kp_pitch_surface},
246  {"ki_pitch_surface", &Params::ki_pitch_surface},
247  {"kd_pitch_surface", &Params::kd_pitch_surface},
248  {"kp_yaw_surface", &Params::kp_yaw_surface},
249  {"ki_yaw_surface", &Params::ki_yaw_surface},
250  {"kd_yaw_surface", &Params::kd_yaw_surface},
251  {"buoyancy_adaptive_rate", &Params::buoyancy_adaptive_rate},
252  {"buoyancy_adaptive_clamp_pct", &Params::buoyancy_adaptive_clamp_pct},
253  {"buoyancy_adaptive_pos_thresh", &Params::buoyancy_adaptive_pos_thresh},
254  {"buoyancy_adaptive_vel_thresh", &Params::buoyancy_adaptive_vel_thresh},
255  {"buoyancy_adaptive_rate_rp", &Params::buoyancy_adaptive_rate_rp},
256  {"buoyancy_adaptive_pos_thresh_rp", &Params::buoyancy_adaptive_pos_thresh_rp},
257  {"buoyancy_adaptive_vel_thresh_rp", &Params::buoyancy_adaptive_vel_thresh_rp},
258  {"slow_down_gain", &Params::slow_down_gain},
259  {"max_xy_vel", &Params::max_xy_vel},
260  {"max_xy_acc", &Params::max_xy_acc},
261  {"max_xy_jerk", &Params::max_xy_jerk},
262  {"max_z_vel", &Params::max_z_vel},
263  {"max_z_acc", &Params::max_z_acc},
264  {"max_z_jerk", &Params::max_z_jerk},
265  {"max_yaw_vel", &Params::max_yaw_vel},
266  {"max_yaw_acc", &Params::max_yaw_acc},
267  {"max_yaw_jerk", &Params::max_yaw_jerk},
268  {"mass", &Params::mass},
269  {"buoyancy_factor", &Params::buoyancy_factor},
270  {"i_xx", &Params::i_xx},
271  {"i_yy", &Params::i_yy},
272  {"i_zz", &Params::i_zz},
273  {"i_xy", &Params::i_xy},
274  {"i_xz", &Params::i_xz},
275  {"i_yz", &Params::i_yz},
276  {"ma_x", &Params::ma_x},
277  {"ma_y", &Params::ma_y},
278  {"ma_z", &Params::ma_z},
279  {"ma_roll", &Params::ma_roll},
280  {"ma_pitch", &Params::ma_pitch},
281  {"ma_yaw", &Params::ma_yaw},
282  {"dl_x", &Params::dl_x},
283  {"dl_y", &Params::dl_y},
284  {"dl_z", &Params::dl_z},
285  {"dl_roll", &Params::dl_roll},
286  {"dl_pitch", &Params::dl_pitch},
287  {"dl_yaw", &Params::dl_yaw},
288  {"dnl_x", &Params::dnl_x},
289  {"dnl_y", &Params::dnl_y},
290  {"dnl_z", &Params::dnl_z},
291  {"dnl_roll", &Params::dnl_roll},
292  {"dnl_pitch", &Params::dnl_pitch},
293  {"dnl_yaw", &Params::dnl_yaw},
294  {"rbb_x", &Params::rbb_x},
295  {"rbb_y", &Params::rbb_y},
296  {"rbb_z", &Params::rbb_z},
297  {"rgb_x", &Params::rgb_x},
298  {"rgb_y", &Params::rgb_y},
299  {"rgb_z", &Params::rgb_z},
300  {"cg_offset_x", &Params::cg_offset_x},
301  {"cg_offset_y", &Params::cg_offset_y},
302  {"cg_offset_z", &Params::cg_offset_z},
303  };
304 
305  static inline const std::unordered_map<std::string_view, bool Params::*> BOOL_PARAM_MAP = {
306  {"surface_gain_scheduling", &Params::surface_gain_scheduling},
307  {"buoyancy_adaptive_z", &Params::buoyancy_adaptive_z},
308  {"buoyancy_adaptive_rp", &Params::buoyancy_adaptive_rp},
309  };
310  // clang-format on
311 
312 protected:
314  static constexpr int CONTROL_LOOP_RATE = 20;
315 
317  static constexpr double MIN_DEPTH_CLAMP = 0.00;
318 
320  static constexpr double POSITION_JUMP_THRESHOLD = 0.5;
321 
323  std::once_flag control_loop_started_;
324 
326  const std::string vehicle_frame_id_;
327 
329  const std::string world_frame_id_;
330 
332  std::unique_ptr<Vehicle> auv_;
333 
334  // ROS subscribers
335  rclcpp::Subscription<nav_msgs::msg::Odometry>::SharedPtr world_sub_;
336  rclcpp::Subscription<bb_sensor_msgs::msg::BatteriesWithId>::SharedPtr battery_sub_;
337  rclcpp::Subscription<geometry_msgs::msg::Twist>::SharedPtr teleop_force_sub_;
338 
339  // ROS publishers
340  rclcpp::Publisher<geometry_msgs::msg::WrenchStamped>::SharedPtr pub_controller_force_;
341  rclcpp::Publisher<bb_controls_msgs::msg::ControllerStatus>::SharedPtr pub_status_;
342  rclcpp::Publisher<geometry_msgs::msg::PoseArray>::SharedPtr pub_traj_viz_;
343  rclcpp::Publisher<bb_controls_msgs::msg::Thrusters>::SharedPtr pub_thruster_commands_;
344  rclcpp::Publisher<geometry_msgs::msg::WrenchStamped>::SharedPtr pub_allocator_force_;
345  rclcpp::Publisher<bb_controls_msgs::msg::ThrusterForces>::SharedPtr pub_thruster_forces_;
346 
347  rclcpp::TimerBase::SharedPtr control_loop_timer_;
348  rclcpp::TimerBase::SharedPtr debug_publish_timer_;
349 
351  moodycamel::ConcurrentQueue<DebugMessage> debug_queue_;
352 
353  rclcpp::Service<bb_controls_msgs::srv::Controller>::SharedPtr controller_srv_;
354  rclcpp::Service<bb_controls_msgs::srv::SplineTraj>::SharedPtr spline_traj_srv_;
355  rclcpp::Service<bb_controls_msgs::srv::EncircleTraj>::SharedPtr encircle_traj_srv_;
356 
357  rclcpp_action::Server<Locomotion>::SharedPtr poly_action_server_;
358  std::mutex action_goal_mutex_;
359  std::shared_ptr<GoalHandleLocomotion> current_action_goal_;
360 
362  std::atomic<bool> shutdown_requested_{false};
363 
366 
367  OnSetParametersCallbackHandle::SharedPtr callback_handle_;
368 
371 
373  double prev_time_ = 0.0;
374 
377 
384  void control_loop();
385 
392 
399  void debug_publish_loop();
400 
408  rcl_interfaces::msg::SetParametersResult parameters_callback(const std::vector<rclcpp::Parameter>& parameters);
409 
414 
423 
428 
434  void sub_callback_world_position(const nav_msgs::msg::Odometry::ConstSharedPtr& m);
435 
441  void sub_callback_battery_voltage(const bb_sensor_msgs::msg::BatteriesWithId::ConstSharedPtr& msg);
442 
450  void sub_callback_teleop_force(const geometry_msgs::msg::Twist::ConstSharedPtr& msg);
451 
458  void srv_callback_controller(const std::shared_ptr<bb_controls_msgs::srv::Controller::Request> req,
459  std::shared_ptr<bb_controls_msgs::srv::Controller::Response> res);
460 
467  void srv_callback_trajectory_xyz(const std::shared_ptr<bb_controls_msgs::srv::SplineTraj::Request> req,
468  std::shared_ptr<bb_controls_msgs::srv::SplineTraj::Response> res);
469 
476  void srv_callback_encircle_traj(const std::shared_ptr<bb_controls_msgs::srv::EncircleTraj::Request> req,
477  std::shared_ptr<bb_controls_msgs::srv::EncircleTraj::Response> res);
478 
487  rclcpp_action::GoalResponse poly_handle_goal(const rclcpp_action::GoalUUID& uuid,
488  std::shared_ptr<const Locomotion::Goal> goal);
489 
497  rclcpp_action::CancelResponse poly_handle_cancel(const std::shared_ptr<GoalHandleLocomotion> goal_handle);
498 
504  void poly_handle_accepted(const std::shared_ptr<GoalHandleLocomotion> goal_handle);
505 
515  void poly_execute_action(const std::shared_ptr<GoalHandleLocomotion> goal_handle);
516 };
517 
518 #endif // CONTROLS_NODES_CONTROLSROS2WRAPPER_H
ROS2 node that wraps the Vehicle control stack and exposes its interface to the rest of the system.
Definition: ControlsROS2Wrapper.h:61
void debug_publish_loop()
Drains the debug queue and publishes all pending messages.
Definition: ControlsROS2Wrapper.cpp:170
rclcpp::Subscription< geometry_msgs::msg::Twist >::SharedPtr teleop_force_sub_
Definition: ControlsROS2Wrapper.h:337
rclcpp::Publisher< bb_controls_msgs::msg::ThrusterForces >::SharedPtr pub_thruster_forces_
Definition: ControlsROS2Wrapper.h:345
static const std::unordered_map< std::string_view, double Params::* > DOUBLE_PARAM_MAP
Maps ROS parameter names to their corresponding Params member pointers.
Definition: ControlsROS2Wrapper.h:204
~ControlsROS2Wrapper() override
Definition: ControlsROS2Wrapper.cpp:104
void sub_callback_teleop_force(const geometry_msgs::msg::Twist::ConstSharedPtr &msg)
Teleop subscriber callback — allocates the raw force directly if the controller is disabled.
Definition: ControlsROS2Wrapper.cpp:230
rclcpp::TimerBase::SharedPtr debug_publish_timer_
Definition: ControlsROS2Wrapper.h:348
const std::string world_frame_id_
TF frame_id of the world frame.
Definition: ControlsROS2Wrapper.h:329
rclcpp_action::GoalResponse poly_handle_goal(const rclcpp_action::GoalUUID &uuid, std::shared_ptr< const Locomotion::Goal > goal)
Action server goal handler — rejects goals when the controller is disabled.
Definition: ControlsROS2Wrapper.cpp:317
rclcpp_action::CancelResponse poly_handle_cancel(const std::shared_ptr< GoalHandleLocomotion > goal_handle)
Action server cancel handler — always accepts cancel requests.
Definition: ControlsROS2Wrapper.cpp:327
std::shared_ptr< GoalHandleLocomotion > current_action_goal_
Definition: ControlsROS2Wrapper.h:359
rclcpp::Subscription< nav_msgs::msg::Odometry >::SharedPtr world_sub_
Definition: ControlsROS2Wrapper.h:335
std::mutex action_goal_mutex_
Definition: ControlsROS2Wrapper.h:358
void apply_config_to_vehicle()
Applies config_ to the Vehicle's dynamics model, controller gains, and limits.
Definition: ControlsROS2Wrapper.cpp:540
static constexpr double MIN_DEPTH_CLAMP
Minimum depth value clamp to avoid near-zero depth noise (m)
Definition: ControlsROS2Wrapper.h:317
void sub_callback_battery_voltage(const bb_sensor_msgs::msg::BatteriesWithId::ConstSharedPtr &msg)
Battery subscriber callback — forwards the minimum cell voltage to the Vehicle.
Definition: ControlsROS2Wrapper.cpp:222
static constexpr int CONTROL_LOOP_RATE
Control loop frequency in Hz.
Definition: ControlsROS2Wrapper.h:314
rclcpp::Service< bb_controls_msgs::srv::SplineTraj >::SharedPtr spline_traj_srv_
Definition: ControlsROS2Wrapper.h:354
rclcpp::Service< bb_controls_msgs::srv::EncircleTraj >::SharedPtr encircle_traj_srv_
Definition: ControlsROS2Wrapper.h:355
Params config_
Local snapshot of ROS parameters, pushed to Vehicle subsystems on change.
Definition: ControlsROS2Wrapper.h:370
rclcpp_action::ServerGoalHandle< Locomotion > GoalHandleLocomotion
Definition: ControlsROS2Wrapper.h:83
rclcpp::Publisher< geometry_msgs::msg::WrenchStamped >::SharedPtr pub_controller_force_
Definition: ControlsROS2Wrapper.h:340
std::once_flag control_loop_started_
Flag for starting control loop.
Definition: ControlsROS2Wrapper.h:323
void load_params_from_server()
Reads all declared ROS parameters into config_.
Definition: ControlsROS2Wrapper.cpp:530
rcl_interfaces::msg::SetParametersResult parameters_callback(const std::vector< rclcpp::Parameter > &parameters)
Callback invoked by the ROS parameter system when any parameter changes.
Definition: ControlsROS2Wrapper.cpp:609
void poly_execute_action(const std::shared_ptr< GoalHandleLocomotion > goal_handle)
Executes a Locomotion action: plans trajectory, waits for completion, checks tolerances.
Definition: ControlsROS2Wrapper.cpp:352
ControlsROS2Wrapper & operator=(ControlsROS2Wrapper &&)=delete
rclcpp::Publisher< geometry_msgs::msg::WrenchStamped >::SharedPtr pub_allocator_force_
Definition: ControlsROS2Wrapper.h:344
OnSetParametersCallbackHandle::SharedPtr callback_handle_
Definition: ControlsROS2Wrapper.h:367
rclcpp::CallbackGroup::SharedPtr actions_cb_group_
Definition: ControlsROS2Wrapper.h:375
std::thread action_execute_thread_
Thread running action execute method; joined before destruction.
Definition: ControlsROS2Wrapper.h:365
void control_loop()
Executes one iteration of the 20 Hz control loop.
Definition: ControlsROS2Wrapper.cpp:116
std::atomic< bool > shutdown_requested_
Signals the action execution thread to exit its loop.
Definition: ControlsROS2Wrapper.h:362
moodycamel::ConcurrentQueue< DebugMessage > debug_queue_
Lock-free queue through which the control loop passes debug messages to the publish timer.
Definition: ControlsROS2Wrapper.h:351
rclcpp::CallbackGroup::SharedPtr odom_cb_group_
Definition: ControlsROS2Wrapper.h:375
rclcpp::TimerBase::SharedPtr control_loop_timer_
Definition: ControlsROS2Wrapper.h:347
ControlsROS2Wrapper & operator=(const ControlsROS2Wrapper &)=delete
rclcpp::CallbackGroup::SharedPtr aux_cb_group_
Definition: ControlsROS2Wrapper.h:376
ControlsROS2Wrapper(ControlsROS2Wrapper &&)=delete
ControlsROS2Wrapper(const ControlsROS2Wrapper &)=delete
void declare_controller_params()
Registers all entries in DOUBLE_PARAM_MAP / BOOL_PARAM_MAP with the ROS parameter server.
Definition: ControlsROS2Wrapper.cpp:520
void srv_callback_trajectory_xyz(const std::shared_ptr< bb_controls_msgs::srv::SplineTraj::Request > req, std::shared_ptr< bb_controls_msgs::srv::SplineTraj::Response > res)
Service callback to request a straight XYZ or multi-waypoint spline trajectory.
Definition: ControlsROS2Wrapper.cpp:260
static constexpr double POSITION_JUMP_THRESHOLD
Position jump threshold for outlier rejection (m)
Definition: ControlsROS2Wrapper.h:320
rclcpp::Publisher< bb_controls_msgs::msg::ControllerStatus >::SharedPtr pub_status_
Definition: ControlsROS2Wrapper.h:341
const std::string vehicle_frame_id_
TF child_frame_id of the vehicle body frame.
Definition: ControlsROS2Wrapper.h:326
void poly_handle_accepted(const std::shared_ptr< GoalHandleLocomotion > goal_handle)
Action server accepted handler — preempts any active goal and starts a new execute thread.
Definition: ControlsROS2Wrapper.cpp:332
rclcpp::Subscription< bb_sensor_msgs::msg::BatteriesWithId >::SharedPtr battery_sub_
Definition: ControlsROS2Wrapper.h:336
void srv_callback_encircle_traj(const std::shared_ptr< bb_controls_msgs::srv::EncircleTraj::Request > req, std::shared_ptr< bb_controls_msgs::srv::EncircleTraj::Response > res)
Service callback to request a circular arc (encircle) trajectory.
Definition: ControlsROS2Wrapper.cpp:287
void srv_callback_controller(const std::shared_ptr< bb_controls_msgs::srv::Controller::Request > req, std::shared_ptr< bb_controls_msgs::srv::Controller::Response > res)
Service callback to enable (stationkeep) or disable the controller.
Definition: ControlsROS2Wrapper.cpp:248
rclcpp::Publisher< bb_controls_msgs::msg::Thrusters >::SharedPtr pub_thruster_commands_
Definition: ControlsROS2Wrapper.h:343
rclcpp_action::Server< Locomotion >::SharedPtr poly_action_server_
Definition: ControlsROS2Wrapper.h:357
rclcpp::Service< bb_controls_msgs::srv::Controller >::SharedPtr controller_srv_
Definition: ControlsROS2Wrapper.h:353
void sub_callback_world_position(const nav_msgs::msg::Odometry::ConstSharedPtr &m)
Odometry subscriber callback — updates vehicle state and starts the control loop.
Definition: ControlsROS2Wrapper.cpp:195
rclcpp::CallbackGroup::SharedPtr control_loop_cb_group_
Definition: ControlsROS2Wrapper.h:375
void publish_controller_status(const Vehicle::ControllerStatus &status)
Publishes a ControllerStatus message from the given status snapshot.
Definition: ControlsROS2Wrapper.cpp:156
bb_controls_msgs::action::Locomotion Locomotion
Definition: ControlsROS2Wrapper.h:82
rclcpp::Publisher< geometry_msgs::msg::PoseArray >::SharedPtr pub_traj_viz_
Definition: ControlsROS2Wrapper.h:342
ControlsROS2Wrapper(const std::string &name, std::unique_ptr< Vehicle > robot, std::string body_frame_tf_name="base_link", std::string world_frame_tf_name="map")
Constructs the node, initialises all ROS interfaces, and loads parameters.
Definition: ControlsROS2Wrapper.cpp:20
double prev_time_
ROS timestamp of the previous control loop iteration.
Definition: ControlsROS2Wrapper.h:373
rclcpp::CallbackGroup::SharedPtr services_cb_group_
Definition: ControlsROS2Wrapper.h:375
std::unique_ptr< Vehicle > auv_
Encapsulated vehicle control stack.
Definition: ControlsROS2Wrapper.h:332
static const std::unordered_map< std::string_view, bool Params::* > BOOL_PARAM_MAP
Definition: ControlsROS2Wrapper.h:305
Internal representation of all ROS-declared controller and dynamics parameters.
Definition: ControlsROS2Wrapper.h:92
double ma_x
Definition: ControlsROS2Wrapper.h:173
double kd_x_surface
Definition: ControlsROS2Wrapper.h:124
double buoyancy_adaptive_vel_thresh_rp
Definition: ControlsROS2Wrapper.h:162
double ki_roll
Definition: ControlsROS2Wrapper.h:114
double axis_gain_roll
Definition: ControlsROS2Wrapper.h:101
double ki_yaw_surface
Definition: ControlsROS2Wrapper.h:138
double rgb_x
Definition: ControlsROS2Wrapper.h:194
double dnl_yaw
Definition: ControlsROS2Wrapper.h:190
double rbb_y
Definition: ControlsROS2Wrapper.h:192
double ki_yaw
Definition: ControlsROS2Wrapper.h:120
double max_yaw_jerk
Definition: ControlsROS2Wrapper.h:149
double max_xy_vel
Definition: ControlsROS2Wrapper.h:141
double kd_x
Definition: ControlsROS2Wrapper.h:106
double dl_z
Definition: ControlsROS2Wrapper.h:181
double dnl_roll
Definition: ControlsROS2Wrapper.h:188
double kp_z_surface
Definition: ControlsROS2Wrapper.h:128
double kd_roll_surface
Definition: ControlsROS2Wrapper.h:133
double rbb_z
Definition: ControlsROS2Wrapper.h:193
double axis_gain_z
Definition: ControlsROS2Wrapper.h:100
double ki_y
Definition: ControlsROS2Wrapper.h:108
double kp_yaw
Definition: ControlsROS2Wrapper.h:119
double buoyancy_factor
Definition: ControlsROS2Wrapper.h:166
double kd_z_surface
Definition: ControlsROS2Wrapper.h:130
double buoyancy_adaptive_pos_thresh_rp
Definition: ControlsROS2Wrapper.h:161
double kd_y
Definition: ControlsROS2Wrapper.h:109
double rgb_z
Definition: ControlsROS2Wrapper.h:196
double ki_x_surface
Definition: ControlsROS2Wrapper.h:123
double ma_yaw
Definition: ControlsROS2Wrapper.h:178
double kd_yaw
Definition: ControlsROS2Wrapper.h:121
double i_xy
Definition: ControlsROS2Wrapper.h:170
double kd_pitch
Definition: ControlsROS2Wrapper.h:118
double kd_roll
Definition: ControlsROS2Wrapper.h:115
double rgb_y
Definition: ControlsROS2Wrapper.h:195
double cg_offset_y
Definition: ControlsROS2Wrapper.h:198
double kd_y_surface
Definition: ControlsROS2Wrapper.h:127
double fb_gain
Definition: ControlsROS2Wrapper.h:94
double buoyancy_gain
Definition: ControlsROS2Wrapper.h:95
double ki_roll_surface
Definition: ControlsROS2Wrapper.h:132
double kd_yaw_surface
Definition: ControlsROS2Wrapper.h:139
double dl_yaw
Definition: ControlsROS2Wrapper.h:184
double ki_x
Definition: ControlsROS2Wrapper.h:105
double kp_roll
Definition: ControlsROS2Wrapper.h:113
double ma_y
Definition: ControlsROS2Wrapper.h:174
bool surface_gain_scheduling
Definition: ControlsROS2Wrapper.h:96
double rbb_x
Definition: ControlsROS2Wrapper.h:191
double i_yz
Definition: ControlsROS2Wrapper.h:172
double dnl_pitch
Definition: ControlsROS2Wrapper.h:189
double dnl_x
Definition: ControlsROS2Wrapper.h:185
double max_xy_jerk
Definition: ControlsROS2Wrapper.h:143
double max_xy_acc
Definition: ControlsROS2Wrapper.h:142
double buoyancy_adaptive_pos_thresh
Definition: ControlsROS2Wrapper.h:155
double buoyancy_adaptive_rate_rp
Definition: ControlsROS2Wrapper.h:160
double dl_roll
Definition: ControlsROS2Wrapper.h:182
double ki_z_surface
Definition: ControlsROS2Wrapper.h:129
double kp_x
Definition: ControlsROS2Wrapper.h:104
double max_z_jerk
Definition: ControlsROS2Wrapper.h:146
double cg_offset_z
Definition: ControlsROS2Wrapper.h:199
double ki_y_surface
Definition: ControlsROS2Wrapper.h:126
double ki_pitch_surface
Definition: ControlsROS2Wrapper.h:135
double max_z_vel
Definition: ControlsROS2Wrapper.h:144
double ki_pitch
Definition: ControlsROS2Wrapper.h:117
double kp_z
Definition: ControlsROS2Wrapper.h:110
double kd_z
Definition: ControlsROS2Wrapper.h:112
double dnl_z
Definition: ControlsROS2Wrapper.h:187
bool buoyancy_adaptive_rp
Definition: ControlsROS2Wrapper.h:159
double dl_pitch
Definition: ControlsROS2Wrapper.h:183
double kp_y
Definition: ControlsROS2Wrapper.h:107
double cg_offset_x
Definition: ControlsROS2Wrapper.h:197
bool buoyancy_adaptive_z
Definition: ControlsROS2Wrapper.h:152
double ki_z
Definition: ControlsROS2Wrapper.h:111
double kp_y_surface
Definition: ControlsROS2Wrapper.h:125
double axis_gain_yaw
Definition: ControlsROS2Wrapper.h:103
double kp_x_surface
Definition: ControlsROS2Wrapper.h:122
double slow_down_gain
Definition: ControlsROS2Wrapper.h:140
double max_yaw_vel
Definition: ControlsROS2Wrapper.h:147
double buoyancy_adaptive_rate
Definition: ControlsROS2Wrapper.h:153
double mass
Definition: ControlsROS2Wrapper.h:165
double max_yaw_acc
Definition: ControlsROS2Wrapper.h:148
double kp_pitch_surface
Definition: ControlsROS2Wrapper.h:134
double i_zz
Definition: ControlsROS2Wrapper.h:169
double i_xx
Definition: ControlsROS2Wrapper.h:167
double i_xz
Definition: ControlsROS2Wrapper.h:171
double i_yy
Definition: ControlsROS2Wrapper.h:168
double axis_gain_x
Definition: ControlsROS2Wrapper.h:98
double dl_x
Definition: ControlsROS2Wrapper.h:179
double ff_gain
Definition: ControlsROS2Wrapper.h:93
double ma_roll
Definition: ControlsROS2Wrapper.h:176
double kd_pitch_surface
Definition: ControlsROS2Wrapper.h:136
double surface_threshold
Definition: ControlsROS2Wrapper.h:97
double ma_z
Definition: ControlsROS2Wrapper.h:175
double buoyancy_adaptive_vel_thresh
Definition: ControlsROS2Wrapper.h:156
double dl_y
Definition: ControlsROS2Wrapper.h:180
double axis_gain_pitch
Definition: ControlsROS2Wrapper.h:102
double ma_pitch
Definition: ControlsROS2Wrapper.h:177
double kp_roll_surface
Definition: ControlsROS2Wrapper.h:131
double max_z_acc
Definition: ControlsROS2Wrapper.h:145
double buoyancy_adaptive_clamp_pct
Definition: ControlsROS2Wrapper.h:154
double kp_pitch
Definition: ControlsROS2Wrapper.h:116
double dnl_y
Definition: ControlsROS2Wrapper.h:186
double axis_gain_y
Definition: ControlsROS2Wrapper.h:99
double kp_yaw_surface
Definition: ControlsROS2Wrapper.h:137
Snapshot of controller status exposed to external callers.
Definition: Vehicle.h:51