ROS_ERROR("This planner has not been initialized yet, but it is being used, please call initialize() before use");
ROS_ERROR("OpendriveGlobalPlanner: this planner has not been initialized yet, but it is being used, please call initialize() before use");
return;
return;
}
}
...
@@ -309,7 +309,7 @@ bool OpendriveGlobalPlanner::makePlan(const geometry_msgs::PoseStamped& start, c
...
@@ -309,7 +309,7 @@ bool OpendriveGlobalPlanner::makePlan(const geometry_msgs::PoseStamped& start, c
boost::mutex::scoped_locklock(mutex_);
boost::mutex::scoped_locklock(mutex_);
if(!initialized_){
if(!initialized_){
ROS_ERROR("This planner has not been initialized yet, but it is being used, please call initialize() before use");
ROS_ERROR("OpendriveGlobalPlanner: this planner has not been initialized yet, but it is being used, please call initialize() before use");
returnfalse;
returnfalse;
}
}
...
@@ -322,13 +322,13 @@ bool OpendriveGlobalPlanner::makePlan(const geometry_msgs::PoseStamped& start, c
...
@@ -322,13 +322,13 @@ bool OpendriveGlobalPlanner::makePlan(const geometry_msgs::PoseStamped& start, c
//until tf can handle transforming things that are way in the past... we'll require the goal to be in our global frame
//until tf can handle transforming things that are way in the past... we'll require the goal to be in our global frame
if(goal.header.frame_id!=global_frame)
if(goal.header.frame_id!=global_frame)
{
{
ROS_ERROR("The goal pose passed to this planner must be in the %s frame. It is instead in the %s frame.",global_frame.c_str(),goal.header.frame_id.c_str());
ROS_ERROR("OpendriveGlobalPlanner: the goal pose passed to this planner must be in the %s frame. It is instead in the %s frame.",global_frame.c_str(),goal.header.frame_id.c_str());
returnfalse;
returnfalse;
}
}
if(start.header.frame_id!=global_frame)
if(start.header.frame_id!=global_frame)
{
{
ROS_ERROR("The start pose passed to this planner must be in the %s frame. It is instead in the %s frame.",global_frame.c_str(),start.header.frame_id.c_str());
ROS_ERROR("OpendriveGlobalPlanner: the start pose passed to this planner must be in the %s frame. It is instead in the %s frame.",global_frame.c_str(),start.header.frame_id.c_str());
returnfalse;
returnfalse;
}
}
...
@@ -343,7 +343,7 @@ bool OpendriveGlobalPlanner::makePlan(const geometry_msgs::PoseStamped& start, c
...
@@ -343,7 +343,7 @@ bool OpendriveGlobalPlanner::makePlan(const geometry_msgs::PoseStamped& start, c