#include <step_controller.h>
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_ |
Definition at line 52 of file step_controller.h.
typedef boost::shared_ptr<const StepController> vigir_step_control::StepController::ConstPtr |
Definition at line 57 of file step_controller.h.
typedef boost::shared_ptr<StepController> vigir_step_control::StepController::Ptr |
Definition at line 56 of file step_controller.h.
nh | Nodehandle living in correct namespace for all services |
Definition at line 9 of file step_controller.cpp.
vigir_step_control::StepController::~StepController | ( | ) | [virtual] |
Definition at line 31 of file step_controller.cpp.
void vigir_step_control::StepController::executePreemptionAction | ( | ExecuteStepPlanActionServerPtr | as | ) | [protected] |
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.
Step | plan 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.
void vigir_step_control::StepController::executeStepPlanAction | ( | ExecuteStepPlanActionServerPtr | as | ) | [protected] |
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.
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. |
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.
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. |
Definition at line 48 of file step_controller.cpp.
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.
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] |
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.
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.
void vigir_step_control::StepController::update | ( | const ros::TimerEvent & | event = ros::TimerEvent() | ) |
Main update loop to be called in regular intervals.
Definition at line 80 of file step_controller.cpp.
boost::shared_mutex vigir_step_control::StepController::controller_mutex_ [protected] |
Definition at line 139 of file step_controller.h.
boost::shared_ptr<ExecuteStepPlanActionServer> vigir_step_control::StepController::execute_step_plan_as_ [protected] |
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.