#include <controller_template.hpp>

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 ¤t_state, const ros::Duration &dt)=0 |
| virtual | ~ControllerBase () |
Defines the basic cartesian controller interface.
Definition at line 18 of file controller_template.hpp.
| generic_control_toolbox::ControllerBase::ControllerBase | ( | ros::NodeHandle | nh = ros::NodeHandle("~") | ) |
Definition at line 5 of file controller_template.cpp.
| generic_control_toolbox::ControllerBase::~ControllerBase | ( | ) | [virtual] |
Definition at line 6 of file controller_template.cpp.
| virtual bool generic_control_toolbox::ControllerBase::isActive | ( | ) | const [pure virtual] |
Indicates if the controller is active.
Implemented in generic_control_toolbox::ControllerTemplate< ActionClass, ActionGoal, ActionFeedback, ActionResult >.
| virtual void generic_control_toolbox::ControllerBase::resetInternalState | ( | ) | [pure virtual] |
Allows resetting the internal controller state.
Implemented in generic_control_toolbox::ControllerTemplate< ActionClass, ActionGoal, ActionFeedback, ActionResult >.
| 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.
| current_state | Current joint states. |
| dt | Elapsed time since last control loop. |
Implemented in generic_control_toolbox::ControllerTemplate< ActionClass, ActionGoal, ActionFeedback, ActionResult >.