Class ControllerBase

Class Documentation

class ControllerBase

Base class for controller plugins loaded by ControllerManager.

Plugins inherit from this class and implement the pure-virtual hooks. The base owns the per-tick state cache, hover latch and essential-parameter tracking so plugins only deal with controller-specific logic.

Public Functions

ControllerBase() = default
virtual ~ControllerBase() = default
ControllerBase(const ControllerBase&) = delete
ControllerBase &operator=(const ControllerBase&) = delete
inline void initialize(as2::Node *node_ptr)

Initialize the plugin.

Called by ControllerManager after the per-plugin setters have been configured. Declares frame parameters, runs ownInitialize() and seeds the pending-essentials set from getEssentialParameters().

Parameters:

node_ptr – Non-owning pointer to the controller node.

inline void setTfHandler(as2::tf::TfHandler *tf_handler)

Inject the TfHandler owned by ControllerManager.

Parameters:

tf_handler – Non-owning pointer to the TfHandler instance.

inline void setBaseLinkFrameId(const std::string &frame_id)

Set the namespaced FLU (base_link) frame id used by the controller node.

Parameters:

frame_id – Fully-qualified base_link frame id.

inline void setPluginParamNamespace(const std::string &ns)

Set the per-plugin parameter namespace (e.g. “pid_speed_controller”).

Plugins compose their parameter names with param(“foo”) which returns “<namespace>.foo”.

Parameters:

ns – Plugin parameter namespace.

inline void requestHoverLatch()

Request that the next state update synthesizes a hover reference.

Called by ControllerHandler after a successful setMode(HOVER).

inline void setDesiredPoseFrameId(const std::string &frame_id)

Override the pose frame id used by the controller for state and references.

Typically called from setMode() to react to the active control mode.

Parameters:

frame_id – Fully-qualified pose frame id.

inline void setDesiredTwistFrameId(const std::string &frame_id)

Override the twist frame id used by the controller for state and references.

See setDesiredPoseFrameId().

Parameters:

frame_id – Fully-qualified twist frame id.

inline std::string getDesiredPoseFrameId() const

Frame id (already namespaced) that the plugin expects for pose state and references.

inline std::string getDesiredTwistFrameId() const

Frame id (already namespaced) that the plugin expects for twist state and references.

inline bool essentialParamsReady() const

Whether all essential parameters have been received and applied.

Consulted by ControllerHandler before accepting setMode.

inline void dispatchParameters(const std::vector<rclcpp::Parameter> &batch)

Filter a parameter batch by the plugin namespace and dispatch each match to updateParameter().

Tracks the essential names still pending and, the first time the set empties, flips essential_params_ready_ and calls onAllParametersRead() exactly once. Invoked by ControllerManager with the initial bulk and by ControllerHandler::parametersCallback for runtime changes. The pending set is populated at the end of initialize() from getEssentialParameters() so plugins do not need to manage this state themselves.

Parameters:

batch – Parameter batch from rclcpp.

inline void updateState(const geometry_msgs::msg::PoseStamped &pose_msg, const geometry_msgs::msg::TwistStamped &twist_msg)

Update the latest state (pose + twist) seen by the controller.

Validates that the incoming frames match the desired ones, caches the state, consumes a pending hover latch (if any) and forwards the state to onUpdateState().

Parameters:
  • pose_msg – Latest pose message received by the controller node.

  • twist_msg – Latest twist message received by the controller node.

inline void updateReference(const geometry_msgs::msg::PoseStamped &ref)

Update the pose reference.

Parameters:

ref – Latest pose reference message received by the controller node.

inline void updateReference(const geometry_msgs::msg::TwistStamped &ref)

Update the twist reference.

Parameters:

ref – Latest twist reference message received by the controller node.

inline void updateReference(const as2_msgs::msg::TrajectorySetpoints &ref)

Update the trajectory reference.

Parameters:

ref – Latest trajectory reference message received by the controller node.

inline void updateReference(const as2_msgs::msg::Thrust &ref)

Update the thrust reference.

Parameters:

ref – Latest thrust reference message received by the controller node.

inline virtual void ownInitialize()

Plugin-specific initialization, called from initialize().

virtual void onUpdateState(const geometry_msgs::msg::PoseStamped &pose_msg, const geometry_msgs::msg::TwistStamped &twist_msg) = 0

Plugin hook called by the base after frame validation and hover latch.

The plugin updates its internal state/integrators here.

Parameters:
  • pose_msg – Latest validated pose message.

  • twist_msg – Latest validated twist message.

inline virtual void onUpdateReference(const geometry_msgs::msg::PoseStamped&)

Plugin hook for pose reference. Default: no-op.

Parameters:

ref – Latest pose reference message.

inline virtual void onUpdateReference(const geometry_msgs::msg::TwistStamped&)

Plugin hook for twist reference. Default: no-op.

Parameters:

ref – Latest twist reference message.

inline virtual void onUpdateReference(const as2_msgs::msg::TrajectorySetpoints&)

Plugin hook for trajectory reference. Default: no-op.

Parameters:

ref – Latest trajectory reference message.

inline virtual void onUpdateReference(const as2_msgs::msg::Thrust&)

Plugin hook for thrust reference. Default: no-op.

Parameters:

ref – Latest thrust reference message.

virtual bool computeOutput(double dt, geometry_msgs::msg::PoseStamped &pose, geometry_msgs::msg::TwistStamped &twist, as2_msgs::msg::Thrust &thrust) = 0

Compute the output signal of the controller plugin.

Parameters:
  • dt – Time elapsed since the last call to computeOutput().

  • pose – Output pose; frame depends on the output control mode.

  • twist – Output twist; frame depends on the output control mode.

  • thrust – Output thrust.

Returns:

true if the output is valid.

virtual bool setMode(const as2_msgs::msg::ControlMode &mode_in, const as2_msgs::msg::ControlMode &mode_out) = 0

Update the control mode to be used by the controller plugin.

Parameters:
  • mode_in – Input control mode requested.

  • mode_out – Output control mode requested.

Returns:

true if the in-out control mode configuration is valid.

virtual std::vector<std::string> getEssentialParameters() const = 0

Names of the parameters whose presence is required before the plugin can accept setMode.

Names must be already namespaced with <plugin_name>.. The manager tracks reception of these names and invokes onAllParametersRead() once the last one arrives.

Returns:

Vector of fully-qualified essential parameter names.

virtual void updateParameter(const rclcpp::Parameter &parameter) = 0

Apply a single parameter to the plugin.

Called by the manager for every parameter (essential or not) with a name starting with <plugin_name>., both at startup and on runtime changes. The plugin can read essentialParamsReady() to decide whether to apply at runtime or defer the configuration to onAllParametersRead().

Parameters:

parameter – Parameter to apply.

inline virtual void onAllParametersRead()

Hook fired once when every essential parameter has been delivered.

The latch essentialParamsReady() is already true on entry. Plugins use this hook to perform first-time configuration of the underlying solver/controller from the now-fully-populated parameter set.

inline virtual void reset()

Reset the controller.

Default implementation clears the per-mode flags maintained by the base. Plugins should override and call ControllerBase::reset() so the base state is also cleared. essential_params_ready_ is intentionally NOT cleared here; it is a monotonic latch — parameters are read once at startup via the rclcpp parameter callback, and reset() runs on every successful setMode and would otherwise leave the latch permanently false, rejecting all subsequent mode transitions.

inline virtual void latchHoverReference(const geometry_msgs::msg::PoseStamped &pose, const geometry_msgs::msg::TwistStamped&)

Default hover latch: synthesize a single-point trajectory at the cached state.

Override in plugins that do not consume trajectory references; in that case feed the hover via updateReference(pose) / updateReference(twist) with twist set to zero.

Parameters:
  • pose – Cached state pose used as the hover anchor.

  • twist – Cached state twist (unused by the default).

inline bool isReferenceReceived() const

Whether at least one motion reference has been received.

Protected Functions

inline void setReferenceReceived(bool value)

Mark the reference as received.

Parameters:

value – Value to set for reference_received_.

inline as2::Node *getNodePtr() const

Non-owning pointer to the controller node.

inline as2::tf::TfHandler *getTfHandler() const

TfHandler owned by ControllerManager.

May be null until the manager injects it; access from ownInitialize() or later.

inline const std::string &getBaseLinkFrameId() const

Namespaced frame id of the body FLU/base_link frame.

inline const std::string &getPluginParamNamespace() const

Per-plugin parameter namespace (e.g. “pid_speed_controller”).

inline std::string param(const std::string &tail) const

Compose a fully-qualified parameter name under the plugin namespace.

Parameters:

tail – Trailing parameter name to append to the plugin namespace.

Returns:

Fully-qualified parameter name.

inline const geometry_msgs::msg::PoseStamped &getStatePose() const

Last validated state pose cached by the base.

inline const geometry_msgs::msg::TwistStamped &getStateTwist() const

Last validated state twist cached by the base.

inline bool isStateReceived() const

Whether at least one state message has been received and validated.

inline bool isHoverPending() const

Whether a hover latch is pending consumption on the next state update.