00001 /* 00002 * Copyright 2013 Armin Hornung, University of Freiburg 00003 * 00004 * Redistribution and use in source and binary forms, with or without 00005 * modification, are permitted provided that the following conditions are met: 00006 * 00007 * * Redistributions of source code must retain the above copyright 00008 * notice, this list of conditions and the following disclaimer. 00009 * * Redistributions in binary form must reproduce the above copyright 00010 * notice, this list of conditions and the following disclaimer in the 00011 * documentation and/or other materials provided with the distribution. 00012 * * Neither the name of the University of Freiburg nor the names of its 00013 * contributors may be used to endorse or promote products derived from 00014 * this software without specific prior written permission. 00015 * 00016 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" 00017 * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE 00018 * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE 00019 * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE 00020 * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR 00021 * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF 00022 * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS 00023 * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN 00024 * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) 00025 * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 00026 * POSSIBILITY OF SUCH DAMAGE. 00027 */ 00028 00029 #include <ros/ros.h> 00030 #include <humanoid_planner_2d/SBPLPlanner2D.h> 00031 00032 class SBPLPlanner2DNode{ 00033 public: 00034 SBPLPlanner2DNode(){ 00035 ros::NodeHandle nh; 00036 00037 map_sub_ = nh.subscribe<nav_msgs::OccupancyGrid>("map", 1, &SBPLPlanner2D::mapCallback, &planner_); 00038 goal_sub_ = nh.subscribe<geometry_msgs::PoseStamped>("goal", 1, &SBPLPlanner2D::goalCallback, &planner_); 00039 start_sub_ = nh.subscribe<geometry_msgs::PoseWithCovarianceStamped>("initialpose", 1, &SBPLPlanner2D::startCallback, &planner_); 00040 00041 } 00042 00043 virtual ~SBPLPlanner2DNode(){} 00044 00045 protected: 00046 SBPLPlanner2D planner_; 00047 ros::Subscriber map_sub_, goal_sub_, start_sub_; 00048 00049 00050 }; 00051 00052 int main(int argc, char** argv){ 00053 ros::init(argc, argv, "humanoid_planner_2d"); 00054 00055 SBPLPlanner2DNode planner; 00056 00057 ros::spin(); 00058 00059 return 0; 00060 }