SBPLPlanner2D.h
Go to the documentation of this file.
1 /*
2  * Copyright 2013 Armin Hornung, University of Freiburg
3  *
4  * Redistribution and use in source and binary forms, with or without
5  * modification, are permitted provided that the following conditions are met:
6  *
7  * * Redistributions of source code must retain the above copyright
8  * notice, this list of conditions and the following disclaimer.
9  * * Redistributions in binary form must reproduce the above copyright
10  * notice, this list of conditions and the following disclaimer in the
11  * documentation and/or other materials provided with the distribution.
12  * * Neither the name of the University of Freiburg nor the names of its
13  * contributors may be used to endorse or promote products derived from
14  * this software without specific prior written permission.
15  *
16  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
17  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
18  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
19  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
20  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
21  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
22  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
23  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
24  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
25  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
26  * POSSIBILITY OF SUCH DAMAGE.
27  */
28 
29 #ifndef HUMANOID_PLANNER_2D_SBPL_2D_PLANNER_
30 #define HUMANOID_PLANNER_2D_SBPL_2D_PLANNER_
31 
32 #include <ros/ros.h>
33 #include <geometry_msgs/PoseStamped.h>
34 #include <geometry_msgs/PoseWithCovarianceStamped.h>
35 #include <sbpl/headers.h>
36 #include <visualization_msgs/Marker.h>
37 #include <nav_msgs/Path.h>
38 #include <gridmap_2d/GridMap2D.h>
39 
40 
42 public:
43  SBPLPlanner2D();
44  virtual ~SBPLPlanner2D();
46  void goalCallback(const geometry_msgs::PoseStampedConstPtr& goal);
48  void startCallback(const geometry_msgs::PoseWithCovarianceStampedConstPtr& start);
50  void mapCallback(const nav_msgs::OccupancyGridConstPtr& occupancy_map);
53 
54  gridmap_2d::GridMap2DPtr getMap() const { return map_;};
55 
64  bool plan(const geometry_msgs::Pose& start, const geometry_msgs::Pose& goal);
65 
72  bool plan(double startX, double startY, double goalX, double goalY);
73 
75  inline double getPathCosts() const{return path_costs_;};
76 
77  inline const nav_msgs::Path& getPath() const{return path_;};
78  inline double getRobotRadius() const{return robot_radius_;};
79 
80 protected:
81  bool plan();
82  void setPlanner();
89 
90  std::string planner_type_;
95  double robot_radius_;
96 
98  geometry_msgs::Pose start_pose_, goal_pose_;
99  nav_msgs::Path path_;
100  double path_costs_;
101 
102  static const unsigned char OBSTACLE_COST = 20;
103 
104 };
105 
106 #endif
nav_msgs::Path path_
Definition: SBPLPlanner2D.h:99
ROSCPP_DECL void start()
void goalCallback(const geometry_msgs::PoseStampedConstPtr &goal)
Set goal and plan when start was already set.
geometry_msgs::Pose goal_pose_
Definition: SBPLPlanner2D.h:98
const nav_msgs::Path & getPath() const
Definition: SBPLPlanner2D.h:77
bool forward_search_
Definition: SBPLPlanner2D.h:94
ros::Subscriber map_sub_
Definition: SBPLPlanner2D.h:84
virtual ~SBPLPlanner2D()
double robot_radius_
Definition: SBPLPlanner2D.h:95
ros::Subscriber goal_sub_
Definition: SBPLPlanner2D.h:84
double initial_epsilon_
Definition: SBPLPlanner2D.h:92
ros::Publisher path_pub_
Definition: SBPLPlanner2D.h:85
ros::Subscriber start_sub_
Definition: SBPLPlanner2D.h:84
bool search_until_first_solution_
Definition: SBPLPlanner2D.h:93
gridmap_2d::GridMap2DPtr getMap() const
Definition: SBPLPlanner2D.h:54
double allocated_time_
Definition: SBPLPlanner2D.h:91
void setPlanner()
(re)sets the planner
static const unsigned char OBSTACLE_COST
void mapCallback(const nav_msgs::OccupancyGridConstPtr &occupancy_map)
calls updateMap()
std::string planner_type_
Definition: SBPLPlanner2D.h:90
bool start_received_
Definition: SBPLPlanner2D.h:97
bool updateMap(gridmap_2d::GridMap2DPtr map)
Setup the internal map representation and initialize the SBPL planning environment.
boost::shared_ptr< EnvironmentNAV2D > planner_environment_
Definition: SBPLPlanner2D.h:87
boost::shared_ptr< SBPLPlanner > planner_
Definition: SBPLPlanner2D.h:86
double path_costs_
void startCallback(const geometry_msgs::PoseWithCovarianceStampedConstPtr &start)
Set start and plan when goal was already set.
geometry_msgs::Pose start_pose_
Definition: SBPLPlanner2D.h:98
gridmap_2d::GridMap2DPtr map_
Definition: SBPLPlanner2D.h:88
ros::NodeHandle nh_
Definition: SBPLPlanner2D.h:83
double getRobotRadius() const
Definition: SBPLPlanner2D.h:78
double getPathCosts() const
Definition: SBPLPlanner2D.h:75


humanoid_planner_2d
Author(s): Armin Hornung
autogenerated on Mon Jun 10 2019 13:38:35