#include <step_controller.h>
Definition at line 52 of file step_controller.h.
vigir_step_control::StepController::~StepController |
( |
| ) |
|
|
virtual |
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
-
Definition at line 63 of file step_controller.cpp.
void vigir_step_control::StepController::executeStepPlan |
( |
const msgs::StepPlanConstPtr & |
step_plan | ) |
|
|
protected |
bool vigir_step_control::StepController::initialize |
( |
ros::NodeHandle & |
nh, |
|
|
bool |
auto_spin = true |
|
) |
| |
Initializes step controller.
- Parameters
-
nh | Nodehandle living in correct namespace for all parameters |
auto_spin | If 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
-
nh | Nodehandle living in correct namespace for all parameters |
step_controller_plugin | Plugin interfacing the H/W layer of the robot |
step_plan_msg_plugin | Plugin decoding the robot specific parameters from step msg |
auto_spin | If 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_name | Name of plugin |
Definition at line 91 of file step_controller.h.
void vigir_step_control::StepController::loadStepControllerPlugin |
( |
const std_msgs::StringConstPtr & |
plugin_name | ) |
|
|
protected |
void vigir_step_control::StepController::loadStepPlanMsgPlugin |
( |
const std_msgs::StringConstPtr & |
plugin_name | ) |
|
|
protected |
void vigir_step_control::StepController::publishFeedback |
( |
| ) |
const |
|
protected |
Publishes feedback messages of current state of execution.
Definition at line 135 of file step_controller.cpp.
boost::shared_mutex vigir_step_control::StepController::controller_mutex_ |
|
protected |
ros::Subscriber vigir_step_control::StepController::load_step_controller_plugin_sub_ |
|
protected |
ros::Subscriber vigir_step_control::StepController::load_step_plan_msg_plugin_sub_ |
|
protected |
vigir_footstep_planning::StepPlanMsgPlugin::Ptr vigir_step_control::StepController::step_plan_msg_plugin_ |
|
protected |
ros::Timer vigir_step_control::StepController::update_timer_ |
|
protected |
The documentation for this class was generated from the following files: