controls  3.0.0
Public Member Functions | List of all members
FeedforwardController Class Reference

Controller that computes open-loop forces via inverse dynamics. More...

#include <FeedforwardController.h>

Inheritance diagram for FeedforwardController:
BaseControllerInterface

Public Member Functions

Vector6d getForce (const State &goal, const State &curr, double dt) override
 Computes the feed-forward force from the goal state's acceleration and velocity. More...
 
 BaseControllerInterface ()=default
 
 BaseControllerInterface (std::shared_ptr< SystemDynamicsBase > auv, std::shared_ptr< ControllerConfig > config)
 Constructs a controller with the given dynamics model and config. More...
 
- Public Member Functions inherited from BaseControllerInterface
 BaseControllerInterface ()=default
 
 BaseControllerInterface (std::shared_ptr< SystemDynamicsBase > auv, std::shared_ptr< ControllerConfig > config)
 Constructs a controller with the given dynamics model and config. More...
 
virtual ~BaseControllerInterface ()=default
 
virtual void reset ()
 Resets any internal state (e.g., integrator terms) More...
 

Additional Inherited Members

- Protected Attributes inherited from BaseControllerInterface
std::shared_ptr< SystemDynamicsBaseauv_
 Vehicle dynamics model shared with all controllers in a stack. More...
 
std::shared_ptr< ControllerConfigconfig_
 Tuning parameters shared with all controllers in a stack. More...
 

Detailed Description

Controller that computes open-loop forces via inverse dynamics.

Uses the vehicle dynamics model to evaluate M·a + C(v)·v + D(v)·v, producing a force that cancels inertial, Coriolis, and damping effects for the desired trajectory state. Returns zero near the surface when surface gain scheduling is enabled.

Member Function Documentation

◆ BaseControllerInterface() [1/2]

BaseControllerInterface::BaseControllerInterface
default

◆ BaseControllerInterface() [2/2]

BaseControllerInterface::BaseControllerInterface
inline

Constructs a controller with the given dynamics model and config.

Parameters
auv[in] Shared vehicle dynamics model
config[in] Shared controller tuning parameters

◆ getForce()

Vector6d FeedforwardController::getForce ( const State goal,
const State curr,
double  dt 
)
overridevirtual

Computes the feed-forward force from the goal state's acceleration and velocity.

Parameters
goal[in] Desired vehicle state (acceleration and twist are used)
curr[in] Current vehicle state (used only for surface-depth check)
dt[in] Time step in seconds (unused by this controller)
Returns
6-element inverse-dynamics force vector, or zero if the result explodes

Implements BaseControllerInterface.


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