voxel_markers.cpp
Go to the documentation of this file.
1 /*********************************************************************
2  *
3  * Software License Agreement (BSD License)
4  *
5  * Copyright (c) 2008, 2013, Willow Garage, Inc.
6  * All rights reserved.
7  *
8  * Redistribution and use in source and binary forms, with or without
9  * modification, are permitted provided that the following conditions
10  * are met:
11  *
12  * * Redistributions of source code must retain the above copyright
13  * notice, this list of conditions and the following disclaimer.
14  * * Redistributions in binary form must reproduce the above
15  * copyright notice, this list of conditions and the following
16  * disclaimer in the documentation and/or other materials provided
17  * with the distribution.
18  * * Neither the name of Willow Garage, Inc. nor the names of its
19  * contributors may be used to endorse or promote products derived
20  * from this software without specific prior written permission.
21  *
22  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
23  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
24  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
25  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
26  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
27  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
28  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
29  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
30  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
31  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
32  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
33  * POSSIBILITY OF SUCH DAMAGE.
34  *
35  * Author: Eitan Marder-Eppstein
36  * David V. Lu!!
37  *********************************************************************/
38 
44 #include <ros/ros.h>
45 #include <visualization_msgs/MarkerArray.h>
46 #include <costmap_2d/VoxelGrid.h>
47 #include <voxel_grid/voxel_grid.h>
48 
49 struct Cell
50 {
51  double x;
52  double y;
53  double z;
55 };
56 typedef std::vector<Cell> V_Cell;
57 
58 float g_colors_r[] = {0.0f, 1.0f, 1.0f};
59 float g_colors_g[] = {1.0f, 1.0f, 0.0f};
60 float g_colors_b[] = {1.0f, 1.0f, 0.0f};
61 float g_colors_a[] = {0.5f, 0.1f, 0.5f};
62 
63 std::string g_marker_ns;
66 void voxelCallback(const ros::Publisher& pub, const costmap_2d::VoxelGridConstPtr& grid)
67 {
68  if (grid->data.empty())
69  {
70  ROS_ERROR("Received empty voxel grid");
71  return;
72  }
73 
75 
76  ROS_DEBUG("Received voxel grid");
77  const std::string frame_id = grid->header.frame_id;
78  const ros::Time stamp = grid->header.stamp;
79  const uint32_t* data = &grid->data.front();
80  const double x_origin = grid->origin.x;
81  const double y_origin = grid->origin.y;
82  const double z_origin = grid->origin.z;
83  const double x_res = grid->resolutions.x;
84  const double y_res = grid->resolutions.y;
85  const double z_res = grid->resolutions.z;
86  const uint32_t x_size = grid->size_x;
87  const uint32_t y_size = grid->size_y;
88  const uint32_t z_size = grid->size_z;
89 
90  g_cells.clear();
91  uint32_t num_markers = 0;
92  for (uint32_t y_grid = 0; y_grid < y_size; ++y_grid)
93  {
94  for (uint32_t x_grid = 0; x_grid < x_size; ++x_grid)
95  {
96  for (uint32_t z_grid = 0; z_grid < z_size; ++z_grid)
97  {
98  voxel_grid::VoxelStatus status = voxel_grid::VoxelGrid::getVoxel(x_grid, y_grid, z_grid, x_size, y_size, z_size,
99  data);
100 
101  if (status == (voxel_grid::VoxelStatus)g_cell_type)
102  {
103  Cell c;
104  c.status = status;
105  c.x = x_origin + (x_grid + 0.5) * x_res;
106  c.y = y_origin + (y_grid + 0.5) * y_res;
107  c.z = z_origin + (z_grid + 0.5) * z_res;
108  g_cells.push_back(c);
109 
110  ++num_markers;
111  }
112  }
113  }
114  }
115 
116  visualization_msgs::Marker m;
117  m.header.frame_id = frame_id;
118  m.header.stamp = stamp;
119  m.ns = g_marker_ns;
120  m.id = 0;
121  m.type = visualization_msgs::Marker::CUBE_LIST;
122  m.action = visualization_msgs::Marker::ADD;
123  m.pose.orientation.w = 1.0;
124  m.scale.x = x_res;
125  m.scale.y = y_res;
126  m.scale.z = z_res;
127  m.color.r = g_colors_r[g_cell_type];
128  m.color.g = g_colors_g[g_cell_type];
129  m.color.b = g_colors_b[g_cell_type];
130  m.color.a = g_colors_a[g_cell_type];
131  m.points.resize(num_markers);
132  for (uint32_t i = 0; i < num_markers; ++i)
133  {
134  Cell& c = g_cells[i];
135  geometry_msgs::Point& p = m.points[i];
136  p.x = c.x;
137  p.y = c.y;
138  p.z = c.z;
139  }
140 
141  pub.publish(m);
142 
144  ROS_DEBUG("Published %d markers in %f seconds", num_markers, (end - start).toSec());
145 }
146 
149 void connectCb()
150 {
151  ros::NodeHandle n;
152  sub = n.subscribe < costmap_2d::VoxelGrid > ("voxel_grid", 1, boost::bind(voxelCallback, pub, _1));
153 }
154 
156 {
157  if(pub.getNumSubscribers()==0)
158  sub.shutdown();
159 }
160 
161 int main(int argc, char** argv)
162 {
163  ros::init(argc, argv, "3d_markers");
164  ros::NodeHandle n;
165  ros::NodeHandle pnh("~");
166 
167  pnh.param("cell_type", g_cell_type, (int)voxel_grid::MARKED);
168  pnh.param("r", g_colors_r[g_cell_type], g_colors_r[g_cell_type]);
169  pnh.param("g", g_colors_g[g_cell_type], g_colors_g[g_cell_type]);
170  pnh.param("b", g_colors_b[g_cell_type], g_colors_b[g_cell_type]);
171  pnh.param("a", g_colors_a[g_cell_type], g_colors_a[g_cell_type]);
172 
173  ROS_DEBUG("Startup");
174 
175  ros::SubscriberStatusCallback connect_cb = boost::bind(connectCb);
176  ros::SubscriberStatusCallback disconnect_cb = boost::bind(disconnectCb);
177 
178  pub = n.advertise < visualization_msgs::Marker > ("visualization_marker", 1, connect_cb, disconnect_cb);
179  g_marker_ns = n.resolveName("voxel_grid");
180 
181  ros::spin();
182 }
std::string g_marker_ns
voxel_grid::VoxelStatus status
boost::function< void(const SingleSubscriberPublisher &)> SubscriberStatusCallback
std::vector< Cell > V_Cell
void publish(const boost::shared_ptr< M > &message) const
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
std::string resolveName(const std::string &name, bool remap=true) const
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
int main(int argc, char **argv)
std::vector< Cell > V_Cell
void connectCb()
VoxelStatus getVoxel(unsigned int x, unsigned int y, unsigned int z)
float g_colors_a[]
ROSCPP_DECL void spin(Spinner &spinner)
int g_cell_type
float g_colors_r[]
float g_colors_g[]
ros::Publisher pub
bool param(const std::string &param_name, T &param_val, const T &default_val) const
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
ros::Subscriber sub
V_Cell g_cells
void voxelCallback(const ros::Publisher &pub, const costmap_2d::VoxelGridConstPtr &grid)
double x
detail::uint32 uint32_t
double z
uint32_t getNumSubscribers() const
static WallTime now()
float g_colors_b[]
#define ROS_ERROR(...)
void disconnectCb()
#define ROS_DEBUG(...)
double y


rtabmap_ros
Author(s): Mathieu Labbe
autogenerated on Mon Dec 14 2020 03:42:19