abstract_planner_execution.h
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.h
34  *
35  * authors:
36  * Sebastian Pütz <spuetz@uni-osnabrueck.de>
37  * Jorge Santos Simón <santos@magazino.eu>
38  *
39  */
40 
41 #ifndef MBF_ABSTRACT_NAV__ABSTRACT_PLANNER_EXECUTION_H_
42 #define MBF_ABSTRACT_NAV__ABSTRACT_PLANNER_EXECUTION_H_
43 
44 #include <map>
45 #include <stdint.h>
46 #include <string>
47 #include <vector>
48 
49 #include <geometry_msgs/PoseStamped.h>
50 #include <tf/transform_listener.h>
51 
53 #include <mbf_utility/types.h>
54 
56 
58 
59 namespace mbf_abstract_nav
60 {
61 
77  {
78  public:
79 
82 
87  AbstractPlannerExecution(const std::string name,
89  const MoveBaseFlexConfig &config,
90  boost::function<void()> setup_fn,
91  boost::function<void()> cleanup_fn);
92 
96  virtual ~AbstractPlannerExecution();
97 
103  std::vector<geometry_msgs::PoseStamped> getPlan();
104 
110 
115  bool isPatienceExceeded();
116 
121  {
132  };
133 
139 
143  double getFrequency() { return frequency_; };
144 
149  double getCost();
150 
156  virtual bool cancel();
157 
163  void setNewGoal(const geometry_msgs::PoseStamped &goal, double tolerance);
164 
169  void setNewStart(const geometry_msgs::PoseStamped &start);
170 
177  void setNewStartAndGoal(const geometry_msgs::PoseStamped &start, const geometry_msgs::PoseStamped &goal,
178  double tolerance);
179 
187  bool start(const geometry_msgs::PoseStamped &start, const geometry_msgs::PoseStamped &goal,
188  double tolerance);
189 
195  void reconfigure(const MoveBaseFlexConfig &config);
196 
197  protected:
198 
201 
203  std::string plugin_name_;
204 
208  virtual void run();
209 
210  private:
211 
223  virtual uint32_t makePlan(
224  const geometry_msgs::PoseStamped &start,
225  const geometry_msgs::PoseStamped &goal,
226  double tolerance,
227  std::vector<geometry_msgs::PoseStamped> &plan,
228  double &cost,
229  std::string &message);
230 
235  void setState(PlanningState state);
236 
238  boost::mutex state_mtx_;
239 
241  boost::mutex plan_mtx_;
242 
244  boost::mutex goal_start_mtx_;
245 
247  boost::mutex planning_mtx_;
248 
251 
254 
257 
260 
262  std::vector<geometry_msgs::PoseStamped> plan_;
263 
265  double cost_;
266 
268  geometry_msgs::PoseStamped start_;
269 
271  geometry_msgs::PoseStamped goal_;
272 
274  double tolerance_;
275 
277  double frequency_;
278 
281 
284 
286  bool planning_;
287 
289  std::string robot_frame_;
290 
292  std::string global_frame_;
293 
296 
299 
301  boost::mutex configuration_mutex_;
302 
303  };
304 
305 } /* namespace mbf_abstract_nav */
306 
307 #endif /* MBF_ABSTRACT_NAV__ABSTRACT_PLANNER_EXECUTION_H_ */
ros::Time last_valid_plan_time_
the last time a valid plan has been computed.
PlanningState getState()
Returns the current internal state.
std::string plugin_name_
the name of the loaded planner plugin
geometry_msgs::PoseStamped goal_
the current goal pose used for planning
bool has_new_start_
true, if a new start pose has been set, until it is used.
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...
geometry_msgs::PoseStamped start_
the current start pose used for planning
double tolerance_
optional goal tolerance, in meters
bool isPatienceExceeded()
Checks whether the patience was exceeded.
No plan has been found (MAX_RETRIES and PAT_EXCEEDED are 0).
PlanningState state_
current internal state
void setState(PlanningState state)
Sets the internal state, thread communication safe.
boost::mutex configuration_mutex_
dynamic reconfigure mutex for a thread safe communication
AbstractPlannerExecution(const std::string name, const mbf_abstract_core::AbstractPlanner::Ptr planner_ptr, const MoveBaseFlexConfig &config, boost::function< void()> setup_fn, boost::function< void()> cleanup_fn)
Constructor.
boost::shared_ptr< AbstractPlannerExecution > Ptr
shared pointer type to the planner execution.
virtual void run()
The main run method, a thread will execute this method. It contains the main planner execution loop...
bool planning_
main cycle variable of the execution loop
Exceeded the maximum number of retries without a valid command.
ros::Time getLastValidPlanTime()
Returns the last time a valid plan was available.
ros::Time last_call_start_time_
the last call start time, updated each cycle.
boost::mutex state_mtx_
mutex to handle safe thread communication for the current state
void setNewStart(const geometry_msgs::PoseStamped &start)
Sets a new start pose for the planner execution.
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.
void setNewGoal(const geometry_msgs::PoseStamped &goal, double tolerance)
Sets a new goal pose for the planner execution.
double frequency_
planning cycle frequency (used only when running full navigation; we store here for grouping paramete...
std::vector< geometry_msgs::PoseStamped > getPlan()
Returns a new plan, if one is available.
boost::mutex plan_mtx_
mutex to handle safe thread communication for the plan and plan-costs
std::string global_frame_
the global frame in which the planner needs to plan
boost::mutex goal_start_mtx_
mutex to handle safe thread communication for the goal and start pose.
std::vector< geometry_msgs::PoseStamped > plan_
current global plan
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.
bool has_new_goal_
true, if a new goal pose has been set, until it is used.
mbf_abstract_core::AbstractPlanner::Ptr planner_
the local planer to calculate the velocity command
boost::mutex planning_mtx_
mutex to handle safe thread communication for the planning_ flag.
void reconfigure(const MoveBaseFlexConfig &config)
Is called by the server thread to reconfigure the controller execution, if a user uses dynamic reconf...
std::string robot_frame_
robot frame used for computing the current robot pose
const TFPtr tf_listener_ptr_
shared pointer to a common TransformListener
The AbstractPlannerExecution class loads and binds the global planner plugin. It contains a thread ru...
ros::Duration patience_
planning patience duration time


mbf_abstract_nav
Author(s): Sebastian Pütz
autogenerated on Tue Jun 18 2019 19:34:34