publisher.cpp
Go to the documentation of this file.
00001 /*
00002  * Software License Agreement (BSD License)
00003  *
00004  *  Copyright (c) 2017, Locus Robotics
00005  *  All rights reserved.
00006  *
00007  *  Redistribution and use in source and binary forms, with or without
00008  *  modification, are permitted provided that the following conditions
00009  *  are met:
00010  *
00011  *   * Redistributions of source code must retain the above copyright
00012  *     notice, this list of conditions and the following disclaimer.
00013  *   * Redistributions in binary form must reproduce the above
00014  *     copyright notice, this list of conditions and the following
00015  *     disclaimer in the documentation and/or other materials provided
00016  *     with the distribution.
00017  *   * Neither the name of the copyright holder nor the names of its
00018  *     contributors may be used to endorse or promote products derived
00019  *     from this software without specific prior written permission.
00020  *
00021  *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00022  *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00023  *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00024  *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00025  *  COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00026  *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00027  *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00028  *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00029  *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00030  *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00031  *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00032  *  POSSIBILITY OF SUCH DAMAGE.
00033  */
00034 #include <dwb_local_planner/publisher.h>
00035 #include <nav_grid/coordinate_conversion.h>
00036 #include <visualization_msgs/Marker.h>
00037 #include <visualization_msgs/MarkerArray.h>
00038 #include <sensor_msgs/PointCloud2.h>
00039 #include <sensor_msgs/point_cloud_conversion.h>
00040 #include <nav_2d_utils/conversions.h>
00041 #include <vector>
00042 
00043 namespace dwb_local_planner
00044 {
00045 
00046 void DWBPublisher::initialize(ros::NodeHandle& nh)
00047 {
00048   ros::NodeHandle global_nh;
00049   // Load Publishers
00050   nh.param("publish_evaluation", publish_evaluation_, true);
00051   if (publish_evaluation_)
00052     eval_pub_ = nh.advertise<dwb_msgs::LocalPlanEvaluation>("evaluation", 1);
00053 
00054   nh.param("publish_input_params", publish_input_params_, true);
00055   if (publish_input_params_)
00056   {
00057     info_pub_ = nh.advertise<nav_2d_msgs::NavGridInfo>("info", 1);
00058     pose_pub_ = nh.advertise<geometry_msgs::Pose2D>("pose", 1);
00059     goal_pub_ = nh.advertise<geometry_msgs::Pose2D>("goal", 1);
00060     velocity_pub_ = nh.advertise<nav_2d_msgs::Twist2D>("velocity", 1);
00061   }
00062 
00063   nh.param("publish_global_plan", publish_global_plan_, true);
00064   if (publish_global_plan_)
00065     global_pub_ = nh.advertise<nav_msgs::Path>("global_plan", 1);
00066 
00067   nh.param("publish_transformed_plan", publish_transformed_, true);
00068   if (publish_transformed_)
00069     transformed_pub_ = nh.advertise<nav_msgs::Path>("transformed_global_plan", 1);
00070 
00071   nh.param("publish_local_plan", publish_local_plan_, true);
00072   if (publish_local_plan_)
00073     local_pub_ = nh.advertise<nav_msgs::Path>("local_plan", 1);
00074 
00075   nh.param("publish_trajectories", publish_trajectories_, true);
00076   if (publish_trajectories_)
00077     marker_pub_ = global_nh.advertise<visualization_msgs::MarkerArray>("marker", 1);
00078   double marker_lifetime;
00079   nh.param("marker_lifetime", marker_lifetime, 0.1);
00080   marker_lifetime_ = ros::Duration(marker_lifetime);
00081 
00082   nh.param("publish_cost_grid_pc", publish_cost_grid_pc_, false);
00083   if (publish_cost_grid_pc_)
00084     cost_grid_pc_pub_ = nh.advertise<sensor_msgs::PointCloud2>("cost_cloud", 1);
00085 }
00086 
00087 void DWBPublisher::publishEvaluation(std::shared_ptr<dwb_msgs::LocalPlanEvaluation> results)
00088 {
00089   if (results == nullptr) return;
00090   if (publish_evaluation_ && eval_pub_.getNumSubscribers() > 0)
00091   {
00092     eval_pub_.publish(*results);
00093   }
00094   publishTrajectories(*results);
00095 }
00096 
00097 void DWBPublisher::publishTrajectories(const dwb_msgs::LocalPlanEvaluation& results)
00098 {
00099   if (!publish_trajectories_ || marker_pub_.getNumSubscribers() == 0) return;
00100   visualization_msgs::MarkerArray ma;
00101   visualization_msgs::Marker m;
00102 
00103   if (results.twists.size() == 0) return;
00104 
00105   geometry_msgs::Point pt;
00106 
00107   m.header = results.header;
00108   m.type = m.LINE_STRIP;
00109   m.pose.orientation.w = 1;
00110   m.scale.x = 0.002;
00111   m.color.a = 1.0;
00112   m.lifetime = marker_lifetime_;
00113 
00114   double best_cost = results.twists[results.best_index].total,
00115          worst_cost = results.twists[results.worst_index].total,
00116          denominator = worst_cost - best_cost;
00117   if (std::fabs(denominator) < 1e-9)
00118   {
00119     denominator = 1.0;
00120   }
00121 
00122   for (unsigned int i = 0; i < results.twists.size(); i++)
00123   {
00124     const dwb_msgs::TrajectoryScore& twist = results.twists[i];
00125     if (twist.total >= 0)
00126     {
00127       m.color.r = 1 - (twist.total - best_cost) / denominator;
00128       m.color.g = 1 - (twist.total - best_cost) / denominator;
00129       m.color.b = 1;
00130       m.ns = "ValidTrajectories";
00131     }
00132     else
00133     {
00134       m.color.b = 0;
00135       m.ns = "InvalidTrajectories";
00136     }
00137     m.points.clear();
00138     for (unsigned int j = 0; j < twist.traj.poses.size(); ++j)
00139     {
00140       pt.x = twist.traj.poses[j].x;
00141       pt.y = twist.traj.poses[j].y;
00142       pt.z = 0;
00143       m.points.push_back(pt);
00144     }
00145     ma.markers.push_back(m);
00146     m.id += 1;
00147   }
00148 
00149   marker_pub_.publish(ma);
00150 }
00151 
00152 void DWBPublisher::publishLocalPlan(const std_msgs::Header& header,
00153                                     const dwb_msgs::Trajectory2D& traj)
00154 {
00155   if (!publish_local_plan_ || local_pub_.getNumSubscribers() == 0) return;
00156 
00157   nav_msgs::Path path = nav_2d_utils::poses2DToPath(traj.poses, header.frame_id, header.stamp);
00158   local_pub_.publish(path);
00159 }
00160 
00161 void DWBPublisher::publishCostGrid(const nav_core2::Costmap::Ptr costmap,
00162                                    const std::vector<TrajectoryCritic::Ptr> critics)
00163 {
00164   if (!publish_cost_grid_pc_ || cost_grid_pc_pub_.getNumSubscribers() == 0) return;
00165 
00166   const nav_grid::NavGridInfo& info = costmap->getInfo();
00167   sensor_msgs::PointCloud cost_grid_pc;
00168   cost_grid_pc.header.frame_id = info.frame_id;
00169   cost_grid_pc.header.stamp = ros::Time::now();
00170 
00171   double x_coord, y_coord;
00172   unsigned int n = info.width * info.height;
00173   cost_grid_pc.points.resize(n);
00174   unsigned int i = 0;
00175   for (unsigned int cy = 0; cy < info.height; cy++)
00176   {
00177     for (unsigned int cx = 0; cx < info.width; cx++)
00178     {
00179       gridToWorld(info, cx, cy, x_coord, y_coord);
00180       cost_grid_pc.points[i].x = x_coord;
00181       cost_grid_pc.points[i].y = y_coord;
00182       i++;
00183     }
00184   }
00185 
00186   sensor_msgs::ChannelFloat32 totals;
00187   totals.name = "total_cost";
00188   totals.values.resize(n);
00189 
00190   for (TrajectoryCritic::Ptr critic : critics)
00191   {
00192     unsigned int channel_index = cost_grid_pc.channels.size();
00193     critic->addCriticVisualization(cost_grid_pc);
00194     if (channel_index == cost_grid_pc.channels.size())
00195     {
00196       // No channels were added, so skip to next critic
00197       continue;
00198     }
00199     double scale = critic->getScale();
00200     for (i = 0; i < n; i++)
00201     {
00202       totals.values[i] = cost_grid_pc.channels[channel_index].values[i] * scale;
00203     }
00204   }
00205   cost_grid_pc.channels.push_back(totals);
00206 
00207   sensor_msgs::PointCloud2 cost_grid_pc2;
00208   convertPointCloudToPointCloud2(cost_grid_pc, cost_grid_pc2);
00209   cost_grid_pc_pub_.publish(cost_grid_pc2);
00210 }
00211 
00212 void DWBPublisher::publishGlobalPlan(const nav_2d_msgs::Path2D plan)
00213 {
00214   publishGenericPlan(plan, global_pub_, publish_global_plan_);
00215 }
00216 
00217 void DWBPublisher::publishTransformedPlan(const nav_2d_msgs::Path2D plan)
00218 {
00219   publishGenericPlan(plan, transformed_pub_, publish_transformed_);
00220 }
00221 
00222 void DWBPublisher::publishLocalPlan(const nav_2d_msgs::Path2D plan)
00223 {
00224   publishGenericPlan(plan, local_pub_, publish_local_plan_);
00225 }
00226 
00227 void DWBPublisher::publishGenericPlan(const nav_2d_msgs::Path2D plan, const ros::Publisher pub, bool flag)
00228 {
00229   if (!flag || pub.getNumSubscribers() == 0) return;
00230   nav_msgs::Path path = nav_2d_utils::pathToPath(plan);
00231   pub.publish(path);
00232 }
00233 
00234 void DWBPublisher::publishInputParams(const nav_grid::NavGridInfo& info, const geometry_msgs::Pose2D& start_pose,
00235                                       const nav_2d_msgs::Twist2D& velocity, const geometry_msgs::Pose2D& goal_pose)
00236 {
00237   if (!publish_input_params_) return;
00238 
00239   info_pub_.publish(nav_2d_utils::toMsg(info));
00240   pose_pub_.publish(start_pose);
00241   goal_pub_.publish(goal_pose);
00242   velocity_pub_.publish(velocity);
00243 }
00244 
00245 }  // namespace dwb_local_planner


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