Public Member Functions | Protected Member Functions | Protected Attributes | Private Member Functions | Private Attributes
generic_control_toolbox::ControllerTemplate< ActionClass, ActionGoal, ActionFeedback, ActionResult > Class Template Reference

#include <controller_template.hpp>

Inheritance diagram for generic_control_toolbox::ControllerTemplate< ActionClass, ActionGoal, ActionFeedback, ActionResult >:
Inheritance graph
[legend]

List of all members.

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 &current_state, const ros::Duration &dt)
virtual ~ControllerTemplate ()

Protected Member Functions

virtual sensor_msgs::JointState controlAlgorithm (const sensor_msgs::JointState &current_state, const ros::Duration &dt)=0
sensor_msgs::JointState lastState (const sensor_msgs::JointState &current)
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< BagManagerbag_manager_
bool has_state_
sensor_msgs::JointState last_state_
ros::NodeHandle nh_

Detailed Description

template<class ActionClass, class ActionGoal, class ActionFeedback, class ActionResult>
class generic_control_toolbox::ControllerTemplate< ActionClass, ActionGoal, ActionFeedback, ActionResult >

A controller interface which implements the SimpleActionServer actionlib protocol.

Definition at line 56 of file controller_template.hpp.


Constructor & Destructor Documentation

template<class ActionClass , class ActionGoal , class ActionFeedback , class ActionResult >
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.

template<class ActionClass , class ActionGoal , class ActionFeedback , class ActionResult >
generic_control_toolbox::ControllerTemplate< ActionClass, ActionGoal, ActionFeedback, ActionResult >::~ControllerTemplate ( ) [virtual]

Definition at line 318 of file controller_template.hpp.


Member Function Documentation

template<class ActionClass , class ActionGoal , class ActionFeedback , class ActionResult >
virtual sensor_msgs::JointState generic_control_toolbox::ControllerTemplate< ActionClass, ActionGoal, ActionFeedback, ActionResult >::controlAlgorithm ( const sensor_msgs::JointState &  current_state,
const ros::Duration dt 
) [protected, pure virtual]

Implementation of the actual control method.

template<class ActionClass , class ActionGoal , class ActionFeedback , class ActionResult >
bool generic_control_toolbox::ControllerTemplate< ActionClass, ActionGoal, ActionFeedback, ActionResult >::goalCB ( ) [private, virtual]

Goal callback method.

Definition at line 266 of file controller_template.hpp.

template<class ActionClass , class ActionGoal , class ActionFeedback , class ActionResult >
bool generic_control_toolbox::ControllerTemplate< ActionClass, ActionGoal, ActionFeedback, ActionResult >::isActive ( ) const [virtual]

Indicates if the controller is active.

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

Implements generic_control_toolbox::ControllerBase.

Definition at line 199 of file controller_template.hpp.

template<class ActionClass , class ActionGoal , class ActionFeedback , class ActionResult >
sensor_msgs::JointState generic_control_toolbox::ControllerTemplate< ActionClass, ActionGoal, ActionFeedback, ActionResult >::lastState ( const sensor_msgs::JointState &  current) [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).

Parameters:
currentThe current joint state.
Returns:
The last commanded joint state before the actionlib goal was preempted or completed.

Definition at line 241 of file controller_template.hpp.

template<class ActionClass , class ActionGoal , class ActionFeedback , class ActionResult >
virtual bool generic_control_toolbox::ControllerTemplate< ActionClass, ActionGoal, ActionFeedback, ActionResult >::parseGoal ( boost::shared_ptr< const ActionGoal >  goal) [protected, pure virtual]

Read goal data.

Parameters:
goalThe goal pointer from actionlib.
Returns:
True in case of success, false otherwise.
template<class ActionClass , class ActionGoal , class ActionFeedback , class ActionResult >
void generic_control_toolbox::ControllerTemplate< ActionClass, ActionGoal, ActionFeedback, ActionResult >::preemptCB ( ) [private, virtual]

Preempt callback method.

Definition at line 308 of file controller_template.hpp.

template<class ActionClass , class ActionGoal , class ActionFeedback , class ActionResult >
virtual void generic_control_toolbox::ControllerTemplate< ActionClass, ActionGoal, ActionFeedback, ActionResult >::resetController ( ) [protected, pure virtual]

Reset the controller to a default state.

template<class ActionClass , class ActionGoal , class ActionFeedback , class ActionResult >
void generic_control_toolbox::ControllerTemplate< ActionClass, ActionGoal, ActionFeedback, ActionResult >::resetFlags ( ) [private]

Resets controller flags

Definition at line 226 of file controller_template.hpp.

template<class ActionClass , class ActionGoal , class ActionFeedback , class ActionResult >
void generic_control_toolbox::ControllerTemplate< ActionClass, ActionGoal, ActionFeedback, ActionResult >::resetInternalState ( ) [virtual]

Allows resetting the internal controller state.

Implements generic_control_toolbox::ControllerBase.

Definition at line 212 of file controller_template.hpp.

template<class ActionClass , class ActionGoal , class ActionFeedback , class ActionResult >
void generic_control_toolbox::ControllerTemplate< ActionClass, ActionGoal, ActionFeedback, ActionResult >::startActionlib ( ) [private]

Method that manages the starting of the actionlib server of each cartesian controller.

Definition at line 325 of file controller_template.hpp.

template<class ActionClass , class ActionGoal , class ActionFeedback , class ActionResult >
sensor_msgs::JointState generic_control_toolbox::ControllerTemplate< ActionClass, ActionGoal, ActionFeedback, ActionResult >::updateControl ( const sensor_msgs::JointState &  current_state,
const ros::Duration dt 
) [virtual]

Wraps the control algorithm with actionlib-related management.

Implements generic_control_toolbox::ControllerBase.

Definition at line 152 of file controller_template.hpp.


Member Data Documentation

template<class ActionClass , class ActionGoal , class ActionFeedback , class ActionResult >
bool generic_control_toolbox::ControllerTemplate< ActionClass, ActionGoal, ActionFeedback, ActionResult >::acquired_goal_ [private]

Definition at line 135 of file controller_template.hpp.

template<class ActionClass , class ActionGoal , class ActionFeedback , class ActionResult >
std::string generic_control_toolbox::ControllerTemplate< ActionClass, ActionGoal, ActionFeedback, ActionResult >::action_name_ [private]

Definition at line 131 of file controller_template.hpp.

template<class ActionClass , class ActionGoal , class ActionFeedback , class ActionResult >
boost::shared_ptr<actionlib::SimpleActionServer<ActionClass> > generic_control_toolbox::ControllerTemplate< ActionClass, ActionGoal, ActionFeedback, ActionResult >::action_server_ [protected]

Definition at line 105 of file controller_template.hpp.

template<class ActionClass , class ActionGoal , class ActionFeedback , class ActionResult >
std::shared_ptr<BagManager> generic_control_toolbox::ControllerTemplate< ActionClass, ActionGoal, ActionFeedback, ActionResult >::bag_manager_ [private]

Definition at line 133 of file controller_template.hpp.

template<class ActionClass , class ActionGoal , class ActionFeedback , class ActionResult >
ActionFeedback generic_control_toolbox::ControllerTemplate< ActionClass, ActionGoal, ActionFeedback, ActionResult >::feedback_ [protected]

Definition at line 106 of file controller_template.hpp.

template<class ActionClass , class ActionGoal , class ActionFeedback , class ActionResult >
bool generic_control_toolbox::ControllerTemplate< ActionClass, ActionGoal, ActionFeedback, ActionResult >::has_state_ [private]

Definition at line 135 of file controller_template.hpp.

template<class ActionClass , class ActionGoal , class ActionFeedback , class ActionResult >
sensor_msgs::JointState generic_control_toolbox::ControllerTemplate< ActionClass, ActionGoal, ActionFeedback, ActionResult >::last_state_ [private]

Definition at line 134 of file controller_template.hpp.

template<class ActionClass , class ActionGoal , class ActionFeedback , class ActionResult >
ros::NodeHandle generic_control_toolbox::ControllerTemplate< ActionClass, ActionGoal, ActionFeedback, ActionResult >::nh_ [private]

Definition at line 132 of file controller_template.hpp.

template<class ActionClass , class ActionGoal , class ActionFeedback , class ActionResult >
ActionResult generic_control_toolbox::ControllerTemplate< ActionClass, ActionGoal, ActionFeedback, ActionResult >::result_ [protected]

Definition at line 107 of file controller_template.hpp.


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


generic_control_toolbox
Author(s): diogo
autogenerated on Thu Jun 6 2019 18:02:57