41 #ifndef MBF_ABSTRACT_NAV__PLANNER_ACTION_H_ 42 #define MBF_ABSTRACT_NAV__PLANNER_ACTION_H_ 48 #include <mbf_msgs/GetPathAction.h> 60 const std::string& name,
75 std::vector<geometry_msgs::PoseStamped> &global_plan);
91 #endif //MBF_ABSTRACT_NAV__PLANNER_ACTION_H_
ros::Publisher current_goal_pub_
Publisher to publish the current goal pose, which is used for path planning.
unsigned int path_seq_count_
Path sequence counter.
boost::shared_ptr< PlannerAction > Ptr
PlannerAction(const std::string &name, const RobotInformation &robot_info)
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.
void run(GoalHandle &goal_handle, AbstractPlannerExecution &execution)
The AbstractPlannerExecution class loads and binds the global planner plugin. It contains a thread ru...