Public Member Functions | List of all members
generic_control_toolbox::ControllerBase Class Referenceabstract

#include <controller_template.hpp>

Inheritance diagram for generic_control_toolbox::ControllerBase:
Inheritance graph
[legend]

Public Member Functions

 ControllerBase (ros::NodeHandle nh=ros::NodeHandle("~"))
 
virtual bool isActive () const =0
 
virtual void resetInternalState ()=0
 
virtual sensor_msgs::JointState updateControl (const sensor_msgs::JointState &current_state, const ros::Duration &dt)=0
 
virtual ~ControllerBase ()
 

Detailed Description

Defines the basic cartesian controller interface.

Definition at line 18 of file controller_template.hpp.

Constructor & Destructor Documentation

◆ ControllerBase()

generic_control_toolbox::ControllerBase::ControllerBase ( ros::NodeHandle  nh = ros::NodeHandle("~"))

Definition at line 5 of file controller_template.cpp.

◆ ~ControllerBase()

generic_control_toolbox::ControllerBase::~ControllerBase ( )
virtual

Definition at line 6 of file controller_template.cpp.

Member Function Documentation

◆ isActive()

virtual bool generic_control_toolbox::ControllerBase::isActive ( ) const
pure virtual

Indicates if the controller is active.

Returns
True if active, and the controller output is to be used, False otherwise.

Implemented in generic_control_toolbox::ControllerTemplate< ActionClass, ActionGoal, ActionFeedback, ActionResult >.

◆ resetInternalState()

virtual void generic_control_toolbox::ControllerBase::resetInternalState ( )
pure virtual

◆ updateControl()

virtual sensor_msgs::JointState generic_control_toolbox::ControllerBase::updateControl ( const sensor_msgs::JointState &  current_state,
const ros::Duration dt 
)
pure virtual

Method for computing the desired joint states given the control algorithm.

Parameters
current_stateCurrent joint states.
dtElapsed time since last control loop.
Returns
Desired joint states.

Implemented in generic_control_toolbox::ControllerTemplate< ActionClass, ActionGoal, ActionFeedback, ActionResult >.


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


generic_control_toolbox
Author(s): diogo
autogenerated on Mon Feb 28 2022 22:24:38