36 #include <visualization_msgs/Marker.h> 37 #include <visualization_msgs/MarkerArray.h> 38 #include <sensor_msgs/PointCloud2.h> 78 double marker_lifetime;
79 nh.
param(
"marker_lifetime", marker_lifetime, 0.1);
89 if (results ==
nullptr)
return;
100 visualization_msgs::MarkerArray ma;
101 visualization_msgs::Marker m;
103 if (results.twists.size() == 0)
return;
105 geometry_msgs::Point pt;
107 m.header = results.header;
108 m.type = m.LINE_STRIP;
109 m.pose.orientation.w = 1;
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)
122 for (
unsigned int i = 0; i < results.twists.size(); i++)
124 const dwb_msgs::TrajectoryScore& twist = results.twists[i];
125 if (twist.total >= 0)
127 m.color.r = 1 - (twist.total - best_cost) / denominator;
128 m.color.g = 1 - (twist.total - best_cost) / denominator;
130 m.ns =
"ValidTrajectories";
135 m.ns =
"InvalidTrajectories";
138 for (
unsigned int j = 0; j < twist.traj.poses.size(); ++j)
140 pt.x = twist.traj.poses[j].x;
141 pt.y = twist.traj.poses[j].y;
143 m.points.push_back(pt);
145 ma.markers.push_back(m);
153 const dwb_msgs::Trajectory2D& traj)
162 const std::vector<TrajectoryCritic::Ptr> critics)
167 sensor_msgs::PointCloud cost_grid_pc;
171 double x_coord, y_coord;
173 cost_grid_pc.points.resize(n);
175 for (
unsigned int cy = 0; cy < info.
height; cy++)
177 for (
unsigned int cx = 0; cx < info.
width; cx++)
180 cost_grid_pc.points[i].x = x_coord;
181 cost_grid_pc.points[i].y = y_coord;
186 sensor_msgs::ChannelFloat32 totals;
187 totals.name =
"total_cost";
188 totals.values.resize(n);
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())
199 double scale = critic->getScale();
200 for (i = 0; i < n; i++)
202 totals.values[i] = cost_grid_pc.channels[channel_index].values[i] * scale;
205 cost_grid_pc.channels.push_back(totals);
207 sensor_msgs::PointCloud2 cost_grid_pc2;
208 convertPointCloudToPointCloud2(cost_grid_pc, cost_grid_pc2);
235 const nav_2d_msgs::Twist2D& velocity,
const geometry_msgs::Pose2D& goal_pose)
void publishCostGrid(const nav_core2::Costmap::Ptr costmap, const std::vector< TrajectoryCritic::Ptr > critics)
void publish(const boost::shared_ptr< M > &message) const
void publishTrajectories(const dwb_msgs::LocalPlanEvaluation &results)
std::shared_ptr< dwb_local_planner::TrajectoryCritic > Ptr
void publishGlobalPlan(const nav_2d_msgs::Path2D plan)
void publishTransformedPlan(const nav_2d_msgs::Path2D plan)
bool publish_transformed_
ros::Publisher cost_grid_pc_pub_
nav_2d_msgs::NavGridInfo toMsg(const nav_grid::NavGridInfo &info)
ros::Publisher velocity_pub_
void publishGenericPlan(const nav_2d_msgs::Path2D plan, const ros::Publisher pub, bool flag)
bool publish_trajectories_
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)
ros::Publisher local_pub_
ros::Duration marker_lifetime_
ros::Publisher transformed_pub_
bool publish_global_plan_
ros::Publisher global_pub_
nav_msgs::Path poses2DToPath(const std::vector< geometry_msgs::Pose2D > &poses, const std::string &frame, const ros::Time &stamp)
ros::Publisher marker_pub_
bool param(const std::string ¶m_name, T ¶m_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.
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
bool publish_input_params_
void publishLocalPlan(const std_msgs::Header &header, const dwb_msgs::Trajectory2D &traj)
uint32_t getNumSubscribers() const
std::shared_ptr< Costmap > Ptr
void initialize(ros::NodeHandle &nh)
Load the parameters and advertise topics as needed.
bool publish_cost_grid_pc_