controls  3.0.0
Public Member Functions | Public Attributes | List of all members
VehicleControllerInterface Class Referenceabstract

Abstract interface for the vehicle-level controller. More...

#include <VehicleControllerInterface.h>

Inheritance diagram for VehicleControllerInterface:
FfFbVehicleController

Public Member Functions

 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
 
virtual 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)=0
 Computes the instantaneous 6DOF body force to drive the vehicle toward the goal state. More...
 
virtual Vector6d get_body_pose_error () const =0
 Returns the most recently computed 6DOF body-frame pose error. More...
 
virtual void on_trajectory_starting ()=0
 Called by the Vehicle state machine just before a trajectory begins executing. More...
 
virtual void on_trajectory_finished ()=0
 Called by the Vehicle state machine when a trajectory completes naturally. More...
 
virtual void on_stationkeep_entered ()=0
 Called by the Vehicle state machine when a stationkeep request is activated. More...
 
virtual void on_trajectory_progress (double progress)=0
 Called every control tick while a trajectory is executing. More...
 

Public Attributes

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

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.

Constructor & Destructor Documentation

◆ VehicleControllerInterface()

VehicleControllerInterface::VehicleControllerInterface ( std::shared_ptr< SystemDynamicsBase system_dynamics,
std::shared_ptr< ControllerConfig controller_config 
)
inline

Constructs a vehicle controller with shared dynamics and config.

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

◆ ~VehicleControllerInterface()

virtual VehicleControllerInterface::~VehicleControllerInterface ( )
virtualdefault

Member Function Documentation

◆ get_body_pose_error()

virtual Vector6d VehicleControllerInterface::get_body_pose_error ( ) 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.

◆ on_stationkeep_entered()

virtual void VehicleControllerInterface::on_stationkeep_entered ( )
pure virtual

Called by the Vehicle state machine when a stationkeep request is activated.

Implemented in FfFbVehicleController.

◆ on_trajectory_finished()

virtual void VehicleControllerInterface::on_trajectory_finished ( )
pure virtual

Called by the Vehicle state machine when a trajectory completes naturally.

Implemented in FfFbVehicleController.

◆ on_trajectory_progress()

virtual void VehicleControllerInterface::on_trajectory_progress ( 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.

◆ on_trajectory_starting()

virtual void VehicleControllerInterface::on_trajectory_starting ( )
pure virtual

Called by the Vehicle state machine just before a trajectory begins executing.

Implemented in FfFbVehicleController.

◆ spin_controller_once()

virtual Vector6d VehicleControllerInterface::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 
)
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
saturated_on_yaw_xy_axis[in] True when the X, Y, or Yaw thruster axes are saturated
saturated_on_depth_roll_pitch_axis[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.

Member Data Documentation

◆ controller_config_

std::shared_ptr<ControllerConfig> VehicleControllerInterface::controller_config_

Tuning parameters used by this controller.

◆ system_dynamics_

std::shared_ptr<SystemDynamicsBase> VehicleControllerInterface::system_dynamics_

Vehicle dynamics model used by this controller.


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