Public Types | Public Member Functions | Protected Member Functions | Protected Attributes
vigir_step_control::StepController Class Reference

#include <step_controller.h>

List of all members.

Public Types

typedef boost::shared_ptr
< const StepController
ConstPtr
typedef boost::shared_ptr
< StepController
Ptr

Public Member Functions

void executeStepPlan (const msgs::StepPlan &step_plan)
 Instruct the controller to execute the given step plan. If execution is already in progress, the step plan will be merged into current execution queue.
bool initialize (ros::NodeHandle &nh, bool auto_spin=true)
 Initializes step controller.
bool initialize (ros::NodeHandle &nh, StepControllerPlugin::Ptr step_controller_plugin, vigir_footstep_planning::StepPlanMsgPlugin::Ptr step_plan_msg_plugin, bool auto_spin=true)
 Initializes step controller.
template<typename T >
bool loadPlugin (const std::string &plugin_name, boost::shared_ptr< T > &plugin)
 Loads plugin with specific name to be used by the controller. The name should be configured in the plugin config file and loaded to the rosparam server. The call can only succeed when currentl no exection is runnning.
 StepController (ros::NodeHandle &nh)
 StepController.
void update (const ros::TimerEvent &event=ros::TimerEvent())
 Main update loop to be called in regular intervals.
virtual ~StepController ()

Protected Member Functions

void executePreemptionAction (ExecuteStepPlanActionServerPtr as)
void executeStepPlan (const msgs::StepPlanConstPtr &step_plan)
void executeStepPlanAction (ExecuteStepPlanActionServerPtr as)
void loadStepControllerPlugin (const std_msgs::StringConstPtr &plugin_name)
void loadStepPlanMsgPlugin (const std_msgs::StringConstPtr &plugin_name)
 ROS API.
void publishFeedback () const
 Publishes feedback messages of current state of execution.

Protected Attributes

boost::shared_mutex controller_mutex_
boost::shared_ptr
< ExecuteStepPlanActionServer
execute_step_plan_as_
ros::Subscriber execute_step_plan_sub_
ros::Publisher feedback_pub_
ros::Subscriber load_step_controller_plugin_sub_
ros::Subscriber load_step_plan_msg_plugin_sub_
StepControllerPlugin::Ptr step_controller_plugin_
vigir_footstep_planning::StepPlanMsgPlugin::Ptr step_plan_msg_plugin_
ros::Timer update_timer_

Detailed Description

Definition at line 52 of file step_controller.h.


Member Typedef Documentation

Definition at line 57 of file step_controller.h.

Definition at line 56 of file step_controller.h.


Constructor & Destructor Documentation

StepController.

Parameters:
nhNodehandle living in correct namespace for all services

Definition at line 9 of file step_controller.cpp.

Definition at line 31 of file step_controller.cpp.


Member Function Documentation

Definition at line 188 of file step_controller.cpp.

void vigir_step_control::StepController::executeStepPlan ( const msgs::StepPlan &  step_plan)

Instruct the controller to execute the given step plan. If execution is already in progress, the step plan will be merged into current execution queue.

Parameters:
Stepplan to be executed

Definition at line 63 of file step_controller.cpp.

void vigir_step_control::StepController::executeStepPlan ( const msgs::StepPlanConstPtr &  step_plan) [protected]

Definition at line 167 of file step_controller.cpp.

Definition at line 174 of file step_controller.cpp.

bool vigir_step_control::StepController::initialize ( ros::NodeHandle nh,
bool  auto_spin = true 
)

Initializes step controller.

Parameters:
nhNodehandle living in correct namespace for all parameters
auto_spinIf true, then the controller sets up it's own ros timer for calling update(...) continously.
Returns:
true, if initialization was successful

Definition at line 35 of file step_controller.cpp.

bool vigir_step_control::StepController::initialize ( ros::NodeHandle nh,
StepControllerPlugin::Ptr  step_controller_plugin,
vigir_footstep_planning::StepPlanMsgPlugin::Ptr  step_plan_msg_plugin,
bool  auto_spin = true 
)

Initializes step controller.

Parameters:
nhNodehandle living in correct namespace for all parameters
step_controller_pluginPlugin interfacing the H/W layer of the robot
step_plan_msg_pluginPlugin decoding the robot specific parameters from step msg
auto_spinIf true, then the controller sets up it's own ros timer for calling update(...) continously.
Returns:
true, if initialization was successful

Definition at line 48 of file step_controller.cpp.

template<typename T >
bool vigir_step_control::StepController::loadPlugin ( const std::string &  plugin_name,
boost::shared_ptr< T > &  plugin 
) [inline]

Loads plugin with specific name to be used by the controller. The name should be configured in the plugin config file and loaded to the rosparam server. The call can only succeed when currentl no exection is runnning.

Parameters:
plugin_nameName of plugin

Definition at line 91 of file step_controller.h.

void vigir_step_control::StepController::loadStepControllerPlugin ( const std_msgs::StringConstPtr &  plugin_name) [protected]

Definition at line 159 of file step_controller.cpp.

void vigir_step_control::StepController::loadStepPlanMsgPlugin ( const std_msgs::StringConstPtr &  plugin_name) [protected]

ROS API.

Definition at line 151 of file step_controller.cpp.

Publishes feedback messages of current state of execution.

Definition at line 135 of file step_controller.cpp.

Main update loop to be called in regular intervals.

Definition at line 80 of file step_controller.cpp.


Member Data Documentation

Definition at line 139 of file step_controller.h.

Definition at line 161 of file step_controller.h.

Definition at line 155 of file step_controller.h.

Definition at line 158 of file step_controller.h.

Definition at line 154 of file step_controller.h.

Definition at line 153 of file step_controller.h.

Definition at line 135 of file step_controller.h.

vigir_footstep_planning::StepPlanMsgPlugin::Ptr vigir_step_control::StepController::step_plan_msg_plugin_ [protected]

Definition at line 136 of file step_controller.h.

Definition at line 164 of file step_controller.h.


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


vigir_step_control
Author(s): Alexander Stumpf
autogenerated on Thu Jun 6 2019 21:13:33