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 > systemProperties, std::shared_ptr< ControllerConfig > controller_config)
 Constructs the combined controller with shared dynamics and config. More...
 
Vector6d spinControllerOnce (const State &goal, const State &current, const bool saturatedOnYawXYAxis, const bool saturatedOnDepthRollPitchAxis, double dt) override
 Computes the total 6DOF body force as a weighted sum of all sub-controllers. More...
 
Vector6d getBodyPoseError () const override
 Returns the most recently computed body-frame pose error from the feedback controller. More...
 
void onTrajectoryStarting () override
 Saves the feedback integral and buoyancy bias before trajectory execution begins. More...
 
void onTrajectoryFinished () override
 Restores the saved integral and buoyancy bias after a trajectory finishes naturally. More...
 
void onStationkeepEntered () override
 Restores the saved integral and buoyancy bias when stationkeep is entered. More...
 
void onTrajectoryProgress (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 > systemDynamics, 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< SystemDynamicsBasesystemDynamics
 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 systemProperties,
std::shared_ptr< ControllerConfig controller_config 
)

Constructs the combined controller with shared dynamics and config.

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

Member Function Documentation

◆ getBodyPoseError()

Vector6d FfFbVehicleController::getBodyPoseError ( ) const
overridevirtual

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

Returns
6-element pose error vector

Implements VehicleControllerInterface.

◆ onStationkeepEntered()

void FfFbVehicleController::onStationkeepEntered ( )
overridevirtual

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

Implements VehicleControllerInterface.

◆ onTrajectoryFinished()

void FfFbVehicleController::onTrajectoryFinished ( )
overridevirtual

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

Implements VehicleControllerInterface.

◆ onTrajectoryProgress()

void FfFbVehicleController::onTrajectoryProgress ( 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.

◆ onTrajectoryStarting()

void FfFbVehicleController::onTrajectoryStarting ( )
overridevirtual

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

Implements VehicleControllerInterface.

◆ spinControllerOnce()

Vector6d FfFbVehicleController::spinControllerOnce ( const State goal,
const State current,
const bool  saturatedOnYawXYAxis,
const bool  saturatedOnDepthRollPitchAxis,
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
saturatedOnYawXYAxis[in] True when X, Y, or Yaw axes are saturated
saturatedOnDepthRollPitchAxis[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: