src/abstract_planner_execution.cpp
Go to the documentation of this file.
1 /*
2  * Copyright 2018, Magazino GmbH, Sebastian Pütz, Jorge Santos Simón
3  *
4  * Redistribution and use in source and binary forms, with or without
5  * modification, are permitted provided that the following conditions
6  * are met:
7  *
8  * 1. Redistributions of source code must retain the above copyright
9  * notice, this list of conditions and the following disclaimer.
10  *
11  * 2. Redistributions in binary form must reproduce the above
12  * copyright notice, this list of conditions and the following
13  * disclaimer in the documentation and/or other materials provided
14  * with the distribution.
15  *
16  * 3. Neither the name of the copyright holder nor the names of its
17  * contributors may be used to endorse or promote products derived
18  * from this software without specific prior written permission.
19  *
20  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
21  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
22  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
23  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
24  * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
25  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
26  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
27  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
28  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
29  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
30  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
31  * POSSIBILITY OF SUCH DAMAGE.
32  *
33  * abstract_planner_execution.cpp
34  *
35  * authors:
36  * Sebastian Pütz <spuetz@uni-osnabrueck.de>
37  * Jorge Santos Simón <santos@magazino.eu>
38  *
39  */
40 
42 
43 namespace mbf_abstract_nav
44 {
46  const mbf_abstract_core::AbstractPlanner::Ptr& planner_ptr,
47  const MoveBaseFlexConfig& config)
48  : AbstractExecutionBase(name)
49  , planner_(planner_ptr)
50  , state_(INITIALIZED)
51  , max_retries_(0)
52  , planning_(false)
53  , has_new_start_(false)
54  , has_new_goal_(false)
55 {
56  ros::NodeHandle private_nh("~");
57 
58  // non-dynamically reconfigurable parameters
59  private_nh.param("robot_frame", robot_frame_, std::string("base_footprint"));
60  private_nh.param("map_frame", global_frame_, std::string("map"));
61 
62  // dynamically reconfigurable parameters
63  reconfigure(config);
64 }
65 
67  const mbf_abstract_core::AbstractPlanner::Ptr& planner_ptr,
68  const TFPtr& tf_listener_ptr, const MoveBaseFlexConfig& config)
69  : AbstractExecutionBase(name)
70  , planner_(planner_ptr)
71  , state_(INITIALIZED)
72  , max_retries_(0)
73  , planning_(false)
74  , tf_listener_ptr_(tf_listener_ptr)
75  , has_new_start_(false)
76  , has_new_goal_(false)
77 {
78  ros::NodeHandle private_nh("~");
79 
80  // non-dynamically reconfigurable parameters
81  private_nh.param("robot_frame", robot_frame_, std::string("base_footprint"));
82  private_nh.param("map_frame", global_frame_, std::string("map"));
83 
84  // dynamically reconfigurable parameters
85  reconfigure(config);
86 }
87 
89 {
90 }
91 
92 template <typename _Iter>
93 double sumDistance(_Iter _begin, _Iter _end)
94 {
95  // helper function to get the distance of a path.
96  // in C++11, we could add static_assert on the interator_type.
97  double dist = 0.;
98 
99  // minimum length of the path is 2.
100  if (std::distance(_begin, _end) < 2)
101  return dist;
102 
103  // two pointer iteration
104  for (_Iter next = _begin + 1; next != _end; ++_begin, ++next)
105  dist += mbf_utility::distance(*_begin, *next);
106 
107  return dist;
108 }
109 
111 {
112  return cost_;
113 }
114 
115 void AbstractPlannerExecution::reconfigure(const MoveBaseFlexConfig &config)
116 {
117  boost::lock_guard<boost::mutex> guard(configuration_mutex_);
118 
119  max_retries_ = config.planner_max_retries;
120  frequency_ = config.planner_frequency;
121 
122  // Timeout granted to the global planner. We keep calling it up to this time or up to max_retries times
123  // If it doesn't return within time, the navigator will cancel it and abort the corresponding action
124  try
125  {
126  patience_ = ros::Duration(config.planner_patience);
127  }
128  catch (std::exception& ex)
129  {
130  ROS_ERROR_STREAM("Failed to set planner_patience: " << ex.what());
132  }
133 }
134 
135 
137 {
138  boost::lock_guard<boost::mutex> guard(state_mtx_);
139  return state_;
140 }
141 
143 {
144  boost::lock_guard<boost::mutex> guard(state_mtx_);
145  state_ = state;
146 
147  // we exit planning if we are signalling.
148  planning_ = !signalling;
149 
150  // some states are quiet, most aren't
151  if(signalling)
152  condition_.notify_all();
153 }
154 
155 
157 {
158  boost::lock_guard<boost::mutex> guard(plan_mtx_);
159  return last_valid_plan_time_;
160 }
161 
162 
164 {
166 }
167 
168 
169 std::vector<geometry_msgs::PoseStamped> AbstractPlannerExecution::getPlan() const
170 {
171  boost::lock_guard<boost::mutex> guard(plan_mtx_);
172  // copy plan and costs to output
173  return plan_;
174 }
175 
176 
177 void AbstractPlannerExecution::setNewGoal(const geometry_msgs::PoseStamped &goal, double tolerance)
178 {
179  boost::lock_guard<boost::mutex> guard(goal_start_mtx_);
180  goal_ = goal;
181  tolerance_ = tolerance;
182  has_new_goal_ = true;
183 }
184 
185 
186 void AbstractPlannerExecution::setNewStart(const geometry_msgs::PoseStamped &start)
187 {
188  boost::lock_guard<boost::mutex> guard(goal_start_mtx_);
189  start_ = start;
190  has_new_start_ = true;
191 }
192 
193 
194 void AbstractPlannerExecution::setNewStartAndGoal(const geometry_msgs::PoseStamped &start,
195  const geometry_msgs::PoseStamped &goal,
196  double tolerance)
197 {
198  boost::lock_guard<boost::mutex> guard(goal_start_mtx_);
199  start_ = start;
200  goal_ = goal;
201  tolerance_ = tolerance;
202  has_new_start_ = true;
203  has_new_goal_ = true;
204 }
205 
206 
207 bool AbstractPlannerExecution::start(const geometry_msgs::PoseStamped &start,
208  const geometry_msgs::PoseStamped &goal,
209  double tolerance)
210 {
211  if (planning_)
212  {
213  return false;
214  }
215  boost::lock_guard<boost::mutex> guard(planning_mtx_);
216  planning_ = true;
217  start_ = start;
218  goal_ = goal;
219  tolerance_ = tolerance;
220 
221  const geometry_msgs::Point& s = start.pose.position;
222  const geometry_msgs::Point& g = goal.pose.position;
223 
224  ROS_DEBUG_STREAM("Start planning from the start pose: (" << s.x << ", " << s.y << ", " << s.z << ")"
225  << " to the goal pose: ("<< g.x << ", " << g.y << ", " << g.z << ")");
226 
228 }
229 
230 
232 {
233  cancel_ = true; // force cancel immediately, as the call to cancel in the planner can take a while
234 
235  // returns false if cancel is not implemented or rejected by the planner (will run until completion)
236  if (!planner_->cancel())
237  {
238  ROS_WARN_STREAM("Cancel planning failed or is not supported by the plugin. "
239  << "Wait until the current planning finished!");
240 
241  return false;
242  }
243  return true;
244 }
245 
246 uint32_t AbstractPlannerExecution::makePlan(const geometry_msgs::PoseStamped &start,
247  const geometry_msgs::PoseStamped &goal,
248  double tolerance,
249  std::vector<geometry_msgs::PoseStamped> &plan,
250  double &cost,
251  std::string &message)
252 {
253  return planner_->makePlan(start, goal, tolerance, plan, cost, message);
254 }
255 
257 {
258  setState(STARTED, false);
259  boost::lock_guard<boost::mutex> guard(planning_mtx_);
260  int retries = 0;
261  geometry_msgs::PoseStamped current_start = start_;
262  geometry_msgs::PoseStamped current_goal = goal_;
263  double current_tolerance = tolerance_;
264 
267 
268  try
269  {
270  while (planning_ && ros::ok())
271  {
272  // call the planner
273  std::vector<geometry_msgs::PoseStamped> plan;
274  double cost;
275 
276  // lock goal start mutex
277  goal_start_mtx_.lock();
278  if (has_new_start_)
279  {
280  has_new_start_ = false;
281  current_start = start_;
282  ROS_INFO_STREAM("A new start pose is available. Planning with the new start pose!");
283  const geometry_msgs::Point& s = start_.pose.position;
284  ROS_INFO_STREAM("New planning start pose: (" << s.x << ", " << s.y << ", " << s.z << ")");
285  }
286  if (has_new_goal_)
287  {
288  has_new_goal_ = false;
289  current_goal = goal_;
290  current_tolerance = tolerance_;
291  ROS_INFO_STREAM("A new goal pose is available. Planning with the new goal pose and the tolerance: "
292  << current_tolerance);
293  const geometry_msgs::Point& g = goal_.pose.position;
294  ROS_INFO_STREAM("New goal pose: (" << g.x << ", " << g.y << ", " << g.z << ")");
295  }
296 
297  // unlock goal
298  goal_start_mtx_.unlock();
299  if (cancel_)
300  {
301  ROS_INFO_STREAM("The global planner has been canceled!");
302  setState(CANCELED, true);
303  }
304  else
305  {
306  setState(PLANNING, false);
307 
308  outcome_ = makePlan(current_start, current_goal, current_tolerance, plan, cost, message_);
309  bool success = outcome_ < 10;
310 
311  boost::lock_guard<boost::mutex> guard(configuration_mutex_);
312 
313  if (cancel_ && !isPatienceExceeded())
314  {
315  ROS_INFO_STREAM("The planner \"" << name_ << "\" has been canceled!"); // but not due to patience exceeded
316  setState(CANCELED, true);
317  }
318  else if (success)
319  {
320  ROS_DEBUG_STREAM("Successfully found a plan.");
321 
322  boost::lock_guard<boost::mutex> plan_mtx_guard(plan_mtx_);
323  plan_ = plan;
324  cost_ = cost;
325  // estimate the cost based on the distance if its zero.
326  if (cost_ == 0)
327  cost_ = sumDistance(plan_.begin(), plan_.end());
328 
330  setState(FOUND_PLAN, true);
331  }
332  else if (max_retries_ > 0 && ++retries > max_retries_)
333  {
334  ROS_INFO_STREAM("Planning reached max retries! (" << max_retries_ << ")");
335  setState(MAX_RETRIES, true);
336  }
337  else if (isPatienceExceeded())
338  {
339  // Patience exceeded is handled at two levels: here to stop retrying planning when max_retries is
340  // disabled, and on the navigation server when the planner doesn't return for more that patience seconds.
341  // In the second case, the navigation server has tried to cancel planning (possibly without success, as
342  // old nav_core-based planners do not support canceling), and we add here the fact to the log for info
343  ROS_INFO_STREAM("Planning patience (" << patience_.toSec() << "s) has been exceeded"
344  << (cancel_ ? "; planner canceled!" : ""));
345  setState(PAT_EXCEEDED, true);
346  }
347  else if (max_retries_ == 0 && patience_.isZero())
348  {
349  ROS_INFO_STREAM("Planning could not find a plan!");
350  setState(NO_PLAN_FOUND, true);
351  }
352  else
353  {
354  ROS_DEBUG_STREAM("Planning could not find a plan! Trying again...");
355  }
356  }
357  } // while (planning_ && ros::ok())
358  }
359  catch (const boost::thread_interrupted &ex)
360  {
361  // Planner thread interrupted; probably we have exceeded planner patience
362  ROS_WARN_STREAM("Planner thread interrupted!");
363  setState(STOPPED, true);
364  }
365  catch (...)
366  {
367  ROS_ERROR_STREAM("Unknown error occurred: " << boost::current_exception_diagnostic_information());
368  setState(INTERNAL_ERROR, true);
369  }
370 }
371 
372 } /* namespace mbf_abstract_nav */
373 
mbf_abstract_nav::AbstractPlannerExecution::INTERNAL_ERROR
@ INTERNAL_ERROR
An internal error occurred.
Definition: abstract_planner_execution.h:136
mbf_abstract_nav::AbstractPlannerExecution::state_
PlanningState state_
current internal state
Definition: abstract_planner_execution.h:307
mbf_abstract_nav::AbstractPlannerExecution::planning_mtx_
boost::mutex planning_mtx_
mutex to handle safe thread communication for the planning_ flag.
Definition: abstract_planner_execution.h:256
mbf_abstract_nav::AbstractPlannerExecution::start_
geometry_msgs::PoseStamped start_
the current start pose used for planning
Definition: abstract_planner_execution.h:280
mbf_abstract_nav::AbstractPlannerExecution::makePlan
virtual uint32_t makePlan(const geometry_msgs::PoseStamped &start, const geometry_msgs::PoseStamped &goal, double tolerance, std::vector< geometry_msgs::PoseStamped > &plan, double &cost, std::string &message)
calls the planner plugin to make a plan from the start pose to the goal pose with the given tolerance...
Definition: src/abstract_planner_execution.cpp:246
mbf_abstract_nav::AbstractPlannerExecution::reconfigure
void reconfigure(const MoveBaseFlexConfig &config)
Is called by the server thread to reconfigure the controller execution, if a user uses dynamic reconf...
Definition: src/abstract_planner_execution.cpp:115
ROS_ERROR_STREAM
#define ROS_ERROR_STREAM(args)
boost::shared_ptr< ::mbf_abstract_core::AbstractPlanner >
mbf_abstract_nav::AbstractExecutionBase::cancel_
bool cancel_
flag for canceling controlling
Definition: abstract_execution_base.h:123
mbf_utility::distance
double distance(const geometry_msgs::PoseStamped &pose1, const geometry_msgs::PoseStamped &pose2)
mbf_abstract_nav::AbstractPlannerExecution::isPatienceExceeded
bool isPatienceExceeded() const
Checks whether the patience was exceeded.
Definition: src/abstract_planner_execution.cpp:163
s
XmlRpcServer s
mbf_abstract_nav::AbstractPlannerExecution::PLANNING
@ PLANNING
Executing the plugin.
Definition: abstract_planner_execution.h:129
mbf_abstract_nav::AbstractPlannerExecution::tolerance_
double tolerance_
optional goal tolerance, in meters
Definition: abstract_planner_execution.h:286
mbf_abstract_nav::AbstractPlannerExecution::getLastValidPlanTime
ros::Time getLastValidPlanTime() const
Returns the last time a valid plan was available.
Definition: src/abstract_planner_execution.cpp:156
mbf_abstract_nav::AbstractExecutionBase::outcome_
uint32_t outcome_
the last received plugin execution outcome
Definition: abstract_execution_base.h:126
mbf_abstract_nav::AbstractPlannerExecution::patience_
ros::Duration patience_
planning patience duration time
Definition: abstract_planner_execution.h:292
mbf_abstract_nav::AbstractPlannerExecution::has_new_start_
bool has_new_start_
true, if a new start pose has been set, until it is used.
Definition: abstract_planner_execution.h:265
mbf_abstract_nav::AbstractPlannerExecution::last_call_start_time_
ros::Time last_call_start_time_
the last call start time, updated each cycle.
Definition: abstract_planner_execution.h:268
mbf_abstract_nav::AbstractPlannerExecution::run
virtual void run()
The main run method, a thread will execute this method. It contains the main planner execution loop.
Definition: src/abstract_planner_execution.cpp:256
mbf_abstract_nav
Definition: abstract_controller_execution.h:58
ROS_DEBUG_STREAM
#define ROS_DEBUG_STREAM(args)
ros::ok
ROSCPP_DECL bool ok()
mbf_abstract_nav::AbstractPlannerExecution::setNewStart
void setNewStart(const geometry_msgs::PoseStamped &start)
Sets a new start pose for the planner execution.
Definition: src/abstract_planner_execution.cpp:186
mbf_abstract_nav::AbstractPlannerExecution::PAT_EXCEEDED
@ PAT_EXCEEDED
Exceeded the patience time without a valid command.
Definition: abstract_planner_execution.h:132
mbf_abstract_nav::AbstractPlannerExecution::frequency_
double frequency_
planning cycle frequency (used only when running full navigation; we store here for grouping paramete...
Definition: abstract_planner_execution.h:289
ROS_WARN_STREAM
#define ROS_WARN_STREAM(args)
mbf_abstract_nav::AbstractPlannerExecution::getCost
double getCost() const
Gets computed costs.
Definition: src/abstract_planner_execution.cpp:110
mbf_abstract_nav::AbstractExecutionBase::condition_
boost::condition_variable condition_
condition variable to wake up control thread
Definition: abstract_execution_base.h:114
mbf_abstract_nav::AbstractPlannerExecution::NO_PLAN_FOUND
@ NO_PLAN_FOUND
No plan has been found (MAX_RETRIES and PAT_EXCEEDED are 0).
Definition: abstract_planner_execution.h:133
mbf_abstract_nav::AbstractPlannerExecution::cost_
double cost_
current global plan cost
Definition: abstract_planner_execution.h:277
mbf_abstract_nav::AbstractPlannerExecution::planning_
bool planning_
main cycle variable of the execution loop
Definition: abstract_planner_execution.h:298
mbf_abstract_nav::AbstractPlannerExecution::getPlan
std::vector< geometry_msgs::PoseStamped > getPlan() const
Returns a new plan, if one is available.
Definition: src/abstract_planner_execution.cpp:169
mbf_abstract_nav::AbstractPlannerExecution::state_mtx_
boost::mutex state_mtx_
mutex to handle safe thread communication for the current state
Definition: abstract_planner_execution.h:247
ROS_INFO_STREAM
#define ROS_INFO_STREAM(args)
mbf_abstract_nav::AbstractPlannerExecution::robot_frame_
std::string robot_frame_
robot frame used for computing the current robot pose
Definition: abstract_planner_execution.h:301
mbf_abstract_nav::AbstractPlannerExecution::AbstractPlannerExecution
AbstractPlannerExecution(const std::string &name, const mbf_abstract_core::AbstractPlanner::Ptr &planner_ptr, const MoveBaseFlexConfig &config)
Constructor.
Definition: src/abstract_planner_execution.cpp:45
mbf_abstract_nav::AbstractPlannerExecution::STOPPED
@ STOPPED
The planner has been stopped.
Definition: abstract_planner_execution.h:135
mbf_abstract_nav::AbstractPlannerExecution::MAX_RETRIES
@ MAX_RETRIES
Exceeded the maximum number of retries without a valid command.
Definition: abstract_planner_execution.h:131
mbf_abstract_nav::AbstractPlannerExecution::CANCELED
@ CANCELED
The planner has been canceled.
Definition: abstract_planner_execution.h:134
mbf_abstract_nav::AbstractPlannerExecution::plan_
std::vector< geometry_msgs::PoseStamped > plan_
current global plan
Definition: abstract_planner_execution.h:274
mbf_abstract_nav::sumDistance
double sumDistance(_Iter _begin, _Iter _end)
Definition: src/abstract_planner_execution.cpp:93
mbf_abstract_nav::AbstractPlannerExecution::getState
PlanningState getState() const
Returns the current internal state.
Definition: src/abstract_planner_execution.cpp:136
ros::Time
mbf_abstract_nav::AbstractExecutionBase::message_
std::string message_
the last received plugin execution message
Definition: abstract_execution_base.h:129
mbf_abstract_nav::AbstractPlannerExecution::~AbstractPlannerExecution
virtual ~AbstractPlannerExecution()
Destructor.
Definition: src/abstract_planner_execution.cpp:88
mbf_abstract_nav::AbstractPlannerExecution::global_frame_
std::string global_frame_
the global frame in which the planner needs to plan
Definition: abstract_planner_execution.h:304
ros::NodeHandle::param
T param(const std::string &param_name, const T &default_val) const
mbf_abstract_nav::AbstractPlannerExecution::plan_mtx_
boost::mutex plan_mtx_
mutex to handle safe thread communication for the plan and plan-costs
Definition: abstract_planner_execution.h:250
mbf_abstract_nav::AbstractPlannerExecution::goal_start_mtx_
boost::mutex goal_start_mtx_
mutex to handle safe thread communication for the goal and start pose.
Definition: abstract_planner_execution.h:253
mbf_abstract_nav::AbstractPlannerExecution::has_new_goal_
bool has_new_goal_
true, if a new goal pose has been set, until it is used.
Definition: abstract_planner_execution.h:262
mbf_abstract_nav::AbstractPlannerExecution::setState
void setState(PlanningState state, bool signalling)
Sets the internal state, thread communication safe.
Definition: src/abstract_planner_execution.cpp:142
mbf_abstract_nav::AbstractPlannerExecution::last_valid_plan_time_
ros::Time last_valid_plan_time_
the last time a valid plan has been computed.
Definition: abstract_planner_execution.h:271
mbf_abstract_nav::AbstractExecutionBase
Base class for running concurrent navigation tasks.
Definition: abstract_execution_base.h:57
mbf_abstract_nav::AbstractPlannerExecution::setNewGoal
void setNewGoal(const geometry_msgs::PoseStamped &goal, double tolerance)
Sets a new goal pose for the planner execution.
Definition: src/abstract_planner_execution.cpp:177
mbf_abstract_nav::AbstractPlannerExecution::PlanningState
PlanningState
Internal states.
Definition: abstract_planner_execution.h:125
DurationBase< Duration >::toSec
double toSec() const
mbf_abstract_nav::AbstractPlannerExecution::cancel
virtual bool cancel()
Cancel the planner execution. This calls the cancel method of the planner plugin. This could be usefu...
Definition: src/abstract_planner_execution.cpp:231
mbf_abstract_nav::AbstractPlannerExecution::FOUND_PLAN
@ FOUND_PLAN
Found a valid plan.
Definition: abstract_planner_execution.h:130
mbf_abstract_nav::AbstractPlannerExecution::max_retries_
int max_retries_
planning max retries
Definition: abstract_planner_execution.h:295
ros::Duration
mbf_abstract_nav::AbstractExecutionBase::start
virtual bool start()
Definition: src/abstract_execution_base.cpp:57
mbf_abstract_nav::AbstractPlannerExecution::STARTED
@ STARTED
Planner started.
Definition: abstract_planner_execution.h:128
DurationBase< Duration >::isZero
bool isZero() const
mbf_abstract_nav::AbstractExecutionBase::name_
std::string name_
the plugin name; not the plugin type!
Definition: abstract_execution_base.h:132
mbf_abstract_nav::AbstractPlannerExecution::planner_
mbf_abstract_core::AbstractPlanner::Ptr planner_
the local planer to calculate the robot trajectory
Definition: abstract_planner_execution.h:205
ros::NodeHandle
mbf_abstract_nav::AbstractPlannerExecution::goal_
geometry_msgs::PoseStamped goal_
the current goal pose used for planning
Definition: abstract_planner_execution.h:283
ros::Time::now
static Time now()
abstract_planner_execution.h
mbf_abstract_nav::AbstractPlannerExecution::setNewStartAndGoal
void setNewStartAndGoal(const geometry_msgs::PoseStamped &start, const geometry_msgs::PoseStamped &goal, double tolerance)
Sets a new star and goal pose for the planner execution.
Definition: src/abstract_planner_execution.cpp:194
mbf_abstract_nav::AbstractPlannerExecution::configuration_mutex_
boost::mutex configuration_mutex_
dynamic reconfigure mutex for a thread safe communication
Definition: abstract_planner_execution.h:259


mbf_abstract_nav
Author(s): Sebastian Pütz
autogenerated on Wed Mar 2 2022 00:33:47