map_grid_visualizer.cpp
Go to the documentation of this file.
1 /*********************************************************************
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2010, Eric Perko
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 Eric Perko 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 OWNER 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 <vector>
37 
38 #include <sensor_msgs/PointCloud2.h>
40 
41 namespace base_local_planner {
43 
44 
45  void MapGridVisualizer::initialize(const std::string& name, std::string frame_id, boost::function<bool (int cx, int cy, float &path_cost, float &goal_cost, float &occ_cost, float &total_cost)> cost_function) {
46  name_ = name;
47  frame_id_ = frame_id;
48  cost_function_ = cost_function;
49 
50  ns_nh_ = ros::NodeHandle("~/" + name_);
51  pub_ = ns_nh_.advertise<sensor_msgs::PointCloud2>("cost_cloud", 1);
52  }
53 
55  sensor_msgs::PointCloud2 cost_cloud;
56  cost_cloud.header.frame_id = frame_id_;
57  cost_cloud.header.stamp = ros::Time::now();
58 
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);
67 
68  unsigned int x_size = costmap_p_->getSizeInCellsX();
69  unsigned int y_size = costmap_p_->getSizeInCellsY();
70  double z_coord = 0.0;
71  double x_coord, y_coord;
72 
73  cloud_mod.resize(x_size * y_size);
74  sensor_msgs::PointCloud2Iterator<float> iter_x(cost_cloud, "x");
75 
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)) {
81  iter_x[0] = x_coord;
82  iter_x[1] = y_coord;
83  iter_x[2] = z_coord;
84  iter_x[3] = path_cost;
85  iter_x[4] = goal_cost;
86  iter_x[5] = occ_cost;
87  iter_x[6] = total_cost;
88  ++iter_x;
89  }
90  }
91  }
92  pub_.publish(cost_cloud);
93  ROS_DEBUG("Cost PointCloud published");
94  }
95 };
point_cloud2_iterator.h
map_grid_visualizer.h
costmap_2d::Costmap2D
costmap_2d::Costmap2D::mapToWorld
void mapToWorld(unsigned int mx, unsigned int my, double &wx, double &wy) const
base_local_planner::MapGridVisualizer::MapGridVisualizer
MapGridVisualizer()
Default constructor.
Definition: map_grid_visualizer.cpp:74
ros::Publisher::publish
void publish(const boost::shared_ptr< M > &message) const
ros::NodeHandle::advertise
Publisher advertise(AdvertiseOptions &ops)
base_local_planner::MapGridVisualizer::pub_
ros::Publisher pub_
Definition: map_grid_visualizer.h:131
sensor_msgs::PointCloud2Iterator
ROS_DEBUG
#define ROS_DEBUG(...)
base_local_planner::MapGridVisualizer::frame_id_
std::string frame_id_
Definition: map_grid_visualizer.h:130
base_local_planner::MapGridVisualizer::name_
std::string name_
The name to get parameters relative to.
Definition: map_grid_visualizer.h:127
costmap_2d::Costmap2D::getSizeInCellsY
unsigned int getSizeInCellsY() const
map_cell.h
base_local_planner::MapGridVisualizer::initialize
void initialize(const std::string &name, std::string frame, boost::function< bool(int cx, int cy, float &path_cost, float &goal_cost, float &occ_cost, float &total_cost)> cost_function)
Initializes the MapGridVisualizer.
Definition: map_grid_visualizer.cpp:77
sensor_msgs::PointCloud2Modifier
base_local_planner::MapGridVisualizer::publishCostCloud
void publishCostCloud(const costmap_2d::Costmap2D *costmap_p_)
Build and publish a PointCloud if the publish_cost_grid_pc parameter was true. Only include points fo...
Definition: map_grid_visualizer.cpp:86
costmap_2d::Costmap2D::getSizeInCellsX
unsigned int getSizeInCellsX() const
base_local_planner
Definition: costmap_model.h:44
base_local_planner::MapGridVisualizer::cost_function_
boost::function< bool(int cx, int cy, float &path_cost, float &goal_cost, float &occ_cost, float &total_cost)> cost_function_
The function to be used to generate the cost components for the output PointCloud.
Definition: map_grid_visualizer.h:128
base_local_planner::MapGridVisualizer::ns_nh_
ros::NodeHandle ns_nh_
Definition: map_grid_visualizer.h:129
ros::NodeHandle
ros::Time::now
static Time now()


base_local_planner
Author(s): Eitan Marder-Eppstein, Eric Perko, contradict@gmail.com
autogenerated on Mon Mar 6 2023 03:50:24