#include <global_footstep_planner_node.h>
Public Member Functions | |
GlobalFootstepPlannerNode (ros::NodeHandle &nh) | |
void | init (ros::NodeHandle &nh) |
virtual | ~GlobalFootstepPlannerNode () |
Protected Member Functions | |
void | editStep (const msgs::EditStepConstPtr &edit_step) |
void | editStepAction (SimpleActionServer< msgs::EditStepAction >::Ptr &as) |
bool | editStepService (msgs::EditStepService::Request &req, msgs::EditStepService::Response &resp) |
void | getStepPlanAction (SimpleActionServer< msgs::GetStepPlanAction >::Ptr &as) |
bool | getStepPlanService (msgs::GetStepPlanService::Request &req, msgs::GetStepPlanService::Response &resp) |
void | setStepPlan (const msgs::StepPlanConstPtr &step_plan) |
void | setStepPlanAction (SimpleActionServer< msgs::SetStepPlanAction >::Ptr &as) |
bool | setStepPlanService (msgs::SetStepPlanService::Request &req, msgs::SetStepPlanService::Response &resp) |
void | stitchStepPlan (const std::vector< msgs::StepPlan > &step_plans) |
void | stitchStepPlan (const msgs::StepPlanConstPtr &step_plan) |
void | stitchStepPlanAction (SimpleActionServer< msgs::StitchStepPlanAction >::Ptr &as) |
bool | stitchStepPlanService (msgs::StitchStepPlanService::Request &req, msgs::StitchStepPlanService::Response &resp) |
Protected Attributes | |
SimpleActionServer < msgs::EditStepAction >::Ptr | edit_step_as |
ros::ServiceServer | edit_step_srv |
ros::Subscriber | edit_step_sub |
SimpleActionServer < msgs::GetStepPlanAction > ::Ptr | get_step_plan_as |
ros::ServiceServer | get_step_plan_srv |
GlobalFootstepPlanner::Ptr | global_footstep_planner |
SimpleActionServer < msgs::SetStepPlanAction > ::Ptr | set_step_plan_as |
ros::ServiceServer | set_step_plan_srv |
ros::Subscriber | set_step_plan_sub |
SimpleActionServer < msgs::StitchStepPlanAction > ::Ptr | stitch_step_plan_as |
ros::ServiceServer | stitch_step_plan_srv |
ros::Subscriber | stitch_step_plan_sub |
Definition at line 44 of file global_footstep_planner_node.h.
vigir_footstep_planning::GlobalFootstepPlannerNode::GlobalFootstepPlannerNode | ( | ros::NodeHandle & | nh | ) |
Definition at line 5 of file global_footstep_planner_node.cpp.
Definition at line 10 of file global_footstep_planner_node.cpp.
void vigir_footstep_planning::GlobalFootstepPlannerNode::editStep | ( | const msgs::EditStepConstPtr & | edit_step | ) | [protected] |
Definition at line 42 of file global_footstep_planner_node.cpp.
void vigir_footstep_planning::GlobalFootstepPlannerNode::editStepAction | ( | SimpleActionServer< msgs::EditStepAction >::Ptr & | as | ) | [protected] |
Definition at line 125 of file global_footstep_planner_node.cpp.
bool vigir_footstep_planning::GlobalFootstepPlannerNode::editStepService | ( | msgs::EditStepService::Request & | req, |
msgs::EditStepService::Response & | resp | ||
) | [protected] |
Definition at line 86 of file global_footstep_planner_node.cpp.
void vigir_footstep_planning::GlobalFootstepPlannerNode::getStepPlanAction | ( | SimpleActionServer< msgs::GetStepPlanAction >::Ptr & | as | ) | [protected] |
Definition at line 164 of file global_footstep_planner_node.cpp.
bool vigir_footstep_planning::GlobalFootstepPlannerNode::getStepPlanService | ( | msgs::GetStepPlanService::Request & | req, |
msgs::GetStepPlanService::Response & | resp | ||
) | [protected] |
Definition at line 106 of file global_footstep_planner_node.cpp.
void vigir_footstep_planning::GlobalFootstepPlannerNode::init | ( | ros::NodeHandle & | nh | ) | [virtual] |
Reimplemented from vigir_footstep_planning::FootstepPlannerNode.
Definition at line 14 of file global_footstep_planner_node.cpp.
void vigir_footstep_planning::GlobalFootstepPlannerNode::setStepPlan | ( | const msgs::StepPlanConstPtr & | step_plan | ) | [protected] |
Definition at line 53 of file global_footstep_planner_node.cpp.
void vigir_footstep_planning::GlobalFootstepPlannerNode::setStepPlanAction | ( | SimpleActionServer< msgs::SetStepPlanAction >::Ptr & | as | ) | [protected] |
Definition at line 145 of file global_footstep_planner_node.cpp.
bool vigir_footstep_planning::GlobalFootstepPlannerNode::setStepPlanService | ( | msgs::SetStepPlanService::Request & | req, |
msgs::SetStepPlanService::Response & | resp | ||
) | [protected] |
Definition at line 96 of file global_footstep_planner_node.cpp.
void vigir_footstep_planning::GlobalFootstepPlannerNode::stitchStepPlan | ( | const std::vector< msgs::StepPlan > & | step_plans | ) | [protected] |
Definition at line 62 of file global_footstep_planner_node.cpp.
void vigir_footstep_planning::GlobalFootstepPlannerNode::stitchStepPlan | ( | const msgs::StepPlanConstPtr & | step_plan | ) | [protected] |
Definition at line 72 of file global_footstep_planner_node.cpp.
void vigir_footstep_planning::GlobalFootstepPlannerNode::stitchStepPlanAction | ( | SimpleActionServer< msgs::StitchStepPlanAction >::Ptr & | as | ) | [protected] |
Definition at line 180 of file global_footstep_planner_node.cpp.
bool vigir_footstep_planning::GlobalFootstepPlannerNode::stitchStepPlanService | ( | msgs::StitchStepPlanService::Request & | req, |
msgs::StitchStepPlanService::Response & | resp | ||
) | [protected] |
Definition at line 112 of file global_footstep_planner_node.cpp.
SimpleActionServer<msgs::EditStepAction>::Ptr vigir_footstep_planning::GlobalFootstepPlannerNode::edit_step_as [protected] |
Definition at line 84 of file global_footstep_planner_node.h.
Definition at line 78 of file global_footstep_planner_node.h.
Definition at line 73 of file global_footstep_planner_node.h.
SimpleActionServer<msgs::GetStepPlanAction>::Ptr vigir_footstep_planning::GlobalFootstepPlannerNode::get_step_plan_as [protected] |
Definition at line 86 of file global_footstep_planner_node.h.
ros::ServiceServer vigir_footstep_planning::GlobalFootstepPlannerNode::get_step_plan_srv [protected] |
Definition at line 80 of file global_footstep_planner_node.h.
GlobalFootstepPlanner::Ptr vigir_footstep_planning::GlobalFootstepPlannerNode::global_footstep_planner [protected] |
Definition at line 89 of file global_footstep_planner_node.h.
SimpleActionServer<msgs::SetStepPlanAction>::Ptr vigir_footstep_planning::GlobalFootstepPlannerNode::set_step_plan_as [protected] |
Definition at line 85 of file global_footstep_planner_node.h.
ros::ServiceServer vigir_footstep_planning::GlobalFootstepPlannerNode::set_step_plan_srv [protected] |
Definition at line 79 of file global_footstep_planner_node.h.
Definition at line 74 of file global_footstep_planner_node.h.
SimpleActionServer<msgs::StitchStepPlanAction>::Ptr vigir_footstep_planning::GlobalFootstepPlannerNode::stitch_step_plan_as [protected] |
Definition at line 87 of file global_footstep_planner_node.h.
ros::ServiceServer vigir_footstep_planning::GlobalFootstepPlannerNode::stitch_step_plan_srv [protected] |
Definition at line 81 of file global_footstep_planner_node.h.
ros::Subscriber vigir_footstep_planning::GlobalFootstepPlannerNode::stitch_step_plan_sub [protected] |
Definition at line 75 of file global_footstep_planner_node.h.