Abstract interface for the vehicle-level controller.
More...
#include <VehicleControllerInterface.h>
Abstract interface for the vehicle-level controller.
A vehicle controller combines one or more BaseControllerInterface instances and participates in the trajectory lifecycle through callbacks invoked by the Vehicle state machine.
◆ VehicleControllerInterface()
Constructs a vehicle controller with shared dynamics and config.
- Parameters
-
| systemDynamics | [in] Shared vehicle dynamics model |
| controller_config | [in] Shared controller tuning parameters |
◆ ~VehicleControllerInterface()
| virtual VehicleControllerInterface::~VehicleControllerInterface |
( |
| ) |
|
|
virtualdefault |
◆ getBodyPoseError()
| virtual Vector6d VehicleControllerInterface::getBodyPoseError |
( |
| ) |
const |
|
pure virtual |
Returns the most recently computed 6DOF body-frame pose error.
- Returns
- 6-element pose error [Δx, Δy, Δz, Δroll, Δpitch, Δyaw]
Implemented in FfFbVehicleController.
◆ onStationkeepEntered()
| virtual void VehicleControllerInterface::onStationkeepEntered |
( |
| ) |
|
|
pure virtual |
◆ onTrajectoryFinished()
| virtual void VehicleControllerInterface::onTrajectoryFinished |
( |
| ) |
|
|
pure virtual |
◆ onTrajectoryProgress()
| virtual void VehicleControllerInterface::onTrajectoryProgress |
( |
double |
progress | ) |
|
|
pure virtual |
Called every control tick while a trajectory is executing.
- Parameters
-
| progress | [in] Fractional trajectory completion in [0, 1] |
Implemented in FfFbVehicleController.
◆ onTrajectoryStarting()
| virtual void VehicleControllerInterface::onTrajectoryStarting |
( |
| ) |
|
|
pure virtual |
◆ spinControllerOnce()
| virtual Vector6d VehicleControllerInterface::spinControllerOnce |
( |
const State & |
goal, |
|
|
const State & |
current, |
|
|
const bool |
saturatedOnYawXYAxis, |
|
|
const bool |
saturatedOnDepthRollPitchAxis, |
|
|
double |
dt |
|
) |
| |
|
pure virtual |
Computes the instantaneous 6DOF body force to drive the vehicle toward the goal state.
- Parameters
-
| goal | [in] Desired vehicle state |
| current | [in] Current vehicle state |
| saturatedOnYawXYAxis | [in] True when the X, Y, or Yaw thruster axes are saturated |
| saturatedOnDepthRollPitchAxis | [in] True when the Z, Roll, or Pitch thruster axes are saturated |
| dt | [in] Time step in seconds since the last call |
- Returns
- 6-element body force/torque vector [Fx, Fy, Fz, Tx, Ty, Tz] in N and Nm
Implemented in FfFbVehicleController.
◆ controller_config
Tuning parameters used by this controller.
◆ systemDynamics
Vehicle dynamics model used by this controller.
The documentation for this class was generated from the following file: