Go to the documentation of this file.
41 #ifndef MBF_ABSTRACT_NAV__PLANNER_ACTION_H_
42 #define MBF_ABSTRACT_NAV__PLANNER_ACTION_H_
46 #include <mbf_msgs/GetPathAction.h>
49 #include "mbf_abstract_nav/abstract_action_base.hpp"
56 class PlannerAction :
public AbstractActionBase<mbf_msgs::GetPathAction, AbstractPlannerExecution>
63 const std::string &name,
78 std::vector<geometry_msgs::PoseStamped>& global_plan);
unsigned int path_seq_count_
Path sequence counter.
bool transformPlanToGlobalFrame(const std::vector< geometry_msgs::PoseStamped > &plan, std::vector< geometry_msgs::PoseStamped > &global_plan)
Transforms a plan to the global frame (global_frame_) coord system.
ros::Publisher current_goal_pub_
Publisher to publish the current goal pose, which is used for path planning.
The AbstractPlannerExecution class loads and binds the global planner plugin. It contains a thread ru...
boost::shared_ptr< PlannerAction > Ptr
void runImpl(GoalHandle &goal_handle, AbstractPlannerExecution &execution)
PlannerAction(const std::string &name, const mbf_utility::RobotInformation &robot_info)
mbf_abstract_nav
Author(s): Sebastian Pütz
autogenerated on Wed Mar 2 2022 00:33:47