debug_dwb_local_planner.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 
36 #include <nav_2d_utils/tf_help.h>
37 #include <nav_core2/exceptions.h>
39 #include <string>
40 
41 namespace dwb_local_planner
42 {
43 
44 void DebugDWBLocalPlanner::initialize(const ros::NodeHandle& parent, const std::string& name,
46 {
47  DWBLocalPlanner::initialize(parent, name, tf, costmap);
48 
49  debug_service_ = planner_nh_.advertiseService("debug_local_plan",
53  score_service_ = planner_nh_.advertiseService("score_trajectory",
55  critic_service_ = planner_nh_.advertiseService("get_critic_score",
59 }
60 
61 bool DebugDWBLocalPlanner::generateTwistsService(dwb_msgs::GenerateTwists::Request &req,
62  dwb_msgs::GenerateTwists::Response &res)
63 {
64  res.twists = traj_generator_->getTwists(req.current_vel);
65  return true;
66 }
67 
68 bool DebugDWBLocalPlanner::generateTrajectoryService(dwb_msgs::GenerateTrajectory::Request &req,
69  dwb_msgs::GenerateTrajectory::Response &res)
70 {
71  res.traj = traj_generator_->generateTrajectory(req.start_pose, req.start_vel, req.cmd_vel);
72  return true;
73 }
74 
75 bool DebugDWBLocalPlanner::scoreTrajectoryService(dwb_msgs::ScoreTrajectory::Request &req,
76  dwb_msgs::ScoreTrajectory::Response &res)
77 {
78  if (req.goal.header.frame_id != "")
79  setGoalPose(req.goal);
80  if (req.global_plan.poses.size() > 0)
81  setPlan(req.global_plan);
82 
83  prepare(req.pose, req.velocity);
84  res.score = scoreTrajectory(req.traj);
85  return true;
86 }
87 
89 {
90  for (TrajectoryCritic::Ptr critic : critics_)
91  {
92  if (critic->getName() == name)
93  return critic;
94  }
95  return nullptr;
96 }
97 
98 bool DebugDWBLocalPlanner::getCriticScoreService(dwb_msgs::GetCriticScore::Request &req,
99  dwb_msgs::GetCriticScore::Response &res)
100 {
101  TrajectoryCritic::Ptr critic = getCritic(req.critic_name);
102  if (critic == nullptr)
103  {
104  ROS_WARN_NAMED("DebugDWBLocalPlanner", "Critic %s not found!", req.critic_name.c_str());
105  return false;
106  }
107  if (req.goal.header.frame_id != "")
108  setGoalPose(req.goal);
109  if (req.global_plan.poses.size() > 0)
110  setPlan(req.global_plan);
111 
112  // This prepares all the critics, even though we only need to prepare the one
113  prepare(req.pose, req.velocity);
114 
115  res.score.raw_score = critic->scoreTrajectory(req.traj);
116  res.score.scale = critic->getScale();
117  res.score.name = req.critic_name;
118 
120 
121  return true;
122 }
123 
124 bool DebugDWBLocalPlanner::debugLocalPlanService(dwb_msgs::DebugLocalPlan::Request &req,
125  dwb_msgs::DebugLocalPlan::Response &res)
126 {
127  if (req.goal.header.frame_id != "")
128  setGoalPose(req.goal);
129  if (req.global_plan.poses.size() > 0)
130  setPlan(req.global_plan);
131  std::shared_ptr<dwb_msgs::LocalPlanEvaluation> results = std::make_shared<dwb_msgs::LocalPlanEvaluation>();
132  try
133  {
134  computeVelocityCommands(req.pose, req.velocity, results);
135  res.results = *results;
136  return true;
137  }
138  catch (const nav_core2::PlannerException& e)
139  {
140  ROS_ERROR_NAMED("DebugDWBLocalPlanner", "Exception in computeVelocityCommands: %s", e.what());
141  return false;
142  }
143 }
144 
145 } // namespace dwb_local_planner
146 
147 
148 // register this planner as a LocalPlanner plugin
bool generateTwistsService(dwb_msgs::GenerateTwists::Request &req, dwb_msgs::GenerateTwists::Response &res)
bool generateTrajectoryService(dwb_msgs::GenerateTrajectory::Request &req, dwb_msgs::GenerateTrajectory::Response &res)
void publishCostGrid(const nav_core2::Costmap::Ptr costmap, const std::vector< TrajectoryCritic::Ptr > critics)
Definition: publisher.cpp:161
TrajectoryCritic::Ptr getCritic(std::string name)
#define ROS_WARN_NAMED(name,...)
std::shared_ptr< dwb_local_planner::TrajectoryCritic > Ptr
TrajectoryGenerator::Ptr traj_generator_
virtual void prepare(const nav_2d_msgs::Pose2DStamped &pose, const nav_2d_msgs::Twist2D &velocity)
Helper method for preparing for the core scoring algorithm.
ServiceServer advertiseService(const std::string &service, bool(T::*srv_func)(MReq &, MRes &), T *obj)
bool scoreTrajectoryService(dwb_msgs::ScoreTrajectory::Request &req, dwb_msgs::ScoreTrajectory::Response &res)
void initialize(const ros::NodeHandle &parent, const std::string &name, TFListenerPtr tf, nav_core2::Costmap::Ptr costmap) override
nav_core2 initialization
nav_2d_msgs::Twist2DStamped computeVelocityCommands(const nav_2d_msgs::Pose2DStamped &pose, const nav_2d_msgs::Twist2D &velocity) override
nav_core2 computeVelocityCommands - calculates the best command given the current pose and velocity ...
bool debugLocalPlanService(dwb_msgs::DebugLocalPlan::Request &req, dwb_msgs::DebugLocalPlan::Response &res)
bool getCriticScoreService(dwb_msgs::GetCriticScore::Request &req, dwb_msgs::GetCriticScore::Response &res)
void setPlan(const nav_2d_msgs::Path2D &path) override
nav_core2 setPlan - Sets the global plan
void initialize(const ros::NodeHandle &parent, const std::string &name, TFListenerPtr tf, nav_core2::Costmap::Ptr costmap) override
Override the DWB constructor to also advertise the services.
#define ROS_ERROR_NAMED(name,...)
A version of DWBLocalPlanner with ROS services for the major components.
std::vector< TrajectoryCritic::Ptr > critics_
std::shared_ptr< Costmap > Ptr
std::shared_ptr< tf::TransformListener > TFListenerPtr
#define PLUGINLIB_EXPORT_CLASS(class_type, base_class_type)
virtual dwb_msgs::TrajectoryScore scoreTrajectory(const dwb_msgs::Trajectory2D &traj, double best_score=-1)
Score a given command. Can be used for testing.
void setGoalPose(const nav_2d_msgs::Pose2DStamped &goal_pose) override
nav_core2 setGoalPose - Sets the global goal pose


dwb_local_planner
Author(s): David V. Lu!!
autogenerated on Wed Jun 26 2019 20:06:13