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 <string>
46 #include <vector>
47 
48 #include <geometry_msgs/PoseStamped.h>
49 
51 #include <mbf_utility/types.h>
52 
54 
56 
57 namespace mbf_abstract_nav
58 {
59 
75  {
76  public:
77 
80 
87  AbstractPlannerExecution(const std::string &name,
88  const mbf_abstract_core::AbstractPlanner::Ptr &planner_ptr,
89  const MoveBaseFlexConfig &config);
90 
94  virtual ~AbstractPlannerExecution();
95 
99  std::vector<geometry_msgs::PoseStamped> getPlan() const;
100 
106 
111  bool isPatienceExceeded() const;
112 
117  {
128  };
129 
134  PlanningState getState() const;
135 
139  double getFrequency() const { return frequency_; };
140 
145  double getCost() const;
146 
152  virtual bool cancel();
153 
159  void setNewGoal(const geometry_msgs::PoseStamped &goal, double tolerance);
160 
165  void setNewStart(const geometry_msgs::PoseStamped &start);
166 
173  void setNewStartAndGoal(const geometry_msgs::PoseStamped &start, const geometry_msgs::PoseStamped &goal,
174  double tolerance);
175 
183  bool start(const geometry_msgs::PoseStamped &start, const geometry_msgs::PoseStamped &goal,
184  double tolerance);
185 
191  void reconfigure(const MoveBaseFlexConfig &config);
192 
193  protected:
194 
197 
199  std::string plugin_name_;
200 
204  virtual void run();
205 
206  private:
207 
219  virtual uint32_t makePlan(
220  const geometry_msgs::PoseStamped &start,
221  const geometry_msgs::PoseStamped &goal,
222  double tolerance,
223  std::vector<geometry_msgs::PoseStamped> &plan,
224  double &cost,
225  std::string &message);
226 
232  void setState(PlanningState state, bool signalling);
233 
235  mutable boost::mutex state_mtx_;
236 
238  mutable boost::mutex plan_mtx_;
239 
241  mutable boost::mutex goal_start_mtx_;
242 
244  mutable boost::mutex planning_mtx_;
245 
247  mutable boost::mutex configuration_mutex_;
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 
300  };
301 
302 } /* namespace mbf_abstract_nav */
303 
304 #endif /* MBF_ABSTRACT_NAV__ABSTRACT_PLANNER_EXECUTION_H_ */
ros::Time last_valid_plan_time_
the last time a valid plan has been computed.
std::vector< geometry_msgs::PoseStamped > getPlan() const
Returns a new plan, if one is available.
std::string plugin_name_
the name of the loaded planner plugin
geometry_msgs::PoseStamped goal_
the current goal pose used for planning
void setState(PlanningState state, bool signalling)
Sets the internal state, thread communication safe.
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
No plan has been found (MAX_RETRIES and PAT_EXCEEDED are 0).
PlanningState state_
current internal state
PlanningState getState() const
Returns the current internal state.
bool isPatienceExceeded() const
Checks whether the patience was exceeded.
boost::mutex configuration_mutex_
dynamic reconfigure mutex for a thread safe communication
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.
double getFrequency() const
Gets planning frequency.
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...
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
double getCost() const
Gets computed costs.
AbstractPlannerExecution(const std::string &name, const mbf_abstract_core::AbstractPlanner::Ptr &planner_ptr, const MoveBaseFlexConfig &config)
Constructor.
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 robot trajectory
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
ros::Time getLastValidPlanTime() const
Returns the last time a valid plan was available.


mbf_abstract_nav
Author(s): Sebastian Pütz
autogenerated on Fri Nov 6 2020 03:56:24