36 #include <visualization_msgs/Marker.h>
37 #include <visualization_msgs/MarkerArray.h>
38 #include <sensor_msgs/PointCloud2.h>
79 double marker_lifetime;
80 nh.
param(
"marker_lifetime", marker_lifetime, 0.1);
90 if (results ==
nullptr)
return;
101 visualization_msgs::MarkerArray ma;
102 visualization_msgs::Marker m;
104 if (results.twists.size() == 0)
return;
106 geometry_msgs::Point pt;
108 m.header = results.header;
109 m.type = m.LINE_STRIP;
110 m.pose.orientation.w = 1;
115 double best_cost = results.twists[results.best_index].total,
116 worst_cost = results.twists[results.worst_index].total,
117 denominator = worst_cost - best_cost;
118 if (std::fabs(denominator) < 1e-9)
123 for (
unsigned int i = 0; i < results.twists.size(); i++)
125 const dwb_msgs::TrajectoryScore& twist = results.twists[i];
126 if (twist.total >= 0)
128 m.color.r = 1 - (twist.total - best_cost) / denominator;
129 m.color.g = 1 - (twist.total - best_cost) / denominator;
131 m.ns =
"ValidTrajectories";
136 m.ns =
"InvalidTrajectories";
139 for (
unsigned int j = 0; j < twist.traj.poses.size(); ++j)
141 pt.x = twist.traj.poses[j].x;
142 pt.y = twist.traj.poses[j].y;
144 m.points.push_back(pt);
146 ma.markers.push_back(m);
154 const dwb_msgs::Trajectory2D& traj)
163 const std::vector<TrajectoryCritic::Ptr> critics)
168 sensor_msgs::PointCloud cost_grid_pc;
172 double x_coord, y_coord;
174 cost_grid_pc.points.resize(n);
176 for (
unsigned int cy = 0; cy < info.
height; cy++)
178 for (
unsigned int cx = 0; cx < info.
width; cx++)
181 cost_grid_pc.points[i].x = x_coord;
182 cost_grid_pc.points[i].y = y_coord;
187 sensor_msgs::ChannelFloat32 totals;
188 totals.name =
"total_cost";
189 totals.values.resize(n);
193 unsigned int channel_index = cost_grid_pc.channels.size();
194 critic->addCriticVisualization(cost_grid_pc);
195 if (channel_index == cost_grid_pc.channels.size())
200 double scale = critic->getScale();
201 for (i = 0; i < n; i++)
203 totals.values[i] += cost_grid_pc.channels[channel_index].values[i] * scale;
206 cost_grid_pc.channels.push_back(totals);
208 sensor_msgs::PointCloud2 cost_grid_pc2;
209 convertPointCloudToPointCloud2(cost_grid_pc, cost_grid_pc2);
236 const nav_2d_msgs::Twist2D& velocity,
const geometry_msgs::Pose2D& goal_pose)