controls  3.0.0
Public Member Functions | List of all members
FfFbVehicleController Class Reference

Vehicle controller combining feed-forward, PID feedback, and buoyancy compensation. More...

#include <FfFbVehicleController.h>

Inheritance diagram for FfFbVehicleController:
VehicleControllerInterface

Public Member Functions

 FfFbVehicleController (std::shared_ptr< SystemDynamicsBase > system_properties, std::shared_ptr< ControllerConfig > controller_config)
 Constructs the combined controller with shared dynamics and config. More...
 
Vector6d spin_controller_once (const State &goal, const State &current, const bool saturated_on_yaw_xy_axis, const bool saturated_on_depth_roll_pitch_axis, double dt) override
 Computes the total 6DOF body force as a weighted sum of all sub-controllers. More...
 
Vector6d get_body_pose_error () const override
 Returns the most recently computed body-frame pose error from the feedback controller. More...
 
void on_trajectory_starting () override
 Saves the feedback integral and buoyancy bias before trajectory execution begins. More...
 
void on_trajectory_finished () override
 Restores the saved integral and buoyancy bias after a trajectory finishes naturally. More...
 
void on_stationkeep_entered () override
 Restores the saved integral and buoyancy bias when stationkeep is entered. More...
 
void on_trajectory_progress (double progress) override
 Ramps the feedback integral from its current value toward the saved snapshot. More...
 
- Public Member Functions inherited from VehicleControllerInterface
 VehicleControllerInterface (std::shared_ptr< SystemDynamicsBase > system_dynamics, std::shared_ptr< ControllerConfig > controller_config)
 Constructs a vehicle controller with shared dynamics and config. More...
 
virtual ~VehicleControllerInterface ()=default
 

Additional Inherited Members

- Public Attributes inherited from VehicleControllerInterface
std::shared_ptr< SystemDynamicsBasesystem_dynamics_
 Vehicle dynamics model used by this controller. More...
 
std::shared_ptr< ControllerConfigcontroller_config_
 Tuning parameters used by this controller. More...
 

Detailed Description

Vehicle controller combining feed-forward, PID feedback, and buoyancy compensation.

The total force is: ff_gain * FF + fb_gain * FB + buoyancy_gain * B, scaled per-axis by axis_gain. The feedback controller's integral term and the buoyancy controller's adaptive bias are snapshotted at trajectory start and restored on finish or stationkeep entry to prevent corruption across trajectory segments.

Constructor & Destructor Documentation

◆ FfFbVehicleController()

FfFbVehicleController::FfFbVehicleController ( std::shared_ptr< SystemDynamicsBase system_properties,
std::shared_ptr< ControllerConfig controller_config 
)

Constructs the combined controller with shared dynamics and config.

Parameters
system_properties[in] Shared vehicle dynamics model
controller_config[in] Shared controller tuning parameters

Member Function Documentation

◆ get_body_pose_error()

Vector6d FfFbVehicleController::get_body_pose_error ( ) const
overridevirtual

Returns the most recently computed body-frame pose error from the feedback controller.

Returns
6-element pose error vector

Implements VehicleControllerInterface.

◆ on_stationkeep_entered()

void FfFbVehicleController::on_stationkeep_entered ( )
overridevirtual

Restores the saved integral and buoyancy bias when stationkeep is entered.

Implements VehicleControllerInterface.

◆ on_trajectory_finished()

void FfFbVehicleController::on_trajectory_finished ( )
overridevirtual

Restores the saved integral and buoyancy bias after a trajectory finishes naturally.

Implements VehicleControllerInterface.

◆ on_trajectory_progress()

void FfFbVehicleController::on_trajectory_progress ( double  progress)
overridevirtual

Ramps the feedback integral from its current value toward the saved snapshot.

Parameters
progress[in] Fractional trajectory completion in [0, 1]

Implements VehicleControllerInterface.

◆ on_trajectory_starting()

void FfFbVehicleController::on_trajectory_starting ( )
overridevirtual

Saves the feedback integral and buoyancy bias before trajectory execution begins.

Implements VehicleControllerInterface.

◆ spin_controller_once()

Vector6d FfFbVehicleController::spin_controller_once ( const State goal,
const State current,
const bool  saturated_on_yaw_xy_axis,
const bool  saturated_on_depth_roll_pitch_axis,
double  dt 
)
overridevirtual

Computes the total 6DOF body force as a weighted sum of all sub-controllers.

Parameters
goal[in] Desired vehicle state
current[in] Current vehicle state
saturated_on_yaw_xy_axis[in] True when X, Y, or Yaw axes are saturated
saturated_on_depth_roll_pitch_axis[in] True when Z, Roll, or Pitch axes are saturated
dt[in] Time step in seconds
Returns
6-element body force/torque vector [Fx, Fy, Fz, Tx, Ty, Tz] in N and Nm

Implements VehicleControllerInterface.


The documentation for this class was generated from the following files: