38 #include <sensor_msgs/PointCloud2.h>
39 #include <sensor_msgs/point_cloud2_iterator.h>
51 pub_ =
ns_nh_.advertise<sensor_msgs::PointCloud2>(
"cost_cloud", 1);
55 sensor_msgs::PointCloud2 cost_cloud;
57 cost_cloud.header.stamp = ros::Time::now();
59 sensor_msgs::PointCloud2Modifier cloud_mod(cost_cloud);
60 cloud_mod.setPointCloud2Fields(7,
"x", 1, sensor_msgs::PointField::FLOAT32,
61 "y", 1, sensor_msgs::PointField::FLOAT32,
62 "z", 1, sensor_msgs::PointField::FLOAT32,
63 "path_cost", 1, sensor_msgs::PointField::FLOAT32,
64 "goal_cost", 1, sensor_msgs::PointField::FLOAT32,
65 "occ_cost", 1, sensor_msgs::PointField::FLOAT32,
66 "total_cost", 1, sensor_msgs::PointField::FLOAT32);
71 double x_coord, y_coord;
73 cloud_mod.resize(x_size * y_size);
74 sensor_msgs::PointCloud2Iterator<float> iter_x(cost_cloud,
"x");
76 float path_cost, goal_cost, occ_cost, total_cost;
77 for (
unsigned int cx = 0; cx < x_size; cx++) {
78 for (
unsigned int cy = 0; cy < y_size; cy++) {
79 costmap_p_->
mapToWorld(cx, cy, x_coord, y_coord);
80 if (
cost_function_(cx, cy, path_cost, goal_cost, occ_cost, total_cost)) {
84 iter_x[3] = path_cost;
85 iter_x[4] = goal_cost;
87 iter_x[6] = total_cost;
92 pub_.publish(cost_cloud);
93 ROS_DEBUG(
"Cost PointCloud published");