Public Types | Public Member Functions | Protected Member Functions | Protected Attributes | Private Attributes | List of all members
vigir_step_control::StepControllerPlugin Class Referenceabstract

The StepControllerPlugin class provides the basic interface in order to handle robot-specific behavior. In order to integrate a new robot system, at least following methods have to be overloaded: initWalk: Initialize all variables and interfaces properly preProcess: Handles state maching by updating the feedback state properly executeStep: Sends step to low level walk algorithm using the provided interfaces by the robot infrastructure. More...

#include <step_controller_plugin.h>

Inheritance diagram for vigir_step_control::StepControllerPlugin:
Inheritance graph
[legend]

Public Types

typedef boost::shared_ptr< const StepControllerPluginConstPtr
 
typedef boost::shared_ptr< StepControllerPluginPtr
 

Public Member Functions

virtual bool executeStep (const msgs::Step &step)=0
 This method will be called when the next step should be added to execution pipeline. The call of this function should be triggered by the process(...) method when next_step_index_needed_ has been changed. More...
 
const msgs::ExecuteStepPlanFeedback & getFeedbackState () const
 Returns current feedback information provided by the plugin. More...
 
int getLastStepIndexSent () const
 Returns last step index which has been sent to walking engine. More...
 
int getNextStepIndexNeeded () const
 Returns next step index needed by the walking engine. More...
 
StepControllerState getState () const
 Get current state of execution. More...
 
virtual void initWalk ()=0
 This method is called when new step plan has been enqueued and previously the walk controller state was READY. This method must be override and set state to ACTIVE when everything has been set up successfully. More...
 
virtual void postProcess (const ros::TimerEvent &event)
 PostProcess Method is called after processing step, in order to sum up the current status and cleanups. More...
 
virtual void preProcess (const ros::TimerEvent &event)
 PreProcess Method is called before processing the walk controller, e.g. for precompute/update data or check walking engine status. For keeping the default behavior running, following variables has to be properly updated here: More...
 
virtual void process (const ros::TimerEvent &event)
 Overwrite to handle robot specific behavior. The default behavior behaves as followed: More...
 
virtual void setStepPlanMsgPlugin (vigir_footstep_planning::StepPlanMsgPlugin::Ptr plugin)
 Sets the StepPlanMsgPlugin to be used. More...
 
 StepControllerPlugin ()
 
virtual void stop ()
 Will be called when (soft) stop is requested and resets plugin. More...
 
void updateQueueFeedback ()
 Updates feedback information with internal state data. More...
 
virtual bool updateStepPlan (const msgs::StepPlan &step_plan)
 Merges given step plan to the current step queue of steps. Hereby, two cases have to considered: More...
 
virtual ~StepControllerPlugin ()
 

Protected Member Functions

virtual void reset ()
 Resets the plugin (called during construction and by stop()). The default implementation raises the READY flag. Overwrite this method if another behavior is desired. More...
 
void setFeedbackState (const msgs::ExecuteStepPlanFeedback &feedback)
 
void setLastStepIndexSent (int index)
 
void setNextStepIndexNeeded (int index)
 
void setState (StepControllerState state)
 

Protected Attributes

boost::shared_mutex plugin_mutex_
 
vigir_footstep_planning::StepPlanMsgPlugin::Ptr step_plan_msg_plugin_
 
StepQueue::Ptr step_queue_
 

Private Attributes

msgs::ExecuteStepPlanFeedback feedback_state_
 
int last_step_index_sent_
 
int next_step_index_needed_
 
StepControllerState state_
 

Detailed Description

The StepControllerPlugin class provides the basic interface in order to handle robot-specific behavior. In order to integrate a new robot system, at least following methods have to be overloaded: initWalk: Initialize all variables and interfaces properly preProcess: Handles state maching by updating the feedback state properly executeStep: Sends step to low level walk algorithm using the provided interfaces by the robot infrastructure.

Definition at line 68 of file step_controller_plugin.h.

Member Typedef Documentation

Definition at line 74 of file step_controller_plugin.h.

Definition at line 73 of file step_controller_plugin.h.

Constructor & Destructor Documentation

vigir_step_control::StepControllerPlugin::StepControllerPlugin ( )

Definition at line 21 of file step_controller_plugin.cpp.

vigir_step_control::StepControllerPlugin::~StepControllerPlugin ( )
virtual

Definition at line 30 of file step_controller_plugin.cpp.

Member Function Documentation

virtual bool vigir_step_control::StepControllerPlugin::executeStep ( const msgs::Step &  step)
pure virtual

This method will be called when the next step should be added to execution pipeline. The call of this function should be triggered by the process(...) method when next_step_index_needed_ has been changed.

Parameters
stepStep to be executed now

Implemented in vigir_step_control::StepControllerTestPlugin.

const msgs::ExecuteStepPlanFeedback & vigir_step_control::StepControllerPlugin::getFeedbackState ( ) const

Returns current feedback information provided by the plugin.

Returns
current feedback

Definition at line 62 of file step_controller_plugin.cpp.

int vigir_step_control::StepControllerPlugin::getLastStepIndexSent ( ) const

Returns last step index which has been sent to walking engine.

Returns
step index

Definition at line 56 of file step_controller_plugin.cpp.

int vigir_step_control::StepControllerPlugin::getNextStepIndexNeeded ( ) const

Returns next step index needed by the walking engine.

Returns
step index

Definition at line 50 of file step_controller_plugin.cpp.

StepControllerState vigir_step_control::StepControllerPlugin::getState ( ) const

Get current state of execution.

Returns
StepControllerState

Definition at line 44 of file step_controller_plugin.cpp.

virtual void vigir_step_control::StepControllerPlugin::initWalk ( )
pure virtual

This method is called when new step plan has been enqueued and previously the walk controller state was READY. This method must be override and set state to ACTIVE when everything has been set up successfully.

Implemented in vigir_step_control::StepControllerTestPlugin.

void vigir_step_control::StepControllerPlugin::postProcess ( const ros::TimerEvent event)
virtual

PostProcess Method is called after processing step, in order to sum up the current status and cleanups.

Definition at line 214 of file step_controller_plugin.cpp.

void vigir_step_control::StepControllerPlugin::preProcess ( const ros::TimerEvent event)
virtual

PreProcess Method is called before processing the walk controller, e.g. for precompute/update data or check walking engine status. For keeping the default behavior running, following variables has to be properly updated here:

  • feedback.first_changeable_step_index (or update it in postProcess(...) or executeStep(...) alternatively)
  • feedback.last_performed_step_index (or update it in postProcess(...) or executeStep(...) alternatively)
  • next_step_index_needed – Note: Don't forget to update header data of the feedback, when updating one of the mentioned values!
  • setState(FINISEHD) when execution of all steps were successfully completed
  • setState(FAILED) when an error has occured

Reimplemented in vigir_step_control::StepControllerTestPlugin.

Definition at line 152 of file step_controller_plugin.cpp.

void vigir_step_control::StepControllerPlugin::process ( const ros::TimerEvent event)
virtual

Overwrite to handle robot specific behavior. The default behavior behaves as followed:

  • For each step s in queue with index in (last_step_index_sent_; next_step_index_needed_] executeStep(s) will be called. Hereby, last_step_index_sent_ will be automatically updated.
  • Each step in [0; feedback.last_performed_step_index] will be removed from step queue

Definition at line 170 of file step_controller_plugin.cpp.

void vigir_step_control::StepControllerPlugin::reset ( )
protectedvirtual

Resets the plugin (called during construction and by stop()). The default implementation raises the READY flag. Overwrite this method if another behavior is desired.

Definition at line 68 of file step_controller_plugin.cpp.

void vigir_step_control::StepControllerPlugin::setFeedbackState ( const msgs::ExecuteStepPlanFeedback &  feedback)
protected

Definition at line 104 of file step_controller_plugin.cpp.

void vigir_step_control::StepControllerPlugin::setLastStepIndexSent ( int  index)
protected

Definition at line 98 of file step_controller_plugin.cpp.

void vigir_step_control::StepControllerPlugin::setNextStepIndexNeeded ( int  index)
protected

Definition at line 92 of file step_controller_plugin.cpp.

void vigir_step_control::StepControllerPlugin::setState ( StepControllerState  state)
protected

Definition at line 84 of file step_controller_plugin.cpp.

void vigir_step_control::StepControllerPlugin::setStepPlanMsgPlugin ( vigir_footstep_planning::StepPlanMsgPlugin::Ptr  plugin)
virtual

Sets the StepPlanMsgPlugin to be used.

Parameters
pluginPlugin of type StepPlanMsgPlugin

Definition at line 34 of file step_controller_plugin.cpp.

void vigir_step_control::StepControllerPlugin::stop ( )
virtual

Will be called when (soft) stop is requested and resets plugin.

Definition at line 229 of file step_controller_plugin.cpp.

void vigir_step_control::StepControllerPlugin::updateQueueFeedback ( )

Updates feedback information with internal state data.

Definition at line 110 of file step_controller_plugin.cpp.

bool vigir_step_control::StepControllerPlugin::updateStepPlan ( const msgs::StepPlan &  step_plan)
virtual

Merges given step plan to the current step queue of steps. Hereby, two cases have to considered:

  1. In case of an empty step queue (robot is standing) the step plan has to begin with step index 0.
  2. In case of an non-empty step queue (robot is walking) the first step of the step plan has to be identical with the corresponding step (=same step index) in the step queue. Be aware that already performed steps have been popped from step queue and therefore are not exisiting anymore. The default implementation resets the plugin previously when in FINISHED or FAILED state.
    Parameters
    step_planStep plan to be merged into step queue.
    Returns
    false if an error has occured

Definition at line 118 of file step_controller_plugin.cpp.

Member Data Documentation

msgs::ExecuteStepPlanFeedback vigir_step_control::StepControllerPlugin::feedback_state_
private

Definition at line 202 of file step_controller_plugin.h.

int vigir_step_control::StepControllerPlugin::last_step_index_sent_
private

Definition at line 199 of file step_controller_plugin.h.

int vigir_step_control::StepControllerPlugin::next_step_index_needed_
private

Definition at line 196 of file step_controller_plugin.h.

boost::shared_mutex vigir_step_control::StepControllerPlugin::plugin_mutex_
mutableprotected

Definition at line 189 of file step_controller_plugin.h.

StepControllerState vigir_step_control::StepControllerPlugin::state_
private

Definition at line 193 of file step_controller_plugin.h.

vigir_footstep_planning::StepPlanMsgPlugin::Ptr vigir_step_control::StepControllerPlugin::step_plan_msg_plugin_
protected

Definition at line 186 of file step_controller_plugin.h.

StepQueue::Ptr vigir_step_control::StepControllerPlugin::step_queue_
protected

Definition at line 184 of file step_controller_plugin.h.


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


vigir_step_control
Author(s): Alexander Stumpf
autogenerated on Mon Jun 10 2019 15:44:47