local_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 
39 #include <nav_2d_utils/tf_help.h>
40 #include <nav_core2/exceptions.h>
42 #include <string>
43 #include <vector>
44 
45 namespace nav_core_adapter
46 {
47 
49  planner_loader_("nav_core2", "nav_core2::LocalPlanner")
50 {
51 }
52 
57 {
58  tf_ = createSharedPointerWithNoDelete<tf::TransformListener>(tf);
59  costmap_ros_ = costmap_ros;
60  costmap_adapter_ = std::make_shared<CostmapAdapter>();
61  costmap_adapter_->initialize(costmap_ros);
62 
63  ros::NodeHandle nh;
64  ros::NodeHandle private_nh("~");
65  ros::NodeHandle adapter_nh("~/" + name);
66  std::string planner_name;
67  adapter_nh.param("planner_name", planner_name, std::string("dwb_local_planner::DWBLocalPlanner"));
68  ROS_INFO_NAMED("LocalPlannerAdapter", "Loading plugin %s", planner_name.c_str());
69  planner_ = planner_loader_.createInstance(planner_name);
70  planner_->initialize(private_nh, planner_loader_.getName(planner_name), tf_, costmap_adapter_);
71  has_active_goal_ = false;
72 
73  odom_sub_ = std::make_shared<nav_2d_utils::OdomSubscriber>(nh);
74 }
75 
79 bool LocalPlannerAdapter::computeVelocityCommands(geometry_msgs::Twist& cmd_vel)
80 {
81  if (!has_active_goal_)
82  {
83  return false;
84  }
85 
86  // Get the Pose
87  nav_2d_msgs::Pose2DStamped pose2d;
88  if (!getRobotPose(pose2d))
89  {
90  return false;
91  }
92 
93  // Get the Velocity
94  nav_2d_msgs::Twist2D velocity = odom_sub_->getTwist();
95 
96  nav_2d_msgs::Twist2DStamped cmd_vel_2d;
97  try
98  {
99  cmd_vel_2d = planner_->computeVelocityCommands(pose2d, velocity);
100  }
101  catch (const nav_core2::PlannerException& e)
102  {
103  ROS_ERROR_NAMED("LocalPlannerAdapter", "computeVelocityCommands exception: %s", e.what());
104  return false;
105  }
106  cmd_vel = nav_2d_utils::twist2Dto3D(cmd_vel_2d.velocity);
107  return true;
108 }
109 
114 {
115  // Get the Pose
116  nav_2d_msgs::Pose2DStamped pose2d;
117  if (!getRobotPose(pose2d))
118  return false;
119 
120  nav_2d_msgs::Twist2D velocity = odom_sub_->getTwist();
121  bool ret = planner_->isGoalReached(pose2d, velocity);
122  if (ret)
123  {
124  has_active_goal_ = false;
125  }
126  return ret;
127 }
128 
132 bool LocalPlannerAdapter::setPlan(const std::vector<geometry_msgs::PoseStamped>& orig_global_plan)
133 {
134  nav_2d_msgs::Path2D path = nav_2d_utils::posesToPath2D(orig_global_plan);
135  try
136  {
137  if (path.poses.size() > 0)
138  {
139  nav_2d_msgs::Pose2DStamped goal_pose;
140  goal_pose.header = path.header;
141  goal_pose.pose = path.poses.back();
142 
143  if (!has_active_goal_ || hasGoalChanged(goal_pose))
144  {
145  last_goal_ = goal_pose;
146  has_active_goal_ = true;
147  planner_->setGoalPose(goal_pose);
148  }
149  }
150 
151  planner_->setPlan(path);
152  return true;
153  }
154  catch (const nav_core2::PlannerException& e)
155  {
156  ROS_ERROR_NAMED("LocalPlannerAdapter", "setPlan Exception: %s", e.what());
157  return false;
158  }
159 }
160 
161 bool LocalPlannerAdapter::hasGoalChanged(const nav_2d_msgs::Pose2DStamped& new_goal)
162 {
163  if (last_goal_.header.frame_id != new_goal.header.frame_id)
164  {
165  return true;
166  }
167 
168  return last_goal_.pose.x != new_goal.pose.x || last_goal_.pose.y != new_goal.pose.y ||
169  last_goal_.pose.theta != new_goal.pose.theta;
170 }
171 
172 bool LocalPlannerAdapter::getRobotPose(nav_2d_msgs::Pose2DStamped& pose2d)
173 {
174  tf::Stamped<tf::Pose> current_pose;
175  if (!costmap_ros_->getRobotPose(current_pose))
176  {
177  ROS_ERROR_NAMED("LocalPlannerAdapter", "Could not get robot pose");
178  return false;
179  }
180  pose2d = nav_2d_utils::stampedPoseToPose2D(current_pose);
181  return true;
182 }
183 
184 } // namespace nav_core_adapter
185 
186 // register this planner as a BaseLocalPlanner plugin
bool hasGoalChanged(const nav_2d_msgs::Pose2DStamped &new_goal)
See if the back of the global plan matches the most recent goal pose.
#define ROS_INFO_NAMED(name,...)
std::shared_ptr< CostmapAdapter > costmap_adapter_
bool getRobotPose(tf::Stamped< tf::Pose > &global_pose) const
std::shared_ptr< nav_2d_utils::OdomSubscriber > odom_sub_
helper class for subscribing to odometry
bool isGoalReached() override
Collect the additional information needed by nav_core2 and call the child isGoalReached.
PLUGINLIB_EXPORT_CLASS(BAGReader, nodelet::Nodelet)
bool computeVelocityCommands(geometry_msgs::Twist &cmd_vel) override
Collect the additional information needed by nav_core2 and call the child computeVelocityCommands.
geometry_msgs::Twist twist2Dto3D(const nav_2d_msgs::Twist2D &cmd_vel_2d)
nav_2d_msgs::Path2D posesToPath2D(const std::vector< geometry_msgs::PoseStamped > &poses)
bool getRobotPose(nav_2d_msgs::Pose2DStamped &pose2d)
Get the robot pose from the costmap and store as Pose2DStamped.
used for employing a nav_core2 local planner (such as dwb) as a nav_core plugin, like in move_base...
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::Pose2DStamped stampedPoseToPose2D(const tf::Stamped< tf::Pose > &pose)
bool setPlan(const std::vector< geometry_msgs::PoseStamped > &plan) override
Convert from 2d to 3d and call child setPlan.
#define ROS_ERROR_NAMED(name,...)
void initialize(std::string name, tf::TransformListener *tf, costmap_2d::Costmap2DROS *costmap_ros) override
Load the nav_core2 local planner and initialize it.
boost::shared_ptr< nav_core2::LocalPlanner > planner_
pluginlib::ClassLoader< nav_core2::LocalPlanner > planner_loader_


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