49 const std::string &name,
51 : AbstractActionBase(name, robot_info), path_seq_count_(0)
60 const mbf_msgs::GetPathGoal& goal = *(goal_handle.getGoal().get());
62 mbf_msgs::GetPathResult result;
63 geometry_msgs::PoseStamped start_pose;
66 result.path.header.frame_id = robot_info_.getGlobalFrame();
68 double tolerance = goal.tolerance;
72 bool planner_active =
true;
76 start_pose = goal.start_pose;
77 const geometry_msgs::Point& p = start_pose.pose.position;
83 if (!robot_info_.getRobotPose(start_pose))
85 result.outcome = mbf_msgs::GetPathResult::TF_ERROR;
86 result.message =
"Could not get the current robot pose!";
87 goal_handle.setAborted(result, result.message);
93 const geometry_msgs::Point& p = start_pose.pose.position;
95 << p.x <<
", " << p.y <<
", " << p.z <<
").");
101 std::vector<geometry_msgs::PoseStamped> plan, global_plan;
103 while (planner_active &&
ros::ok())
106 state_planning_input = execution.
getState();
108 switch (state_planning_input)
112 if (!execution.
start(start_pose, goal.target_pose, tolerance))
114 result.outcome = mbf_msgs::GetPathResult::INTERNAL_ERROR;
115 result.message =
"Another thread is still planning!";
116 goal_handle.setAborted(result, result.message);
118 planner_active =
false;
129 result.outcome = mbf_msgs::GetPathResult::STOPPED;
130 result.message =
"Global planner has been stopped!";
131 goal_handle.setAborted(result, result.message);
132 planner_active =
false;
139 result.outcome = mbf_msgs::GetPathResult::CANCELED;
140 result.message =
"Global planner has been canceled!";
141 goal_handle.setCanceled(result, result.message);
142 planner_active =
false;
168 result.outcome = mbf_msgs::GetPathResult::TF_ERROR;
169 result.message =
"Could not transform the plan to the global frame!";
172 goal_handle.setAborted(result, result.message);
173 planner_active =
false;
177 if (global_plan.empty())
179 result.outcome = mbf_msgs::GetPathResult::EMPTY_PATH;
180 result.message =
"Global planner returned an empty path!";
183 goal_handle.setAborted(result, result.message);
184 planner_active =
false;
188 result.path.poses = global_plan;
189 result.cost = execution.
getCost();
192 goal_handle.setSucceeded(result, result.message);
194 planner_active =
false;
202 goal_handle.setAborted(result, result.message);
203 planner_active =
false;
210 goal_handle.setAborted(result, result.message);
211 planner_active =
false;
216 result.outcome = mbf_msgs::GetPathResult::PAT_EXCEEDED;
217 result.message =
"Global planner exceeded the patience time";
218 goal_handle.setAborted(result, result.message);
219 planner_active =
false;
224 planner_active =
false;
225 result.outcome = mbf_msgs::GetPathResult::INTERNAL_ERROR;
226 result.message =
"Internal error: Unknown error thrown by the plugin!";
227 goal_handle.setAborted(result, result.message);
231 result.outcome = mbf_msgs::GetPathResult::INTERNAL_ERROR;
232 std::ostringstream ss;
233 ss <<
"Internal error: Unknown state in a move base flex planner execution with the number: " 234 <<
static_cast<int>(state_planning_input);
235 result.message = ss.str();
237 goal_handle.setAborted(result, result.message);
238 planner_active =
false;
262 std::vector<geometry_msgs::PoseStamped>& global_plan)
265 global_plan.reserve(plan.size());
266 std::vector<geometry_msgs::PoseStamped>::const_iterator iter;
267 bool tf_success =
false;
268 for (iter = plan.begin(); iter != plan.end(); ++iter)
270 geometry_msgs::PoseStamped global_pose;
272 robot_info_.getTfTimeout(), *iter, global_pose);
275 ROS_ERROR_STREAM(
"Can not transform pose from the \"" << iter->header.frame_id <<
"\" frame into the \"" 276 << robot_info_.getGlobalFrame() <<
"\" frame !");
279 global_plan.push_back(global_pose);
void runImpl(GoalHandle &goal_handle, AbstractPlannerExecution &execution)
#define ROS_DEBUG_STREAM_NAMED(name, args)
#define ROS_ERROR_STREAM_NAMED(name, args)
PlannerAction(const std::string &name, const mbf_utility::RobotInformation &robot_info)
ros::Publisher current_goal_pub_
Publisher to publish the current goal pose, which is used for path planning.
The planner has been stopped.
unsigned int path_seq_count_
Path sequence counter.
No plan has been found (MAX_RETRIES and PAT_EXCEEDED are 0).
The planner has been canceled.
#define ROS_INFO_STREAM_NAMED(name, args)
boost::cv_status waitForStateUpdate(boost::chrono::microseconds const &duration)
double getCost() const
Gets computed costs.
bool isPatienceExceeded() const
Checks whether the patience was exceeded.
std::vector< geometry_msgs::PoseStamped > getPlan() const
Returns a new plan, if one is available.
void publish(const boost::shared_ptr< M > &message) const
Exceeded the maximum number of retries without a valid command.
#define ROS_FATAL_STREAM_NAMED(name, args)
An internal error occurred.
virtual bool cancel()
Cancel the planner execution. This calls the cancel method of the planner plugin. This could be usefu...
Exceeded the patience time without a valid command.
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
uint32_t getOutcome() const
Gets the current plugin execution outcome.
PlanningState
Internal states.
const std::string & getMessage() const
Gets the current plugin execution message.
PlanningState getState() const
Returns the current internal state.
#define ROS_DEBUG_THROTTLE_NAMED(period, name,...)
#define ROS_ERROR_STREAM(args)
bool start(const geometry_msgs::PoseStamped &start, const geometry_msgs::PoseStamped &goal, double tolerance)
Starts the planner execution thread with the given parameters.
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.
bool transformPose(const TF &tf, const std::string &target_frame, const ros::Duration &timeout, const geometry_msgs::PoseStamped &in, geometry_msgs::PoseStamped &out)
The AbstractPlannerExecution class loads and binds the global planner plugin. It contains a thread ru...
#define ROS_WARN_STREAM_NAMED(name, args)