#include <planner_action.h>

| Public Types | |
| typedef boost::shared_ptr< PlannerAction > | Ptr | 
|  Public Types inherited from mbf_abstract_nav::AbstractAction< mbf_msgs::GetPathAction, AbstractPlannerExecution > | |
| typedef actionlib::ActionServer< mbf_msgs::GetPathAction >::GoalHandle | GoalHandle | 
| typedef boost::shared_ptr< AbstractAction > | Ptr | 
| typedef boost::function< void(GoalHandle &goal_handle, AbstractPlannerExecution &execution)> | RunMethod | 
| Public Member Functions | |
| PlannerAction (const std::string &name, const RobotInformation &robot_info) | |
| void | run (GoalHandle &goal_handle, AbstractPlannerExecution &execution) | 
|  Public Member Functions inherited from mbf_abstract_nav::AbstractAction< mbf_msgs::GetPathAction, AbstractPlannerExecution > | |
| AbstractAction (const std::string &name, const RobotInformation &robot_info, const RunMethod run_method) | |
| virtual void | cancel (GoalHandle &goal_handle) | 
| virtual void | cancelAll () | 
| virtual void | reconfigureAll (mbf_abstract_nav::MoveBaseFlexConfig &config, uint32_t level) | 
| virtual void | runAndCleanUp (GoalHandle &goal_handle, typename AbstractPlannerExecution::Ptr execution_ptr) | 
| virtual void | start (GoalHandle &goal_handle, typename AbstractPlannerExecution::Ptr execution_ptr) | 
| Protected Member Functions | |
| bool | transformPlanToGlobalFrame (std::vector< geometry_msgs::PoseStamped > &plan, std::vector< geometry_msgs::PoseStamped > &global_plan) | 
| Transforms a plan to the global frame (global_frame_) coord system.  More... | |
| Private Attributes | |
| ros::Publisher | current_goal_pub_ | 
| Publisher to publish the current goal pose, which is used for path planning.  More... | |
| unsigned int | path_seq_count_ | 
| Path sequence counter.  More... | |
| Additional Inherited Members | |
|  Protected Attributes inherited from mbf_abstract_nav::AbstractAction< mbf_msgs::GetPathAction, AbstractPlannerExecution > | |
| std::map< uint8_t, ConcurrencySlot > | concurrency_slots_ | 
| const std::string & | name_ | 
| const RobotInformation & | robot_info_ | 
| RunMethod | run_ | 
| boost::mutex | slot_map_mtx_ | 
| boost::thread_group | threads_ | 
Definition at line 53 of file planner_action.h.
Definition at line 57 of file planner_action.h.
| mbf_abstract_nav::PlannerAction::PlannerAction | ( | const std::string & | name, | 
| const RobotInformation & | robot_info | ||
| ) | 
Definition at line 47 of file planner_action.cpp.
| void mbf_abstract_nav::PlannerAction::run | ( | GoalHandle & | goal_handle, | 
| AbstractPlannerExecution & | execution | ||
| ) | 
Definition at line 57 of file planner_action.cpp.
| 
 | protected | 
Transforms a plan to the global frame (global_frame_) coord system.
| plan | Input plan to be transformed. | 
| global_plan | Output plan, which is then transformed to the global frame. | 
Definition at line 268 of file planner_action.cpp.
| 
 | private | 
Publisher to publish the current goal pose, which is used for path planning.
Definition at line 81 of file planner_action.h.
| 
 | private | 
Path sequence counter.
Definition at line 84 of file planner_action.h.