global_planner_adapter.cpp
Go to the documentation of this file.
1 /*
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2017, 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 
38 #include <nav_2d_utils/tf_help.h>
39 #include <nav_core2/exceptions.h>
41 #include <string>
42 #include <vector>
43 
44 namespace nav_core_adapter
45 {
46 
48  planner_loader_("nav_core2", "nav_core2::GlobalPlanner")
49 {
50 }
51 
55 void GlobalPlannerAdapter::initialize(std::string name, costmap_2d::Costmap2DROS* costmap_ros)
56 {
57  costmap_ros_ = costmap_ros;
58  costmap_adapter_ = std::make_shared<CostmapAdapter>();
59  costmap_adapter_->initialize(costmap_ros);
60 
61  ros::NodeHandle private_nh("~");
62  ros::NodeHandle adapter_nh("~/" + name);
63  std::string planner_name;
64  adapter_nh.param("planner_name", planner_name, std::string("dlux_global_planner::DluxGlobalPlanner"));
65  ROS_INFO_NAMED("GlobalPlannerAdapter", "Loading plugin %s", planner_name.c_str());
66  planner_ = planner_loader_.createInstance(planner_name);
67  planner_->initialize(private_nh, planner_loader_.getName(planner_name), tf_, costmap_adapter_);
68  path_pub_ = private_nh.advertise<nav_msgs::Path>("plan", 1);
69 }
70 
71 bool GlobalPlannerAdapter::makePlan(const geometry_msgs::PoseStamped& start,
72  const geometry_msgs::PoseStamped& goal,
73  std::vector<geometry_msgs::PoseStamped>& plan)
74 {
75  nav_2d_msgs::Pose2DStamped start2d = nav_2d_utils::poseStampedToPose2D(start),
76  goal2d = nav_2d_utils::poseStampedToPose2D(goal);
77  try
78  {
79  nav_2d_msgs::Path2D path2d = planner_->makePlan(start2d, goal2d);
80  nav_msgs::Path path = nav_2d_utils::pathToPath(path2d);
81  plan = path.poses;
82  path_pub_.publish(path);
83  return true;
84  }
86  {
87  ROS_ERROR_NAMED("GlobalPlannerAdapter", "makePlan Exception: %s", e.what());
88  return false;
89  }
90 }
91 } // namespace nav_core_adapter
92 
93 
94 // register this planner as a BaseGlobalPlanner plugin
#define ROS_INFO_NAMED(name,...)
void initialize(std::string name, costmap_2d::Costmap2DROS *costmap_ros) override
Load the nav_core2 global planner and initialize it.
void publish(const boost::shared_ptr< M > &message) const
boost::shared_ptr< nav_core2::GlobalPlanner > planner_
std::shared_ptr< CostmapAdapter > costmap_adapter_
PLUGINLIB_EXPORT_CLASS(BAGReader, nodelet::Nodelet)
nav_2d_msgs::Path2D pathToPath(const nav_msgs::Path &path)
pluginlib::ClassLoader< nav_core2::GlobalPlanner > planner_loader_
bool makePlan(const geometry_msgs::PoseStamped &start, const geometry_msgs::PoseStamped &goal, std::vector< geometry_msgs::PoseStamped > &plan) override
nav_2d_msgs::Pose2DStamped poseStampedToPose2D(const geometry_msgs::PoseStamped &pose)
bool param(const std::string &param_name, T &param_val, const T &default_val) const
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
virtual std::string getName(const std::string &lookup_name)
#define ROS_ERROR_NAMED(name,...)
used for employing a nav_core2 global planner interface as a nav_core plugin, like in move_base...


nav_core_adapter
Author(s):
autogenerated on Wed Jun 26 2019 20:06:25