publisher.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  */
36 #include <visualization_msgs/Marker.h>
37 #include <visualization_msgs/MarkerArray.h>
38 #include <sensor_msgs/PointCloud2.h>
41 #include <vector>
42 
43 namespace dwb_local_planner
44 {
45 
47 {
48  ros::NodeHandle global_nh;
49  // Load Publishers
50  nh.param("publish_evaluation", publish_evaluation_, true);
52  eval_pub_ = nh.advertise<dwb_msgs::LocalPlanEvaluation>("evaluation", 1);
53 
54  nh.param("publish_input_params", publish_input_params_, true);
56  {
57  info_pub_ = nh.advertise<nav_2d_msgs::NavGridInfo>("info", 1);
58  pose_pub_ = nh.advertise<geometry_msgs::Pose2D>("pose", 1);
59  goal_pub_ = nh.advertise<geometry_msgs::Pose2D>("goal", 1);
60  velocity_pub_ = nh.advertise<nav_2d_msgs::Twist2D>("velocity", 1);
61  }
62 
63  nh.param("publish_global_plan", publish_global_plan_, true);
65  global_pub_ = nh.advertise<nav_msgs::Path>("global_plan", 1);
66 
67  nh.param("publish_transformed_plan", publish_transformed_, true);
69  transformed_pub_ = nh.advertise<nav_msgs::Path>("transformed_global_plan", 1);
70 
71  nh.param("publish_local_plan", publish_local_plan_, true);
73  local_pub_ = nh.advertise<nav_msgs::Path>("local_plan", 1);
74 
75  nh.param("publish_trajectories", publish_trajectories_, true);
77  marker_pub_ = global_nh.advertise<visualization_msgs::MarkerArray>("marker", 1);
78  double marker_lifetime;
79  nh.param("marker_lifetime", marker_lifetime, 0.1);
80  marker_lifetime_ = ros::Duration(marker_lifetime);
81 
82  nh.param("publish_cost_grid_pc", publish_cost_grid_pc_, false);
84  cost_grid_pc_pub_ = nh.advertise<sensor_msgs::PointCloud2>("cost_cloud", 1);
85 }
86 
87 void DWBPublisher::publishEvaluation(std::shared_ptr<dwb_msgs::LocalPlanEvaluation> results)
88 {
89  if (results == nullptr) return;
91  {
92  eval_pub_.publish(*results);
93  }
94  publishTrajectories(*results);
95 }
96 
97 void DWBPublisher::publishTrajectories(const dwb_msgs::LocalPlanEvaluation& results)
98 {
100  visualization_msgs::MarkerArray ma;
101  visualization_msgs::Marker m;
102 
103  if (results.twists.size() == 0) return;
104 
105  geometry_msgs::Point pt;
106 
107  m.header = results.header;
108  m.type = m.LINE_STRIP;
109  m.pose.orientation.w = 1;
110  m.scale.x = 0.002;
111  m.color.a = 1.0;
112  m.lifetime = marker_lifetime_;
113 
114  double best_cost = results.twists[results.best_index].total,
115  worst_cost = results.twists[results.worst_index].total,
116  denominator = worst_cost - best_cost;
117  if (std::fabs(denominator) < 1e-9)
118  {
119  denominator = 1.0;
120  }
121 
122  for (unsigned int i = 0; i < results.twists.size(); i++)
123  {
124  const dwb_msgs::TrajectoryScore& twist = results.twists[i];
125  if (twist.total >= 0)
126  {
127  m.color.r = 1 - (twist.total - best_cost) / denominator;
128  m.color.g = 1 - (twist.total - best_cost) / denominator;
129  m.color.b = 1;
130  m.ns = "ValidTrajectories";
131  }
132  else
133  {
134  m.color.b = 0;
135  m.ns = "InvalidTrajectories";
136  }
137  m.points.clear();
138  for (unsigned int j = 0; j < twist.traj.poses.size(); ++j)
139  {
140  pt.x = twist.traj.poses[j].x;
141  pt.y = twist.traj.poses[j].y;
142  pt.z = 0;
143  m.points.push_back(pt);
144  }
145  ma.markers.push_back(m);
146  m.id += 1;
147  }
148 
149  marker_pub_.publish(ma);
150 }
151 
152 void DWBPublisher::publishLocalPlan(const std_msgs::Header& header,
153  const dwb_msgs::Trajectory2D& traj)
154 {
155  if (!publish_local_plan_ || local_pub_.getNumSubscribers() == 0) return;
156 
157  nav_msgs::Path path = nav_2d_utils::poses2DToPath(traj.poses, header.frame_id, header.stamp);
158  local_pub_.publish(path);
159 }
160 
162  const std::vector<TrajectoryCritic::Ptr> critics)
163 {
165 
166  const nav_grid::NavGridInfo& info = costmap->getInfo();
167  sensor_msgs::PointCloud cost_grid_pc;
168  cost_grid_pc.header.frame_id = info.frame_id;
169  cost_grid_pc.header.stamp = ros::Time::now();
170 
171  double x_coord, y_coord;
172  unsigned int n = info.width * info.height;
173  cost_grid_pc.points.resize(n);
174  unsigned int i = 0;
175  for (unsigned int cy = 0; cy < info.height; cy++)
176  {
177  for (unsigned int cx = 0; cx < info.width; cx++)
178  {
179  gridToWorld(info, cx, cy, x_coord, y_coord);
180  cost_grid_pc.points[i].x = x_coord;
181  cost_grid_pc.points[i].y = y_coord;
182  i++;
183  }
184  }
185 
186  sensor_msgs::ChannelFloat32 totals;
187  totals.name = "total_cost";
188  totals.values.resize(n);
189 
190  for (TrajectoryCritic::Ptr critic : critics)
191  {
192  unsigned int channel_index = cost_grid_pc.channels.size();
193  critic->addCriticVisualization(cost_grid_pc);
194  if (channel_index == cost_grid_pc.channels.size())
195  {
196  // No channels were added, so skip to next critic
197  continue;
198  }
199  double scale = critic->getScale();
200  for (i = 0; i < n; i++)
201  {
202  totals.values[i] = cost_grid_pc.channels[channel_index].values[i] * scale;
203  }
204  }
205  cost_grid_pc.channels.push_back(totals);
206 
207  sensor_msgs::PointCloud2 cost_grid_pc2;
208  convertPointCloudToPointCloud2(cost_grid_pc, cost_grid_pc2);
209  cost_grid_pc_pub_.publish(cost_grid_pc2);
210 }
211 
212 void DWBPublisher::publishGlobalPlan(const nav_2d_msgs::Path2D plan)
213 {
215 }
216 
217 void DWBPublisher::publishTransformedPlan(const nav_2d_msgs::Path2D plan)
218 {
220 }
221 
222 void DWBPublisher::publishLocalPlan(const nav_2d_msgs::Path2D plan)
223 {
225 }
226 
227 void DWBPublisher::publishGenericPlan(const nav_2d_msgs::Path2D plan, const ros::Publisher pub, bool flag)
228 {
229  if (!flag || pub.getNumSubscribers() == 0) return;
230  nav_msgs::Path path = nav_2d_utils::pathToPath(plan);
231  pub.publish(path);
232 }
233 
234 void DWBPublisher::publishInputParams(const nav_grid::NavGridInfo& info, const geometry_msgs::Pose2D& start_pose,
235  const nav_2d_msgs::Twist2D& velocity, const geometry_msgs::Pose2D& goal_pose)
236 {
237  if (!publish_input_params_) return;
238 
240  pose_pub_.publish(start_pose);
241  goal_pub_.publish(goal_pose);
242  velocity_pub_.publish(velocity);
243 }
244 
245 } // namespace dwb_local_planner
void publishCostGrid(const nav_core2::Costmap::Ptr costmap, const std::vector< TrajectoryCritic::Ptr > critics)
Definition: publisher.cpp:161
void publish(const boost::shared_ptr< M > &message) const
void publishTrajectories(const dwb_msgs::LocalPlanEvaluation &results)
Definition: publisher.cpp:97
std::shared_ptr< dwb_local_planner::TrajectoryCritic > Ptr
void publishGlobalPlan(const nav_2d_msgs::Path2D plan)
Definition: publisher.cpp:212
void publishTransformedPlan(const nav_2d_msgs::Path2D plan)
Definition: publisher.cpp:217
ros::Publisher cost_grid_pc_pub_
Definition: publisher.h:100
nav_2d_msgs::NavGridInfo toMsg(const nav_grid::NavGridInfo &info)
void publishGenericPlan(const nav_2d_msgs::Path2D plan, const ros::Publisher pub, bool flag)
Definition: publisher.cpp:227
nav_2d_msgs::Path2D pathToPath(const nav_msgs::Path &path)
void gridToWorld(const NavGridInfo &info, int mx, int my, double &wx, double &wy)
void publishInputParams(const nav_grid::NavGridInfo &info, const geometry_msgs::Pose2D &start_pose, const nav_2d_msgs::Twist2D &velocity, const geometry_msgs::Pose2D &goal_pose)
Definition: publisher.cpp:234
ros::Duration marker_lifetime_
Definition: publisher.h:97
ros::Publisher transformed_pub_
Definition: publisher.h:100
nav_msgs::Path poses2DToPath(const std::vector< geometry_msgs::Pose2D > &poses, const std::string &frame, const ros::Time &stamp)
bool param(const std::string &param_name, T &param_val, const T &default_val) const
void publishEvaluation(std::shared_ptr< dwb_msgs::LocalPlanEvaluation > results)
If the pointer is not null, publish the evaluation and trajectories as needed.
Definition: publisher.cpp:87
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
void publishLocalPlan(const std_msgs::Header &header, const dwb_msgs::Trajectory2D &traj)
Definition: publisher.cpp:152
uint32_t getNumSubscribers() const
static Time now()
std::shared_ptr< Costmap > Ptr
void initialize(ros::NodeHandle &nh)
Load the parameters and advertise topics as needed.
Definition: publisher.cpp:46


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