#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 |
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 141 of file controller_template.hpp.
|
virtual |
Definition at line 318 of file controller_template.hpp.
|
protectedpure virtual |
Implementation of the actual control method.
|
privatevirtual |
Goal callback method.
Definition at line 266 of file controller_template.hpp.
|
virtual |
Indicates if the controller is active.
Implements generic_control_toolbox::ControllerBase.
Definition at line 199 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 241 of file controller_template.hpp.
|
protectedpure virtual |
Read goal data.
goal | The goal pointer from actionlib. |
|
privatevirtual |
Preempt callback method.
Definition at line 308 of file controller_template.hpp.
|
protectedpure virtual |
Reset the controller to a default state.
|
private |
Resets controller flags
Definition at line 226 of file controller_template.hpp.
|
virtual |
Allows resetting the internal controller state.
Implements generic_control_toolbox::ControllerBase.
Definition at line 212 of file controller_template.hpp.
|
private |
Method that manages the starting of the actionlib server of each cartesian controller.
Definition at line 325 of file controller_template.hpp.
|
virtual |
Wraps the control algorithm with actionlib-related management.
Implements generic_control_toolbox::ControllerBase.
Definition at line 152 of file controller_template.hpp.
|
private |
Definition at line 135 of file controller_template.hpp.
|
private |
Definition at line 131 of file controller_template.hpp.
|
protected |
Definition at line 105 of file controller_template.hpp.
|
private |
Definition at line 133 of file controller_template.hpp.
|
protected |
Definition at line 106 of file controller_template.hpp.
|
private |
Definition at line 135 of file controller_template.hpp.
|
private |
Definition at line 134 of file controller_template.hpp.
|
private |
Definition at line 132 of file controller_template.hpp.
|
protected |
Definition at line 107 of file controller_template.hpp.