1 #ifndef CONTROLS_CONTROLLER_FF_FB_VEHICLE_CONTROLLER_H
2 #define CONTROLS_CONTROLLER_FF_FB_VEHICLE_CONTROLLER_H
55 const bool saturatedOnDepthRollPitchAxis,
double dt)
override;
Eigen::Matrix< double, 6, 1 > Vector6d
Definition: Types.h:29
Controller that compensates for buoyancy and gravity restoring forces.
Definition: BuoyancyController.h:25
PID feedback controller with anti-windup integral clamping.
Definition: FeedbackController.h:14
Controller that computes open-loop forces via inverse dynamics.
Definition: FeedforwardController.h:14
Vehicle controller combining feed-forward, PID feedback, and buoyancy compensation.
Definition: FfFbVehicleController.h:19
Vector6d spinControllerOnce(const State &goal, const State ¤t, const bool saturatedOnYawXYAxis, const bool saturatedOnDepthRollPitchAxis, double dt) override
Computes the total 6DOF body force as a weighted sum of all sub-controllers.
Definition: FfFbVehicleController.cpp:19
void onStationkeepEntered() override
Restores the saved integral and buoyancy bias when stationkeep is entered.
Definition: FfFbVehicleController.cpp:57
void onTrajectoryStarting() override
Saves the feedback integral and buoyancy bias before trajectory execution begins.
Definition: FfFbVehicleController.cpp:47
void onTrajectoryFinished() override
Restores the saved integral and buoyancy bias after a trajectory finishes naturally.
Definition: FfFbVehicleController.cpp:52
FfFbVehicleController(std::shared_ptr< SystemDynamicsBase > systemProperties, std::shared_ptr< ControllerConfig > controller_config)
Constructs the combined controller with shared dynamics and config.
Definition: FfFbVehicleController.cpp:8
Vector6d getBodyPoseError() const override
Returns the most recently computed body-frame pose error from the feedback controller.
Definition: FfFbVehicleController.cpp:36
void onTrajectoryProgress(double progress) override
Ramps the feedback integral from its current value toward the saved snapshot.
Definition: FfFbVehicleController.cpp:62
Abstract interface for the vehicle-level controller.
Definition: VehicleControllerInterface.h:18
std::shared_ptr< ControllerConfig > controller_config
Tuning parameters used by this controller.
Definition: VehicleControllerInterface.h:37
Full kinematic state of the vehicle.
Definition: Types.h:63