LCOV - code coverage report
Current view: top level - controller - VehicleControllerInterface.h Hit Total Coverage
Test: doc-coverage.info Lines: 8 9 88.9 %
Date: 2026-04-20 18:26:22

          Line data    Source code
       1             : #ifndef CONTROLS_CONTROLLER_VEHICLE_CONTROLLER_INTERFACE_H
       2             : #define CONTROLS_CONTROLLER_VEHICLE_CONTROLLER_INTERFACE_H
       3             : 
       4             : #include <controller/BaseControllerInterface.h>
       5             : #include <controller/ControllerConfig.h>
       6             : 
       7             : #include <memory>
       8             : 
       9             : #include "dynamics/SystemDynamicsBase.h"
      10             : 
      11             : /**
      12             :  * @brief Abstract interface for the vehicle-level controller
      13             :  *
      14             :  * A vehicle controller combines one or more BaseControllerInterface instances
      15             :  * and participates in the trajectory lifecycle through callbacks invoked by
      16             :  * the Vehicle state machine.
      17             :  */
      18           1 : class VehicleControllerInterface {
      19             : public:
      20             :     /**
      21             :      * @brief Constructs a vehicle controller with shared dynamics and config
      22             :      *
      23             :      * @param systemDynamics    [in] Shared vehicle dynamics model
      24             :      * @param controller_config [in] Shared controller tuning parameters
      25             :      */
      26           1 :     VehicleControllerInterface(std::shared_ptr<SystemDynamicsBase> systemDynamics,
      27             :                                std::shared_ptr<ControllerConfig> controller_config)
      28             :         : systemDynamics(std::move(systemDynamics)), controller_config(std::move(controller_config)) {
      29             :     }
      30             : 
      31           0 :     virtual ~VehicleControllerInterface() = default;
      32             : 
      33             :     /** @brief Vehicle dynamics model used by this controller */
      34             :     std::shared_ptr<SystemDynamicsBase> systemDynamics;
      35             : 
      36             :     /** @brief Tuning parameters used by this controller */
      37             :     std::shared_ptr<ControllerConfig> controller_config;
      38             : 
      39             :     /**
      40             :      * @brief Computes the instantaneous 6DOF body force to drive the vehicle toward the goal state
      41             :      *
      42             :      * @param goal                        [in] Desired vehicle state
      43             :      * @param current                     [in] Current vehicle state
      44             :      * @param saturatedOnYawXYAxis        [in] True when the X, Y, or Yaw thruster axes are saturated
      45             :      * @param saturatedOnDepthRollPitchAxis [in] True when the Z, Roll, or Pitch thruster axes are saturated
      46             :      * @param dt                          [in] Time step in seconds since the last call
      47             :      *
      48             :      * @return 6-element body force/torque vector [Fx, Fy, Fz, Tx, Ty, Tz] in N and Nm
      49             :      */
      50           1 :     virtual Vector6d spinControllerOnce(const State& goal, const State& current, const bool saturatedOnYawXYAxis,
      51             :                                         const bool saturatedOnDepthRollPitchAxis, double dt)
      52             :         = 0;
      53             : 
      54             :     /**
      55             :      * @brief Returns the most recently computed 6DOF body-frame pose error
      56             :      *
      57             :      * @return 6-element pose error [Δx, Δy, Δz, Δroll, Δpitch, Δyaw]
      58             :      */
      59           1 :     virtual Vector6d getBodyPoseError() const = 0;
      60             : 
      61             :     /**
      62             :      * @brief Called by the Vehicle state machine just before a trajectory begins executing
      63             :      */
      64           1 :     virtual void onTrajectoryStarting() = 0;
      65             : 
      66             :     /**
      67             :      * @brief Called by the Vehicle state machine when a trajectory completes naturally
      68             :      */
      69           1 :     virtual void onTrajectoryFinished() = 0;
      70             : 
      71             :     /**
      72             :      * @brief Called by the Vehicle state machine when a stationkeep request is activated
      73             :      */
      74           1 :     virtual void onStationkeepEntered() = 0;
      75             : 
      76             :     /**
      77             :      * @brief Called every control tick while a trajectory is executing
      78             :      *
      79             :      * @param progress [in] Fractional trajectory completion in [0, 1]
      80             :      */
      81           1 :     virtual void onTrajectoryProgress(double progress) = 0;
      82             : };
      83             : 
      84             : #endif  // CONTROLS_CONTROLLER_VEHICLE_CONTROLLER_INTERFACE_H

Generated by: LCOV version 1.14