humanoid_planner_2d.cpp
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 #include <ros/ros.h>
31 
33 public:
35  ros::NodeHandle nh;
36 
37  map_sub_ = nh.subscribe<nav_msgs::OccupancyGrid>("map", 1, &SBPLPlanner2D::mapCallback, &planner_);
38  goal_sub_ = nh.subscribe<geometry_msgs::PoseStamped>("goal", 1, &SBPLPlanner2D::goalCallback, &planner_);
39  start_sub_ = nh.subscribe<geometry_msgs::PoseWithCovarianceStamped>("initialpose", 1, &SBPLPlanner2D::startCallback, &planner_);
40 
41  }
42 
43  virtual ~SBPLPlanner2DNode(){}
44 
45 protected:
48 
49 
50 };
51 
52 int main(int argc, char** argv){
53  ros::init(argc, argv, "humanoid_planner_2d");
54 
55  SBPLPlanner2DNode planner;
56 
57  ros::spin();
58 
59  return 0;
60 }
void goalCallback(const geometry_msgs::PoseStampedConstPtr &goal)
Set goal and plan when start was already set.
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
ros::Subscriber goal_sub_
void mapCallback(const nav_msgs::OccupancyGridConstPtr &occupancy_map)
calls updateMap()
ROSCPP_DECL void spin()
ros::Subscriber start_sub_
void startCallback(const geometry_msgs::PoseWithCovarianceStampedConstPtr &start)
Set start and plan when goal was already set.
ros::Subscriber map_sub_
int main(int argc, char **argv)


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