|
controls
3.0.0
|
ROS2 node that wraps the Vehicle control stack and exposes its interface to the rest of the system. More...
#include <ControlsROS2Wrapper.h>
Classes | |
| struct | Params |
| Internal representation of all ROS-declared controller and dynamics parameters. More... | |
Public Types | |
| using | Locomotion = bb_controls_msgs::action::Locomotion |
| using | GoalHandleLocomotion = rclcpp_action::ServerGoalHandle< Locomotion > |
Public Member Functions | |
| 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. More... | |
| ~ControlsROS2Wrapper () override | |
| ControlsROS2Wrapper (const ControlsROS2Wrapper &)=delete | |
| ControlsROS2Wrapper & | operator= (const ControlsROS2Wrapper &)=delete |
| ControlsROS2Wrapper (ControlsROS2Wrapper &&)=delete | |
| ControlsROS2Wrapper & | operator= (ControlsROS2Wrapper &&)=delete |
Static Public Attributes | |
| static const std::unordered_map< std::string_view, double Params::* > | DOUBLE_PARAM_MAP |
| Maps ROS parameter names to their corresponding Params member pointers. More... | |
| static const std::unordered_map< std::string_view, bool Params::* > | BOOL_PARAM_MAP |
Protected Member Functions | |
| void | control_loop () |
| Executes one iteration of the 20 Hz control loop. More... | |
| void | publish_controller_status (const Vehicle::ControllerStatus &status) |
| Publishes a ControllerStatus message from the given status snapshot. More... | |
| void | debug_publish_loop () |
| Drains the debug queue and publishes all pending messages. More... | |
| rcl_interfaces::msg::SetParametersResult | parameters_callback (const std::vector< rclcpp::Parameter > ¶meters) |
| Callback invoked by the ROS parameter system when any parameter changes. More... | |
| void | declare_controller_params () |
| Registers all entries in DOUBLE_PARAM_MAP / BOOL_PARAM_MAP with the ROS parameter server. More... | |
| void | load_params_from_server () |
| Reads all declared ROS parameters into config_. More... | |
| void | apply_config_to_vehicle () |
| Applies config_ to the Vehicle's dynamics model, controller gains, and limits. More... | |
| void | sub_callback_world_position (const nav_msgs::msg::Odometry::ConstSharedPtr &m) |
| Odometry subscriber callback — updates vehicle state and starts the control loop. More... | |
| void | sub_callback_battery_voltage (const bb_sensor_msgs::msg::BatteriesWithId::ConstSharedPtr &msg) |
| Battery subscriber callback — forwards the minimum cell voltage to the Vehicle. More... | |
| 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. More... | |
| 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. More... | |
| 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. More... | |
| 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. More... | |
| 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. More... | |
| rclcpp_action::CancelResponse | poly_handle_cancel (const std::shared_ptr< GoalHandleLocomotion > goal_handle) |
| Action server cancel handler — always accepts cancel requests. More... | |
| 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. More... | |
| void | poly_execute_action (const std::shared_ptr< GoalHandleLocomotion > goal_handle) |
| Executes a Locomotion action: plans trajectory, waits for completion, checks tolerances. More... | |
Protected Attributes | |
| std::once_flag | control_loop_started_ |
| Flag for starting control loop. More... | |
| const std::string | vehicle_frame_id_ |
| TF child_frame_id of the vehicle body frame. More... | |
| const std::string | world_frame_id_ |
| TF frame_id of the world frame. More... | |
| std::unique_ptr< Vehicle > | auv_ |
| Encapsulated vehicle control stack. More... | |
| rclcpp::Subscription< nav_msgs::msg::Odometry >::SharedPtr | world_sub_ |
| rclcpp::Subscription< bb_sensor_msgs::msg::BatteriesWithId >::SharedPtr | battery_sub_ |
| rclcpp::Subscription< geometry_msgs::msg::Twist >::SharedPtr | teleop_force_sub_ |
| rclcpp::Publisher< geometry_msgs::msg::WrenchStamped >::SharedPtr | pub_controller_force_ |
| rclcpp::Publisher< bb_controls_msgs::msg::ControllerStatus >::SharedPtr | pub_status_ |
| rclcpp::Publisher< geometry_msgs::msg::PoseArray >::SharedPtr | pub_traj_viz_ |
| rclcpp::Publisher< bb_controls_msgs::msg::Thrusters >::SharedPtr | pub_thruster_commands_ |
| rclcpp::Publisher< geometry_msgs::msg::WrenchStamped >::SharedPtr | pub_allocator_force_ |
| rclcpp::Publisher< bb_controls_msgs::msg::ThrusterForces >::SharedPtr | pub_thruster_forces_ |
| rclcpp::TimerBase::SharedPtr | control_loop_timer_ |
| rclcpp::TimerBase::SharedPtr | debug_publish_timer_ |
| moodycamel::ConcurrentQueue< DebugMessage > | debug_queue_ |
| Lock-free queue through which the control loop passes debug messages to the publish timer. More... | |
| rclcpp::Service< bb_controls_msgs::srv::Controller >::SharedPtr | controller_srv_ |
| rclcpp::Service< bb_controls_msgs::srv::SplineTraj >::SharedPtr | spline_traj_srv_ |
| rclcpp::Service< bb_controls_msgs::srv::EncircleTraj >::SharedPtr | encircle_traj_srv_ |
| rclcpp_action::Server< Locomotion >::SharedPtr | poly_action_server_ |
| std::mutex | action_goal_mutex_ |
| std::shared_ptr< GoalHandleLocomotion > | current_action_goal_ |
| std::atomic< bool > | shutdown_requested_ {false} |
| Signals the action execution thread to exit its loop. More... | |
| std::thread | action_execute_thread_ |
| Thread running action execute method; joined before destruction. More... | |
| OnSetParametersCallbackHandle::SharedPtr | callback_handle_ |
| Params | config_ |
| Local snapshot of ROS parameters, pushed to Vehicle subsystems on change. More... | |
| double | prev_time_ = 0.0 |
| ROS timestamp of the previous control loop iteration. More... | |
| rclcpp::CallbackGroup::SharedPtr | odom_cb_group_ |
| rclcpp::CallbackGroup::SharedPtr | control_loop_cb_group_ |
| rclcpp::CallbackGroup::SharedPtr | services_cb_group_ |
| rclcpp::CallbackGroup::SharedPtr | actions_cb_group_ |
| rclcpp::CallbackGroup::SharedPtr | aux_cb_group_ |
Static Protected Attributes | |
| static constexpr int | CONTROL_LOOP_RATE = 20 |
| Control loop frequency in Hz. More... | |
| static constexpr double | MIN_DEPTH_CLAMP = 0.00 |
| Minimum depth value clamp to avoid near-zero depth noise (m) More... | |
| static constexpr double | POSITION_JUMP_THRESHOLD = 0.5 |
| Position jump threshold for outlier rejection (m) More... | |
ROS2 node that wraps the Vehicle control stack and exposes its interface to the rest of the system.
Manages all ROS publishers, subscribers, services, and actions. Runs the 20 Hz control loop (started on receipt of the first odometry message), drains a lock-free debug queue at 20 Hz on a separate timer, and forwards parameter updates to the Vehicle and SystemDynamicsBase objects at runtime.
Services:
Actions:
Subscriptions:
Publications:
| using ControlsROS2Wrapper::GoalHandleLocomotion = rclcpp_action::ServerGoalHandle<Locomotion> |
| using ControlsROS2Wrapper::Locomotion = bb_controls_msgs::action::Locomotion |
|
explicit |
Constructs the node, initialises all ROS interfaces, and loads parameters.
| name | [in] ROS node name |
| robot | [in] Fully constructed Vehicle instance |
| body_frame_tf_name | [in] TF frame ID of the vehicle body frame |
| world_frame_tf_name | [in] TF frame ID of the world frame |
|
override |
|
delete |
|
delete |
|
protected |
Applies config_ to the Vehicle's dynamics model, controller gains, and limits.
|
protected |
Executes one iteration of the 20 Hz control loop.
Calls process_pending, get_force, allocate_force, and publishes thruster commands. Enqueues debug data for the background publish timer.
|
protected |
Drains the debug queue and publishes all pending messages.
Also publishes the current controller status. Called at 20 Hz by a separate timer on the aux callback group.
|
protected |
Registers all entries in DOUBLE_PARAM_MAP / BOOL_PARAM_MAP with the ROS parameter server.
|
protected |
Reads all declared ROS parameters into config_.
Only valid when values have already been committed to the server (i.e. at startup, after declare_controller_params). Must NOT be called from inside a set-parameter callback, where the new values are not yet committed.
|
delete |
|
delete |
|
protected |
Callback invoked by the ROS parameter system when any parameter changes.
| parameters | [in] List of parameters that were set |
|
protected |
Executes a Locomotion action: plans trajectory, waits for completion, checks tolerances.
Runs in action_execute_thread_. Publishes periodic feedback and resolves the action result to SUCCESS when pose errors fall within the goal tolerances, or to ABORTED/FAILURE on preemption or planning errors.
| goal_handle | [in] Handle used to publish feedback and set the final result |
|
protected |
Action server accepted handler — preempts any active goal and starts a new execute thread.
| goal_handle | [in] Handle to the newly accepted goal |
|
protected |
Action server cancel handler — always accepts cancel requests.
| goal_handle | [in] Handle to the goal being cancelled |
|
protected |
Action server goal handler — rejects goals when the controller is disabled.
| uuid | [in] Goal UUID assigned by the action client |
| goal | [in] Locomotion goal |
|
protected |
Publishes a ControllerStatus message from the given status snapshot.
| status | [in] Controller status snapshot to publish |
|
protected |
Service callback to enable (stationkeep) or disable the controller.
| req | [in] Request with an enable flag |
| res | [out] Response with a status flag (always true) |
|
protected |
Service callback to request a circular arc (encircle) trajectory.
| req | [in] EncircleTraj request containing radius, turn angle, and spiral parameters |
| res | [out] Response populated with the assigned trajectory UUID, or empty on failure |
|
protected |
Service callback to request a straight XYZ or multi-waypoint spline trajectory.
| req | [in] SplineTraj request containing waypoints and relative-coordinate flags |
| res | [out] Response populated with the assigned trajectory UUID, or empty on failure |
|
protected |
Battery subscriber callback — forwards the minimum cell voltage to the Vehicle.
| msg | [in] Incoming battery message containing per-cell voltages |
|
protected |
Teleop subscriber callback — allocates the raw force directly if the controller is disabled.
If the controller is not disabled, issues a disable request and ignores the message.
| msg | [in] Twist message interpreted as a 6DOF body force [Fx, Fy, Fz, Tx, Ty, Tz] |
|
protected |
Odometry subscriber callback — updates vehicle state and starts the control loop.
| m | [in] Incoming odometry message |
|
protected |
Thread running action execute method; joined before destruction.
|
protected |
|
protected |
|
protected |
Encapsulated vehicle control stack.
|
protected |
|
protected |
|
inlinestatic |
|
protected |
|
protected |
Local snapshot of ROS parameters, pushed to Vehicle subsystems on change.
|
protected |
|
staticconstexprprotected |
Control loop frequency in Hz.
|
protected |
Flag for starting control loop.
|
protected |
|
protected |
|
protected |
|
protected |
|
protected |
Lock-free queue through which the control loop passes debug messages to the publish timer.
|
inlinestatic |
Maps ROS parameter names to their corresponding Params member pointers.
|
protected |
|
staticconstexprprotected |
Minimum depth value clamp to avoid near-zero depth noise (m)
|
protected |
|
protected |
|
staticconstexprprotected |
Position jump threshold for outlier rejection (m)
|
protected |
ROS timestamp of the previous control loop iteration.
|
protected |
|
protected |
|
protected |
|
protected |
|
protected |
|
protected |
|
protected |
|
protected |
Signals the action execution thread to exit its loop.
|
protected |
|
protected |
|
protected |
TF child_frame_id of the vehicle body frame.
|
protected |
TF frame_id of the world frame.
|
protected |