1 #ifndef CONTROLS_CONTROLLER_VEHICLE_CONTROLLER_INTERFACE_H
2 #define CONTROLS_CONTROLLER_VEHICLE_CONTROLLER_INTERFACE_H
27 std::shared_ptr<ControllerConfig> controller_config)
51 const bool saturated_on_depth_roll_pitch_axis,
double dt)
Eigen::Matrix< double, 6, 1 > Vector6d
Definition: Types.h:29
Abstract interface for the vehicle-level controller.
Definition: VehicleControllerInterface.h:18
virtual Vector6d spin_controller_once(const State &goal, const State ¤t, 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.
std::shared_ptr< ControllerConfig > controller_config_
Tuning parameters used by this controller.
Definition: VehicleControllerInterface.h:37
virtual void on_stationkeep_entered()=0
Called by the Vehicle state machine when a stationkeep request is activated.
virtual Vector6d get_body_pose_error() const =0
Returns the most recently computed 6DOF body-frame pose error.
VehicleControllerInterface(std::shared_ptr< SystemDynamicsBase > system_dynamics, std::shared_ptr< ControllerConfig > controller_config)
Constructs a vehicle controller with shared dynamics and config.
Definition: VehicleControllerInterface.h:26
virtual ~VehicleControllerInterface()=default
virtual void on_trajectory_progress(double progress)=0
Called every control tick while a trajectory is executing.
std::shared_ptr< SystemDynamicsBase > system_dynamics_
Vehicle dynamics model used by this controller.
Definition: VehicleControllerInterface.h:34
virtual void on_trajectory_finished()=0
Called by the Vehicle state machine when a trajectory completes naturally.
virtual void on_trajectory_starting()=0
Called by the Vehicle state machine just before a trajectory begins executing.
Full kinematic state of the vehicle.
Definition: Types.h:63