exploration_node.cpp
Go to the documentation of this file.
1 //=================================================================================================
2 // Copyright (c) 2012, Stefan Kohlbrecher, TU Darmstadt
3 // All rights reserved.
4 
5 // Redistribution and use in source and binary forms, with or without
6 // modification, are permitted provided that the following conditions are met:
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 Simulation, Systems Optimization and Robotics
13 // group, TU Darmstadt nor the names of its contributors may be used to
14 // endorse or promote products derived from this software without
15 // specific prior written permission.
16 
17 // THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
18 // ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
19 // WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
20 // DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER BE LIABLE FOR ANY
21 // DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
22 // (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
23 // LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
24 // ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
25 // (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
26 // SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
27 //=================================================================================================
28 
29 
30 #include <ros/ros.h>
33 #include <hector_nav_msgs/GetRobotTrajectory.h>
34 
36 {
37 public:
39  {
40  ros::NodeHandle nh;
41 
42  costmap_2d_ros_ = new costmap_2d::Costmap2DROS("global_costmap", tfl_);
43 
45  planner_->initialize("hector_exploration_planner",costmap_2d_ros_);
46 
48 
49  exploration_plan_pub_ = nh.advertise<nav_msgs::Path>("exploration_path",2);
50  }
51 
52  bool explorationServiceCallback(hector_nav_msgs::GetRobotTrajectory::Request &req,
53  hector_nav_msgs::GetRobotTrajectory::Response &res )
54  {
55  ROS_INFO("Exploration Service called");
56 
57  tf::Stamped<tf::Pose> robot_pose_tf;
58  costmap_2d_ros_->getRobotPose(robot_pose_tf);
59 
60  geometry_msgs::PoseStamped pose;
61  tf::poseStampedTFToMsg(robot_pose_tf, pose);
62  planner_->doExploration(pose, res.trajectory.poses);
63  res.trajectory.header.frame_id = "map";
64  res.trajectory.header.stamp = ros::Time::now();
65 
67  {
68  exploration_plan_pub_.publish(res.trajectory);
69  }
70 
71  return true;
72  }
73 
74 protected:
80 
81 };
82 
83 int main(int argc, char **argv) {
84  ros::init(argc, argv, ROS_PACKAGE_NAME);
85 
87 
88  ros::spin();
89 
90  return 0;
91 }
costmap_2d::Costmap2DROS * costmap_2d_ros_
bool explorationServiceCallback(hector_nav_msgs::GetRobotTrajectory::Request &req, hector_nav_msgs::GetRobotTrajectory::Response &res)
void publish(const boost::shared_ptr< M > &message) const
bool getRobotPose(tf::Stamped< tf::Pose > &global_pose) const
ros::Publisher exploration_plan_pub_
static void poseStampedTFToMsg(const Stamped< Pose > &bt, geometry_msgs::PoseStamped &msg)
tf::TransformListener tfl_
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
ServiceServer advertiseService(const std::string &service, bool(T::*srv_func)(MReq &, MRes &), T *obj)
ros::ServiceServer exploration_plan_service_server_
ROSCPP_DECL void spin(Spinner &spinner)
void initialize(std::string name, costmap_2d::Costmap2DROS *costmap_ros)
#define ROS_INFO(...)
int main(int argc, char **argv)
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
uint32_t getNumSubscribers() const
static Time now()
bool doExploration(const geometry_msgs::PoseStamped &start, std::vector< geometry_msgs::PoseStamped > &plan)
hector_exploration_planner::HectorExplorationPlanner * planner_


hector_exploration_node
Author(s):
autogenerated on Mon Jun 10 2019 13:34:44