controls  3.0.0
VehicleControllerInterface.h
Go to the documentation of this file.
1 #ifndef CONTROLS_CONTROLLER_VEHICLE_CONTROLLER_INTERFACE_H
2 #define CONTROLS_CONTROLLER_VEHICLE_CONTROLLER_INTERFACE_H
3 
6 
7 #include <memory>
8 
10 
19 public:
26  VehicleControllerInterface(std::shared_ptr<SystemDynamicsBase> systemDynamics,
27  std::shared_ptr<ControllerConfig> controller_config)
29  }
30 
31  virtual ~VehicleControllerInterface() = default;
32 
34  std::shared_ptr<SystemDynamicsBase> systemDynamics;
35 
37  std::shared_ptr<ControllerConfig> controller_config;
38 
50  virtual Vector6d spinControllerOnce(const State& goal, const State& current, const bool saturatedOnYawXYAxis,
51  const bool saturatedOnDepthRollPitchAxis, double dt)
52  = 0;
53 
59  virtual Vector6d getBodyPoseError() const = 0;
60 
64  virtual void onTrajectoryStarting() = 0;
65 
69  virtual void onTrajectoryFinished() = 0;
70 
74  virtual void onStationkeepEntered() = 0;
75 
81  virtual void onTrajectoryProgress(double progress) = 0;
82 };
83 
84 #endif // CONTROLS_CONTROLLER_VEHICLE_CONTROLLER_INTERFACE_H
Eigen::Matrix< double, 6, 1 > Vector6d
Definition: Types.h:29
Abstract interface for the vehicle-level controller.
Definition: VehicleControllerInterface.h:18
virtual void onTrajectoryStarting()=0
Called by the Vehicle state machine just before a trajectory begins executing.
virtual void onStationkeepEntered()=0
Called by the Vehicle state machine when a stationkeep request is activated.
virtual Vector6d getBodyPoseError() const =0
Returns the most recently computed 6DOF body-frame pose error.
virtual void onTrajectoryFinished()=0
Called by the Vehicle state machine when a trajectory completes naturally.
virtual ~VehicleControllerInterface()=default
virtual Vector6d spinControllerOnce(const State &goal, const State &current, const bool saturatedOnYawXYAxis, const bool saturatedOnDepthRollPitchAxis, 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 onTrajectoryProgress(double progress)=0
Called every control tick while a trajectory is executing.
std::shared_ptr< SystemDynamicsBase > systemDynamics
Vehicle dynamics model used by this controller.
Definition: VehicleControllerInterface.h:34
VehicleControllerInterface(std::shared_ptr< SystemDynamicsBase > systemDynamics, std::shared_ptr< ControllerConfig > controller_config)
Constructs a vehicle controller with shared dynamics and config.
Definition: VehicleControllerInterface.h:26
Full kinematic state of the vehicle.
Definition: Types.h:63