#include <controller_template.hpp>
Public Member Functions | |
ControllerTemplate (const std::string &action_name, ros::NodeHandle nh=ros::NodeHandle("~")) | |
virtual bool | isActive () const |
virtual void | resetInternalState () |
virtual sensor_msgs::JointState | updateControl (const sensor_msgs::JointState ¤t_state, const ros::Duration &dt) |
virtual | ~ControllerTemplate () |
Public Member Functions inherited from generic_control_toolbox::ControllerBase | |
ControllerBase (ros::NodeHandle nh=ros::NodeHandle("~")) | |
virtual | ~ControllerBase () |
Protected Member Functions | |
virtual sensor_msgs::JointState | controlAlgorithm (const sensor_msgs::JointState ¤t_state, const ros::Duration &dt)=0 |
virtual bool | customDefaultBehavior () |
sensor_msgs::JointState | lastState (const sensor_msgs::JointState ¤t) |
virtual bool | parseGoal (boost::shared_ptr< const ActionGoal > goal)=0 |
virtual void | resetController ()=0 |
Protected Attributes | |
boost::shared_ptr< actionlib::SimpleActionServer< ActionClass > > | action_server_ |
ActionFeedback | feedback_ |
ActionResult | result_ |
Private Member Functions | |
virtual bool | goalCB () |
virtual void | preemptCB () |
void | resetFlags () |
void | startActionlib () |
Private Attributes | |
bool | acquired_goal_ |
std::string | action_name_ |
std::shared_ptr< BagManager > | bag_manager_ |
bool | has_state_ |
sensor_msgs::JointState | last_state_ |
ros::NodeHandle | nh_ |
A controller interface which implements the SimpleActionServer actionlib protocol.
Definition at line 56 of file controller_template.hpp.
generic_control_toolbox::ControllerTemplate< ActionClass, ActionGoal, ActionFeedback, ActionResult >::ControllerTemplate | ( | const std::string & | action_name, |
ros::NodeHandle | nh = ros::NodeHandle("~") |
||
) |
Definition at line 151 of file controller_template.hpp.
|
virtual |
Definition at line 343 of file controller_template.hpp.
|
protectedpure virtual |
Implementation of the actual control method.
|
inlineprotectedvirtual |
Overload and set to true if you want the control algorithm to be called when there is no active goal. Do this when you want a custom behavior when the controller is iddle, as opposed to returning lastState.
returns | False, meaning the controller will return lastState when no active goal exists. True, if the controlAlgorithm is to be called instead. |
Definition at line 102 of file controller_template.hpp.
|
privatevirtual |
Goal callback method.
Definition at line 290 of file controller_template.hpp.
|
virtual |
Indicates if the controller is active.
Implements generic_control_toolbox::ControllerBase.
Definition at line 223 of file controller_template.hpp.
|
protected |
Return the last controlled joint state. If the controller does not have an active actionlib goal, it will set the references of the joint controller to the last desired position (and null velocity).
current | The current joint state. |
Definition at line 265 of file controller_template.hpp.
|
protectedpure virtual |
Read goal data.
goal | The goal pointer from actionlib. |
|
privatevirtual |
Preempt callback method.
Definition at line 333 of file controller_template.hpp.
|
protectedpure virtual |
Reset the controller to a default state.
|
private |
Resets controller flags
Definition at line 250 of file controller_template.hpp.
|
virtual |
Allows resetting the internal controller state.
Implements generic_control_toolbox::ControllerBase.
Definition at line 236 of file controller_template.hpp.
|
private |
Method that manages the starting of the actionlib server of each cartesian controller.
Definition at line 351 of file controller_template.hpp.
|
virtual |
Wraps the control algorithm with actionlib-related management.
Implements generic_control_toolbox::ControllerBase.
Definition at line 162 of file controller_template.hpp.
|
private |
Definition at line 145 of file controller_template.hpp.
|
private |
Definition at line 141 of file controller_template.hpp.
|
protected |
Definition at line 115 of file controller_template.hpp.
|
private |
Definition at line 143 of file controller_template.hpp.
|
protected |
Definition at line 116 of file controller_template.hpp.
|
private |
Definition at line 145 of file controller_template.hpp.
|
private |
Definition at line 144 of file controller_template.hpp.
|
private |
Definition at line 142 of file controller_template.hpp.
|
protected |
Definition at line 117 of file controller_template.hpp.