dlux_global_planner.h
Go to the documentation of this file.
1 /*
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2018, Locus Robotics
5  * All rights reserved.
6  *
7  * Redistribution and use in source and binary forms, with or without
8  * modification, are permitted provided that the following conditions
9  * are met:
10  *
11  * * Redistributions of source code must retain the above copyright
12  * notice, this list of conditions and the following disclaimer.
13  * * Redistributions in binary form must reproduce the above
14  * copyright notice, this list of conditions and the following
15  * disclaimer in the documentation and/or other materials provided
16  * with the distribution.
17  * * Neither the name of the copyright holder nor the names of its
18  * contributors may be used to endorse or promote products derived
19  * from this software without specific prior written permission.
20  *
21  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25  * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32  * POSSIBILITY OF SUCH DAMAGE.
33  */
34 
35 #ifndef DLUX_GLOBAL_PLANNER_DLUX_GLOBAL_PLANNER_H
36 #define DLUX_GLOBAL_PLANNER_DLUX_GLOBAL_PLANNER_H
37 
39 #include <nav_core2/costmap.h>
43 #include <nav_2d_msgs/Pose2DStamped.h>
45 #include <pluginlib/class_loader.h>
46 #include <ros/ros.h>
47 #include <string>
48 
49 namespace dlux_global_planner
50 {
56 {
57 public:
59 
60  // Standard GlobalPlanner Interface
61  void initialize(const ros::NodeHandle& parent, const std::string& name,
62  TFListenerPtr tf, nav_core2::Costmap::Ptr costmap) override;
63  nav_2d_msgs::Path2D makePlan(const nav_2d_msgs::Pose2DStamped& start,
64  const nav_2d_msgs::Pose2DStamped& goal) override;
65 
71  virtual bool isPlanValid(const nav_2d_msgs::Path2D& path) const;
72 
73 protected:
74  // Path Caching Methods
75 
89  virtual bool hasValidCachedPath(const geometry_msgs::Pose2D& local_goal,
90  unsigned int goal_x, unsigned int goal_y);
91 
96  virtual bool shouldReturnCachedPathImmediately() const;
97 
104  virtual bool shouldReturnNewPath(const nav_2d_msgs::Path2D& new_path, const double new_path_cost) const;
105 
106  // Plugins
111 
112  // Key members
117 
118  // Path Caching
121  nav_2d_msgs::Path2D cached_path_;
124 
125  // potential publishing
127 
128  // debug printing
130 };
131 } // namespace dlux_global_planner
132 
133 #endif // DLUX_GLOBAL_PLANNER_DLUX_GLOBAL_PLANNER_H
boost::shared_ptr< Traceback > traceback_
virtual bool shouldReturnCachedPathImmediately() const
Whether the planner should always return a valid cached path without running the planning algorithm...
boost::shared_ptr< PotentialCalculator > calculator_
pluginlib::ClassLoader< PotentialCalculator > calc_loader_
virtual bool hasValidCachedPath(const geometry_msgs::Pose2D &local_goal, unsigned int goal_x, unsigned int goal_y)
Check whether there is a valid cached path where the goal hasn&#39;t changed.
Plugin-based global wavefront planner that conforms to the nav_core2 GlobalPlanner interface...
nav_grid_pub_sub::ScaleGridPublisher< float > potential_pub_
pluginlib::ClassLoader< Traceback > traceback_loader_
std::shared_ptr< CostInterpreter > Ptr
virtual bool shouldReturnNewPath(const nav_2d_msgs::Path2D &new_path, const double new_path_cost) const
Given a cached path is available and a new path, should the new path be the one returned?
nav_2d_msgs::Path2D makePlan(const nav_2d_msgs::Pose2DStamped &start, const nav_2d_msgs::Pose2DStamped &goal) override
virtual bool isPlanValid(const nav_2d_msgs::Path2D &path) const
Check the costmap for any obstacles on this path.
void initialize(const ros::NodeHandle &parent, const std::string &name, TFListenerPtr tf, nav_core2::Costmap::Ptr costmap) override
std::shared_ptr< Costmap > Ptr
std::shared_ptr< tf::TransformListener > TFListenerPtr


dlux_global_planner
Author(s):
autogenerated on Wed Jun 26 2019 20:06:30