Public Member Functions | Protected Member Functions | Protected Attributes | Private Member Functions | Private Attributes | List of all members
generic_control_toolbox::ControllerTemplate< ActionClass, ActionGoal, ActionFeedback, ActionResult > Class Template Referenceabstract

#include <controller_template.hpp>

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

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 ()
 
- 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 &current_state, const ros::Duration &dt)=0
 
virtual bool customDefaultBehavior ()
 
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

◆ ControllerTemplate()

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 151 of file controller_template.hpp.

◆ ~ControllerTemplate()

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

Definition at line 343 of file controller_template.hpp.

Member Function Documentation

◆ controlAlgorithm()

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 
)
protectedpure virtual

Implementation of the actual control method.

◆ customDefaultBehavior()

template<class ActionClass , class ActionGoal , class ActionFeedback , class ActionResult >
virtual bool generic_control_toolbox::ControllerTemplate< ActionClass, ActionGoal, ActionFeedback, ActionResult >::customDefaultBehavior ( )
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.

Parameters
returnsFalse, 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.

◆ goalCB()

template<class ActionClass , class ActionGoal , class ActionFeedback , class ActionResult >
bool generic_control_toolbox::ControllerTemplate< ActionClass, ActionGoal, ActionFeedback, ActionResult >::goalCB ( )
privatevirtual

Goal callback method.

Definition at line 290 of file controller_template.hpp.

◆ isActive()

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 223 of file controller_template.hpp.

◆ lastState()

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 265 of file controller_template.hpp.

◆ parseGoal()

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)
protectedpure virtual

Read goal data.

Parameters
goalThe goal pointer from actionlib.
Returns
True in case of success, false otherwise.

◆ preemptCB()

template<class ActionClass , class ActionGoal , class ActionFeedback , class ActionResult >
void generic_control_toolbox::ControllerTemplate< ActionClass, ActionGoal, ActionFeedback, ActionResult >::preemptCB ( )
privatevirtual

Preempt callback method.

Definition at line 333 of file controller_template.hpp.

◆ resetController()

template<class ActionClass , class ActionGoal , class ActionFeedback , class ActionResult >
virtual void generic_control_toolbox::ControllerTemplate< ActionClass, ActionGoal, ActionFeedback, ActionResult >::resetController ( )
protectedpure virtual

Reset the controller to a default state.

◆ resetFlags()

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 250 of file controller_template.hpp.

◆ resetInternalState()

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 236 of file controller_template.hpp.

◆ startActionlib()

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 351 of file controller_template.hpp.

◆ updateControl()

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 162 of file controller_template.hpp.

Member Data Documentation

◆ acquired_goal_

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

Definition at line 145 of file controller_template.hpp.

◆ action_name_

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 141 of file controller_template.hpp.

◆ action_server_

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 115 of file controller_template.hpp.

◆ bag_manager_

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 143 of file controller_template.hpp.

◆ feedback_

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

Definition at line 116 of file controller_template.hpp.

◆ has_state_

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

Definition at line 145 of file controller_template.hpp.

◆ last_state_

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 144 of file controller_template.hpp.

◆ nh_

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

Definition at line 142 of file controller_template.hpp.

◆ result_

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

Definition at line 117 of file controller_template.hpp.


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


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