Public Types | Public Member Functions | Protected Attributes | List of all members
vigir_step_control::StepControllerTestPlugin Class Reference

#include <step_controller_test_plugin.h>

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

Public Types

typedef boost::shared_ptr< const StepControllerTestPluginConstPtr
 
typedef boost::shared_ptr< StepControllerTestPluginPtr
 
- Public Types inherited from vigir_step_control::StepControllerPlugin
typedef boost::shared_ptr< const StepControllerPluginConstPtr
 
typedef boost::shared_ptr< StepControllerPluginPtr
 

Public Member Functions

bool executeStep (const msgs::Step &step) override
 Handles fake execution of step. In fact it does nothing as accepting the step. More...
 
void initWalk () override
 We have to initialize all variables at beginning of new step plan execution here. More...
 
void preProcess (const ros::TimerEvent &event) override
 Simulates handling of walking engine and triggers in regular interval a succesful execution of a step. More...
 
 StepControllerTestPlugin ()
 
virtual ~StepControllerTestPlugin ()
 
- Public Member Functions inherited from vigir_step_control::StepControllerPlugin
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 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 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 Attributes

ros::Time next_step_needed_time_
 
- Protected Attributes inherited from vigir_step_control::StepControllerPlugin
boost::shared_mutex plugin_mutex_
 
vigir_footstep_planning::StepPlanMsgPlugin::Ptr step_plan_msg_plugin_
 
StepQueue::Ptr step_queue_
 

Additional Inherited Members

- Protected Member Functions inherited from vigir_step_control::StepControllerPlugin
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)
 

Detailed Description

Definition at line 42 of file step_controller_test_plugin.h.

Member Typedef Documentation

Definition at line 48 of file step_controller_test_plugin.h.

Definition at line 47 of file step_controller_test_plugin.h.

Constructor & Destructor Documentation

vigir_step_control::StepControllerTestPlugin::StepControllerTestPlugin ( )

Definition at line 7 of file step_controller_test_plugin.cpp.

vigir_step_control::StepControllerTestPlugin::~StepControllerTestPlugin ( )
virtual

Definition at line 12 of file step_controller_test_plugin.cpp.

Member Function Documentation

bool vigir_step_control::StepControllerTestPlugin::executeStep ( const msgs::Step &  step)
overridevirtual

Handles fake execution of step. In fact it does nothing as accepting the step.

Parameters
Stepto be executed
Returns
Returns always true for demonstration

Implements vigir_step_control::StepControllerPlugin.

Definition at line 74 of file step_controller_test_plugin.cpp.

void vigir_step_control::StepControllerTestPlugin::initWalk ( )
overridevirtual

We have to initialize all variables at beginning of new step plan execution here.

Implements vigir_step_control::StepControllerPlugin.

Definition at line 16 of file step_controller_test_plugin.cpp.

void vigir_step_control::StepControllerTestPlugin::preProcess ( const ros::TimerEvent event)
overridevirtual

Simulates handling of walking engine and triggers in regular interval a succesful execution of a step.

Reimplemented from vigir_step_control::StepControllerPlugin.

Definition at line 33 of file step_controller_test_plugin.cpp.

Member Data Documentation

ros::Time vigir_step_control::StepControllerTestPlugin::next_step_needed_time_
protected

Definition at line 74 of file step_controller_test_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