global_planner_adapter2.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 <memory>
42 #include <string>
43 #include <vector>
44 
45 namespace nav_core_adapter
46 {
47 
49  planner_loader_("nav_core", "nav_core::BaseGlobalPlanner")
50 {
51 }
52 
56 void GlobalPlannerAdapter2::initialize(const ros::NodeHandle& parent, const std::string& name,
58 {
59  costmap_ = costmap;
60  std::shared_ptr<CostmapAdapter> ptr = std::static_pointer_cast<CostmapAdapter>(costmap);
61 
62  if (!ptr)
63  {
64  ROS_FATAL_NAMED("GlobalPlannerAdapter2",
65  "GlobalPlannerAdapter2 can only be used with the CostmapAdapter, not other Costmaps!");
66  exit(EXIT_FAILURE);
67  }
68  costmap_ros_ = ptr->getCostmap2DROS();
69 
70  ros::NodeHandle planner_nh(parent, name);
71  std::string planner_name;
72  planner_nh.param("planner_name", planner_name, std::string("global_planner/GlobalPlanner"));
73  ROS_INFO_NAMED("GlobalPlannerAdapter2", "Loading plugin %s", planner_name.c_str());
74  planner_ = planner_loader_.createInstance(planner_name);
75  planner_->initialize(planner_loader_.getName(planner_name), costmap_ros_);
76 }
77 
78 nav_2d_msgs::Path2D GlobalPlannerAdapter2::makePlan(const nav_2d_msgs::Pose2DStamped& start,
79  const nav_2d_msgs::Pose2DStamped& goal)
80 {
81  geometry_msgs::PoseStamped start3d = nav_2d_utils::pose2DToPoseStamped(start),
82  goal3d = nav_2d_utils::pose2DToPoseStamped(goal);
83  std::vector<geometry_msgs::PoseStamped> plan;
84  bool ret = planner_->makePlan(start3d, goal3d, plan);
85  if (!ret)
86  {
87  throw nav_core2::PlannerException("Generic Global Planner Error");
88  }
89  return nav_2d_utils::posesToPath2D(plan);
90 }
91 } // namespace nav_core_adapter
92 
93 
94 // register this planner as a GlobalPlanner plugin
#define ROS_INFO_NAMED(name,...)
used for employing a nav_core global planner (such as navfn) as a nav_core2 plugin, like in locomotor.
boost::shared_ptr< nav_core::BaseGlobalPlanner > planner_
pluginlib::ClassLoader< nav_core::BaseGlobalPlanner > planner_loader_
PLUGINLIB_EXPORT_CLASS(BAGReader, nodelet::Nodelet)
void initialize(const ros::NodeHandle &parent, const std::string &name, TFListenerPtr tf, nav_core2::Costmap::Ptr costmap) override
Load the nav_core global planner and initialize it.
nav_2d_msgs::Path2D posesToPath2D(const std::vector< geometry_msgs::PoseStamped > &poses)
geometry_msgs::PoseStamped pose2DToPoseStamped(const nav_2d_msgs::Pose2DStamped &pose2d)
bool param(const std::string &param_name, T &param_val, const T &default_val) const
virtual std::string getName(const std::string &lookup_name)
nav_2d_msgs::Path2D makePlan(const nav_2d_msgs::Pose2DStamped &start, const nav_2d_msgs::Pose2DStamped &goal) override
#define ROS_FATAL_NAMED(name,...)
std::shared_ptr< Costmap > Ptr
std::shared_ptr< tf::TransformListener > TFListenerPtr


nav_core_adapter
Author(s):
autogenerated on Sun Jan 10 2021 04:08:46