octomap_server_contact_nodelet.cpp
Go to the documentation of this file.
1 // -*- mode: c++ -*-
2 /*********************************************************************
3  * Software License Agreement (BSD License)
4  *
5  * Copyright (c) 2015, JSK Lab
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 the JSK Lab 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 
36 #define BOOST_PARAMETER_MAX_ARITY 7
38 #include <algorithm>
39 
40 using namespace octomap;
41 using octomap_msgs::Octomap;
42 
43 namespace jsk_pcl_ros
44 {
45  OctomapServerContact::OctomapServerContact(const ros::NodeHandle &privateNh)
46  : OctomapServer(privateNh),
47  DiagnosticNodelet("OctomapServerContact"),
48  m_octreeContact(NULL),
49  m_publishUnknownSpace(false),
50  m_publishFrontierSpace(false),
51  m_offsetVisualizeUnknown(0),
52  m_maxRangeProximity(0.05),
53  m_occupancyMinX(-std::numeric_limits<double>::max()),
54  m_occupancyMaxX(std::numeric_limits<double>::max()),
55  m_occupancyMinY(-std::numeric_limits<double>::max()),
56  m_occupancyMaxY(std::numeric_limits<double>::max()),
57  m_useContactSurface(true)
58  {
59  delete m_octree;
60  m_octree = NULL;
62  m_octreeContact = dynamic_cast<OcTreeContact*>(m_octree);
63  if (!m_octreeContact) {
64  ROS_ERROR("Could not convert OcTreeContact from OcTree");
65  assert(m_octreeContact);
66  }
67 
68  m_useHeightMap = false;
69 
70  privateNh.param("publish_unknown_space", m_publishUnknownSpace, m_publishUnknownSpace);
71  privateNh.param("offset_vis_unknown", m_offsetVisualizeUnknown, m_offsetVisualizeUnknown);
72  privateNh.param("sensor_model/max_range_proximity", m_maxRangeProximity, m_maxRangeProximity);
73  privateNh.param("publish_frontier_space", m_publishFrontierSpace, m_publishFrontierSpace);
74 
75  privateNh.param("occupancy_min_x", m_occupancyMinX,m_occupancyMinX);
76  privateNh.param("occupancy_max_x", m_occupancyMaxX,m_occupancyMaxX);
77  privateNh.param("occupancy_min_y", m_occupancyMinY,m_occupancyMinY);
78  privateNh.param("occupancy_max_y", m_occupancyMaxY,m_occupancyMaxY);
79 
80  privateNh.param("use_contact_surface", m_useContactSurface,m_useContactSurface);
81 
82  double r, g, b, a;
83  privateNh.param("color_unknown/r", r, 0.5);
84  privateNh.param("color_unknown/g", g, 0.5);
85  privateNh.param("color_unknown/b", b, 0.7);
86  privateNh.param("color_unknown/a", a, 1.0);
87  m_colorUnknown.r = r;
88  m_colorUnknown.g = g;
89  m_colorUnknown.b = b;
90  m_colorUnknown.a = a;
91  privateNh.param("color_frontier/r", r, 1.0);
92  privateNh.param("color_frontier/g", g, 0.0);
93  privateNh.param("color_frontier/b", b, 0.0);
94  privateNh.param("color_frontier/a", a, 1.0);
95  m_colorFrontier.r = r;
96  m_colorFrontier.g = g;
97  m_colorFrontier.b = b;
98  m_colorFrontier.a = a;
99 
100  m_unknownPointCloudPub = m_nh.advertise<sensor_msgs::PointCloud2>("octomap_unknown_point_cloud_centers", 1, m_latchedTopics);
101  m_umarkerPub = m_nh.advertise<visualization_msgs::MarkerArray>("unknown_cells_vis_array", 1, m_latchedTopics);
102 
105  m_tfPointProximitySub->registerCallback(boost::bind(&OctomapServerContact::insertProximityCallback, this, _1));
106 
107  m_frontierPointCloudPub = m_nh.advertise<sensor_msgs::PointCloud2>("octomap_frontier_point_cloud_centers", 1, m_latchedTopics);
108  m_fromarkerPub = m_nh.advertise<visualization_msgs::MarkerArray>("frontier_cells_vis_array", 1, m_latchedTopics);
109 
110  m_contactSensorSub.subscribe(m_nh, "contact_sensors_in", 2);
113  m_tfContactSensorSub->registerCallback(boost::bind(&OctomapServerContact::insertContactSensorCallback, this, _1));
114 
115  initContactSensor(privateNh);
116  }
117 
119  }
120 
122  double defaultPadding, defaultScale;
123  privateNh.param<double>("self_see_defaultPadding", defaultPadding, .01);
124  privateNh.param<double>("self_see_defaultScale", defaultScale, 1.0);
125  std::vector<robot_self_filter::LinkInfo> links;
126 
127  if (!privateNh.hasParam("self_see_links")) {
128  ROS_WARN("No links specified for self filtering.");
129  }
130  else {
131  XmlRpc::XmlRpcValue sslVals;;
132  privateNh.getParam("self_see_links", sslVals);
133  if (sslVals.getType() != XmlRpc::XmlRpcValue::TypeArray) {
134  ROS_WARN("Self see links need to be an array");
135  }
136  else {
137  if (sslVals.size() == 0) {
138  ROS_WARN("No values in self see links array");
139  }
140  else {
141  for (int i = 0; i < sslVals.size(); i++) {
143  if (sslVals[i].getType() != XmlRpc::XmlRpcValue::TypeStruct) {
144  ROS_WARN("Self see links entry %d is not a structure. Stopping processing of self see links",i);
145  break;
146  }
147  if (!sslVals[i].hasMember("name")) {
148  ROS_WARN("Self see links entry %d has no name. Stopping processing of self see links",i);
149  break;
150  }
151  li.name = std::string(sslVals[i]["name"]);
152  if (!sslVals[i].hasMember("padding")) {
153  ROS_DEBUG("Self see links entry %d has no padding. Assuming default padding of %g",i,defaultPadding);
154  li.padding = defaultPadding;
155  }
156  else {
157  li.padding = sslVals[i]["padding"];
158  }
159  if (!sslVals[i].hasMember("scale")) {
160  ROS_DEBUG("Self see links entry %d has no scale. Assuming default scale of %g",i,defaultScale);
161  li.scale = defaultScale;
162  }
163  else {
164  li.scale = sslVals[i]["scale"];
165  }
166  links.push_back(li);
167  }
168  }
169  }
170  }
172  }
173 
174  void OctomapServerContact::insertProximityCallback(const sensor_msgs::PointCloud2::ConstPtr& cloud) {
175  // ROS_INFO("insertProximityCallback is called");
176 
177  ros::WallTime startTime = ros::WallTime::now();
178 
179  //
180  // ground filtering in base frame
181  //
182  PCLPointCloud pc; // input cloud for filtering and ground-detection
183  pcl::fromROSMsg(*cloud, pc);
184 
185  tf::StampedTransform sensorToWorldTf;
186  try {
187  m_tfListener.lookupTransform(m_worldFrameId, cloud->header.frame_id, cloud->header.stamp, sensorToWorldTf);
188  } catch(tf::TransformException& ex){
189  ROS_ERROR_STREAM( "Transform error of sensor data: " << ex.what() << ", quitting callback");
190  return;
191  }
192 
193  Eigen::Matrix4f sensorToWorld;
194  pcl_ros::transformAsMatrix(sensorToWorldTf, sensorToWorld);
195 
196  // directly transform to map frame:
197  pcl::transformPointCloud(pc, pc, sensorToWorld);
198 
199  pc.header = pc.header;
200 
201  insertScanProximity(sensorToWorldTf.getOrigin(), pc);
202 
203  double total_elapsed = (ros::WallTime::now() - startTime).toSec();
204  ROS_DEBUG("Pointcloud insertion in OctomapServer done (%zu pts, %f sec)", pc.size(), total_elapsed);
205 
206  publishAll(cloud->header.stamp);
207  }
208 
209  void OctomapServerContact::insertScanProximity(const tf::Point& sensorOriginTf, const PCLPointCloud& pc) {
210  point3d sensorOrigin = pointTfToOctomap(sensorOriginTf);
211 
212  if (!m_octree->coordToKeyChecked(sensorOrigin, m_updateBBXMin)
213  || !m_octree->coordToKeyChecked(sensorOrigin, m_updateBBXMax))
214  {
215  ROS_ERROR_STREAM("Could not generate Key for origin "<<sensorOrigin);
216  }
217 
218 #ifdef COLOR_OCTOMAP_SERVER
219  unsigned char* colors = new unsigned char[3];
220 #endif
221 
222  // instead of direct scan insertion, compute update to filter ground:
223  KeySet free_cells, occupied_cells;
224 
225  // all other points: free on ray, occupied on endpoint:
226  for (PCLPointCloud::const_iterator it = pc.begin(); it != pc.end(); ++it) {
227  point3d point(it->x, it->y, it->z);
228  // maxrange check
229  if ((m_maxRangeProximity < 0.0) || ((point - sensorOrigin).norm() <= m_maxRangeProximity) ) {
230 
231  // free cells
232  if (m_octree->computeRayKeys(sensorOrigin, point, m_keyRay)){
233  free_cells.insert(m_keyRay.begin(), m_keyRay.end());
234  }
235  // occupied endpoint
236  OcTreeKey key;
237  if (m_octree->coordToKeyChecked(point, key)){
238  occupied_cells.insert(key);
239 
242 
243 #ifdef COLOR_OCTOMAP_SERVER // NB: Only read and interpret color if it's an occupied node
244  const int rgb = *reinterpret_cast<const int*>(&(it->rgb)); // TODO: there are other ways to encode color than this one
245  colors[0] = ((rgb >> 16) & 0xff);
246  colors[1] = ((rgb >> 8) & 0xff);
247  colors[2] = (rgb & 0xff);
248  m_octree->averageNodeColor(it->x, it->y, it->z, colors[0], colors[1], colors[2]);
249 #endif
250  }
251  } else {// ray longer than maxrange:;
252  point3d new_end = sensorOrigin + (point - sensorOrigin).normalized() * m_maxRangeProximity;
253  if (m_octree->computeRayKeys(sensorOrigin, new_end, m_keyRay)){
254  free_cells.insert(m_keyRay.begin(), m_keyRay.end());
255 
256  octomap::OcTreeKey endKey;
257  if (m_octree->coordToKeyChecked(new_end, endKey)){
258  updateMinKey(endKey, m_updateBBXMin);
259  updateMaxKey(endKey, m_updateBBXMax);
260  } else{
261  ROS_ERROR_STREAM("Could not generate Key for endpoint "<<new_end);
262  }
263  }
264  }
265  }
266 
267  // mark free cells only if not seen occupied in this cloud
268  for(KeySet::iterator it = free_cells.begin(), end=free_cells.end(); it!= end; ++it){
269  if (occupied_cells.find(*it) == occupied_cells.end()){
270  m_octree->updateNode(*it, false);
271  }
272  }
273 
274  // now mark all occupied cells:
275  for (KeySet::iterator it = occupied_cells.begin(), end=occupied_cells.end(); it!= end; it++) {
276  m_octree->updateNode(*it, true);
277  }
278 
279  // TODO: eval lazy+updateInner vs. proper insertion
280  // non-lazy by default (updateInnerOccupancy() too slow for large maps)
281  //m_octree->updateInnerOccupancy();
282  octomap::point3d minPt, maxPt;
283  ROS_DEBUG_STREAM("Bounding box keys (before): " << m_updateBBXMin[0] << " " <<m_updateBBXMin[1] << " " << m_updateBBXMin[2] << " / " <<m_updateBBXMax[0] << " "<<m_updateBBXMax[1] << " "<< m_updateBBXMax[2]);
284 
285  // TODO: snap max / min keys to larger voxels by m_maxTreeDepth
286  // if (m_maxTreeDepth < 16)
287  // {
288  // OcTreeKey tmpMin = getIndexKey(m_updateBBXMin, m_maxTreeDepth); // this should give us the first key at depth m_maxTreeDepth that is smaller or equal to m_updateBBXMin (i.e. lower left in 2D grid coordinates)
289  // OcTreeKey tmpMax = getIndexKey(m_updateBBXMax, m_maxTreeDepth); // see above, now add something to find upper right
290  // tmpMax[0]+= m_octree->getNodeSize( m_maxTreeDepth ) - 1;
291  // tmpMax[1]+= m_octree->getNodeSize( m_maxTreeDepth ) - 1;
292  // tmpMax[2]+= m_octree->getNodeSize( m_maxTreeDepth ) - 1;
293  // m_updateBBXMin = tmpMin;
294  // m_updateBBXMax = tmpMax;
295  // }
296 
297  // TODO: we could also limit the bbx to be within the map bounds here (see publishing check)
300  ROS_DEBUG_STREAM("Updated area bounding box: "<< minPt << " - "<<maxPt);
301  ROS_DEBUG_STREAM("Bounding box keys (after): " << m_updateBBXMin[0] << " " <<m_updateBBXMin[1] << " " << m_updateBBXMin[2] << " / " <<m_updateBBXMax[0] << " "<<m_updateBBXMax[1] << " "<< m_updateBBXMax[2]);
302 
303  if (m_compressMap)
304  m_octree->prune();
305 
306 #ifdef COLOR_OCTOMAP_SERVER
307  if (colors)
308  {
309  delete[] colors;
310  colors = NULL;
311  }
312 #endif
313  }
314 
315  void OctomapServerContact::insertContactSensor(const jsk_recognition_msgs::ContactSensorArray::ConstPtr& msg) {
316  std::vector<jsk_recognition_msgs::ContactSensor> datas = msg->datas;
317 
318  // setup tf transformation between octomap and each link
319  {
320  std_msgs::Header tmpHeader;
321  tmpHeader.frame_id = m_worldFrameId;
322  tmpHeader.stamp = msg->header.stamp;
323  if(!m_selfMask->assumeFrame(tmpHeader)) {
324  ROS_ERROR_STREAM("failed tf transformation in insertContactSensor");
325  return;
326  }
327  }
328 
329  // clamp min and max points cf. https://github.com/OctoMap/octomap/issues/146
332  point3d pmin = m_octree->keyToCoord(m_octree->coordToKey(pmin_raw));
333  point3d pmax = m_octree->keyToCoord(m_octree->coordToKey(pmax_raw));
334  float diff[3];
335  unsigned int steps[3];
337  for (int i = 0; i < 3; ++i) {
338  diff[i] = pmax(i) - pmin(i);
339  steps[i] = floor(diff[i] / resolution);
340  // std::cout << "bbx " << i << " size: " << diff[i] << " " << steps[i] << " steps\n";
341  }
342 
343  // loop for grids of octomap
344  if (m_useContactSurface) {
345  std::vector< std::vector<bool> > containFlag(datas.size(), std::vector<bool>(8));
346  point3d p = pmin;
347  for (unsigned int x = 0; x < steps[0]; ++x) {
348  p.x() += resolution;
349  for (unsigned int y = 0; y < steps[1]; ++y) {
350  p.y() += resolution;
351  for (unsigned int z = 0; z < steps[2]; ++z) {
352  // std::cout << "querying p=" << p << std::endl;
353  p.z() += resolution;
354  // loop for vertices of each gird
355  point3d vertexOffset(-resolution/2.0, -resolution/2.0, -resolution/2.0);
356  point3d vertex;
357  for (int i = 0; i < 2; i++) {
358  if (i == 1) { vertexOffset.z() += resolution; }
359  for (int j = 0; j < 2; j++) {
360  if (j == 1) { vertexOffset.y() += resolution; }
361  for (int k = 0; k < 2; k++) {
362  if (k == 1) { vertexOffset.x() += resolution; }
363  vertex = p + vertexOffset;
364  // std::cout << "vertex = " << vertex << std::endl;
365  // loop for each body link
366  for (int l=0; l<datas.size(); l++) {
367  if (m_selfMask->getMaskContainmentforNamedLink(vertex(0), vertex(1), vertex(2), datas[l].link_name) == robot_self_filter::INSIDE) {
368  // std::cout << "inside vertex = " << vertex << std::endl;
369  containFlag[l][i+j*2+k*4] = true;
370  }
371  else {
372  containFlag[l][i+j*2+k*4] = false;
373  }
374  }
375  }
376  vertexOffset.x() -= resolution;
377  }
378  vertexOffset.y() -= resolution;
379  }
380 
381  // update probability of grid
382  std::vector<bool> containFlagLinkSum(8, false);
383  std::vector<bool> containFlagVerticesSum(datas.size(), false);
384  std::vector<bool> containFlagVerticesProd(datas.size(), true);
385  bool insideFlag = false;
386  bool surfaceFlag = false;
387  for (int l = 0; l < datas.size(); l++) {
388  for (int i = 0; i < 8; i++) {
389  if (containFlag[l][i]) {
390  containFlagLinkSum[i] = true;
391  containFlagVerticesSum[l] = true;
392  }
393  else {
394  containFlagVerticesProd[l] = false;
395  }
396  }
397  }
398  insideFlag = (std::find(containFlagLinkSum.begin(), containFlagLinkSum.end(), false) == containFlagLinkSum.end()); // when all elements is true
399  for (int l = 0; l < datas.size(); l++) {
400  if (containFlagVerticesSum[l] && !(containFlagVerticesProd[l]) ) {
401  if (datas[l].contact) {
402  surfaceFlag = true;
403  }
404  }
405  }
406  if (insideFlag) { // inside
407  octomap::OcTreeKey pKey;
408  if (m_octreeContact->coordToKeyChecked(p, pKey)) {
410  // std::cout << "find inside grid and find key. p = " << vertex << std::endl;
411  }
412  }
413  else if (surfaceFlag) { // surface
414  octomap::OcTreeKey pKey;
415  if (m_octreeContact->coordToKeyChecked(p, pKey)) {
417  // std::cout << "find surface grid and find key. p = " << vertex << std::endl;
418  }
419  }
420  }
421  p.z() = pmin.z();
422  }
423  p.y() = pmin.y();
424  }
425  }
426  else {
427  point3d vertexOffset(-resolution/2.0, -resolution/2.0, -resolution/2.0);
428 #pragma omp parallel for
429  for (unsigned int cnt = 0; cnt < steps[0] * steps[1] * steps[2]; ++cnt) {
430  // get grid center
431  point3d p;
432  {
433  unsigned int id[3];
434  id[0] = cnt / (steps[1] * steps[2]);
435  id[1] = (cnt % (steps[1] * steps[2])) / steps[2];
436  id[2] = (cnt % (steps[1] * steps[2])) % steps[2];
437  p.x() = pmin(0) + resolution * id[0];
438  p.y() = pmin(1) + resolution * id[1];
439  p.z() = pmin(2) + resolution * id[2];
440  }
441  point3d vertex;
442  vertex = p + vertexOffset;
443  // loop for each body link
444  for (int l=0; l<datas.size(); l++) {
445  if (m_selfMask->getMaskContainmentforNamedLink(vertex(0), vertex(1), vertex(2), datas[l].link_name) == robot_self_filter::INSIDE) {
446  octomap::OcTreeKey pKey;
447  if (m_octreeContact->coordToKeyChecked(p, pKey)) {
448 #pragma omp critical
450  }
451  break;
452  }
453  }
454  }
455  }
457  }
458 
459  void OctomapServerContact::insertContactSensorCallback(const jsk_recognition_msgs::ContactSensorArray::ConstPtr& msg) {
460  NODELET_INFO("insert contact sensor");
462 
463  publishAll(msg->header.stamp);
464  }
465 
467  ros::WallTime startTime = ros::WallTime::now();
468  size_t octomapSize = m_octreeContact->size();
469  // TODO: estimate num occ. voxels for size of arrays (reserve)
470  if (octomapSize <= 1) {
471  ROS_WARN("Nothing to publish, octree is empty");
472  return;
473  }
474 
475  bool publishFreeMarkerArray = m_publishFreeSpace && (m_latchedTopics || m_fmarkerPub.getNumSubscribers() > 0);
476  bool publishUnknownMarkerArray = m_publishUnknownSpace && (m_latchedTopics || m_umarkerPub.getNumSubscribers() > 0);
477  bool publishFrontierMarkerArray = m_publishFrontierSpace && (m_latchedTopics || m_fromarkerPub.getNumSubscribers() > 0);
478  bool publishMarkerArray = (m_latchedTopics || m_markerPub.getNumSubscribers() > 0);
479  bool publishPointCloud = (m_latchedTopics || m_pointCloudPub.getNumSubscribers() > 0);
480  bool publishBinaryMap = (m_latchedTopics || m_binaryMapPub.getNumSubscribers() > 0);
481  bool publishFullMap = (m_latchedTopics || m_fullMapPub.getNumSubscribers() > 0);
483 
484  // init markers for free space:
485  visualization_msgs::MarkerArray freeNodesVis;
486  // each array stores all cubes of a different size, one for each depth level:
487  freeNodesVis.markers.resize(m_treeDepth+1);
488 
489  geometry_msgs::Pose pose;
490  pose.orientation = tf::createQuaternionMsgFromYaw(0.0);
491 
492  // init markers:
493  visualization_msgs::MarkerArray occupiedNodesVis;
494  // each array stores all cubes of a different size, one for each depth level:
495  occupiedNodesVis.markers.resize(m_treeDepth+1);
496 
497  // init pointcloud:
498  pcl::PointCloud<pcl::PointXYZ> pclCloud;
499 
500  // call pre-traversal hook:
501  handlePreNodeTraversal(rostime);
502 
503  // now, traverse all leafs in the tree:
504  for (OcTree::iterator it = m_octreeContact->begin(m_maxTreeDepth), end = m_octreeContact->end(); it != end; ++it) {
505  bool inUpdateBBX = isInUpdateBBX(it);
506 
507  // call general hook:
508  handleNode(it);
509  if (inUpdateBBX) {
510  handleNodeInBBX(it);
511  }
512 
513  if (m_octreeContact->isNodeOccupied(*it)) {
514  double x = it.getX();
515  double y = it.getY();
516  double z = it.getZ();
517  if (x > m_occupancyMinX && x < m_occupancyMaxX && y > m_occupancyMinY && y < m_occupancyMaxY && z > m_occupancyMinZ && z < m_occupancyMaxZ) {
518  double size = it.getSize();
519  double x = it.getX();
520  double y = it.getY();
521 
522  // Ignore speckles in the map:
523  if (m_filterSpeckles && (it.getDepth() == m_treeDepth +1) && isSpeckleNode(it.getKey())) {
524  ROS_DEBUG("Ignoring single speckle at (%f,%f,%f)", x, y, z);
525  continue;
526  } // else: current octree node is no speckle, send it out
527 
528  handleOccupiedNode(it);
529  if (inUpdateBBX) {
531  }
532 
533  //create marker:
534  if (publishMarkerArray) {
535  unsigned idx = it.getDepth();
536  assert(idx < occupiedNodesVis.markers.size());
537 
538  geometry_msgs::Point cubeCenter;
539  cubeCenter.x = x;
540  cubeCenter.y = y;
541  cubeCenter.z = z;
542 
543  occupiedNodesVis.markers[idx].points.push_back(cubeCenter);
544  if (m_useHeightMap) {
545  double minX, minY, minZ, maxX, maxY, maxZ;
546  m_octreeContact->getMetricMin(minX, minY, minZ);
547  m_octreeContact->getMetricMax(maxX, maxY, maxZ);
548 
549  double h = (1.0 - std::min(std::max((cubeCenter.z-minZ)/ (maxZ - minZ), 0.0), 1.0)) *m_colorFactor;
550  occupiedNodesVis.markers[idx].colors.push_back(heightMapColor(h));
551  }
552  }
553 
554  // insert into pointcloud:
555  if (publishPointCloud) {
556  pclCloud.push_back(pcl::PointXYZ(x, y, z));
557  }
558 
559  }
560  } else { // node not occupied => mark as free in 2D map if unknown so far
561  double x = it.getX();
562  double y = it.getY();
563  double z = it.getZ();
564  if (x > m_occupancyMinX && x < m_occupancyMaxX && y > m_occupancyMinY && y < m_occupancyMaxY && z > m_occupancyMinZ && z < m_occupancyMaxZ) {
565  handleFreeNode(it);
566  if (inUpdateBBX)
568 
569  if (m_publishFreeSpace) {
570  double x = it.getX();
571  double y = it.getY();
572 
573  //create marker for free space:
574  if (publishFreeMarkerArray) {
575  unsigned idx = it.getDepth();
576  assert(idx < freeNodesVis.markers.size());
577 
578  geometry_msgs::Point cubeCenter;
579  cubeCenter.x = x;
580  cubeCenter.y = y;
581  cubeCenter.z = z;
582 
583  freeNodesVis.markers[idx].points.push_back(cubeCenter);
584  }
585  }
586  }
587  }
588  }
589 
590  // call post-traversal hook:
591  handlePostNodeTraversal(rostime);
592 
593  // finish MarkerArray:
594  if (publishMarkerArray) {
595  for (unsigned i = 0; i < occupiedNodesVis.markers.size(); ++i) {
596  double size = m_octreeContact->getNodeSize(i);
597 
598  occupiedNodesVis.markers[i].header.frame_id = m_worldFrameId;
599  occupiedNodesVis.markers[i].header.stamp = rostime;
600  occupiedNodesVis.markers[i].ns = m_worldFrameId;
601  occupiedNodesVis.markers[i].id = i;
602  occupiedNodesVis.markers[i].type = visualization_msgs::Marker::CUBE_LIST;
603  occupiedNodesVis.markers[i].scale.x = size;
604  occupiedNodesVis.markers[i].scale.y = size;
605  occupiedNodesVis.markers[i].scale.z = size;
606  occupiedNodesVis.markers[i].color = m_color;
607 
608 
609  if (occupiedNodesVis.markers[i].points.size() > 0) {
610  occupiedNodesVis.markers[i].action = visualization_msgs::Marker::ADD;
611  }
612  else {
613  occupiedNodesVis.markers[i].action = visualization_msgs::Marker::DELETE;
614  }
615  }
616 
617  m_markerPub.publish(occupiedNodesVis);
618  }
619 
620 
621  // finish FreeMarkerArray:
622  if (publishFreeMarkerArray) {
623  for (unsigned i = 0; i < freeNodesVis.markers.size(); ++i) {
624  double size = m_octreeContact->getNodeSize(i);
625 
626  freeNodesVis.markers[i].header.frame_id = m_worldFrameId;
627  freeNodesVis.markers[i].header.stamp = rostime;
628  freeNodesVis.markers[i].ns = m_worldFrameId;
629  freeNodesVis.markers[i].id = i;
630  freeNodesVis.markers[i].type = visualization_msgs::Marker::CUBE_LIST;
631  freeNodesVis.markers[i].scale.x = size;
632  freeNodesVis.markers[i].scale.y = size;
633  freeNodesVis.markers[i].scale.z = size;
634  freeNodesVis.markers[i].color = m_colorFree;
635 
636 
637  if (freeNodesVis.markers[i].points.size() > 0) {
638  freeNodesVis.markers[i].action = visualization_msgs::Marker::ADD;
639  }
640  else {
641  freeNodesVis.markers[i].action = visualization_msgs::Marker::DELETE;
642  }
643  }
644 
645  m_fmarkerPub.publish(freeNodesVis);
646  }
647 
648 
649  // publish unknown grid as marker
650  if (publishUnknownMarkerArray) {
651  visualization_msgs::MarkerArray unknownNodesVis;
652  unknownNodesVis.markers.resize(1);
653 
654  point3d_list unknownLeaves;
655  double offset = m_offsetVisualizeUnknown;
656  point3d pMin(m_occupancyMinX + offset, m_occupancyMinY + offset, m_occupancyMinZ + offset);
657  point3d pMax(m_occupancyMaxX - offset, m_occupancyMaxY - offset, m_occupancyMaxZ - offset);
658 
659  m_octreeContact->getUnknownLeafCenters(unknownLeaves, pMin, pMax);
660  pcl::PointCloud<pcl::PointXYZ> unknownCloud;
661 
662  for (point3d_list::iterator it = unknownLeaves.begin(); it != unknownLeaves.end(); it++) {
663  float x = (*it).x();
664  float y = (*it).y();
665  float z = (*it).z();
666  unknownCloud.push_back(pcl::PointXYZ(x, y, z));
667 
668  geometry_msgs::Point cubeCenter;
669  cubeCenter.x = x;
670  cubeCenter.y = y;
671  cubeCenter.z = z;
672  if (m_useHeightMap) {
673  double minX, minY, minZ, maxX, maxY, maxZ;
674  m_octreeContact->getMetricMin(minX, minY, minZ);
675  m_octreeContact->getMetricMax(maxX, maxY, maxZ);
676  double h = (1.0 - std::min(std::max((cubeCenter.z-minZ)/ (maxZ - minZ), 0.0), 1.0)) *m_colorFactor;
677  unknownNodesVis.markers[0].colors.push_back(heightMapColor(h));
678  }
679  unknownNodesVis.markers[0].points.push_back(cubeCenter);
680  }
681 
683  unknownNodesVis.markers[0].header.frame_id = m_worldFrameId;
684  unknownNodesVis.markers[0].header.stamp = rostime;
685  unknownNodesVis.markers[0].ns = m_worldFrameId;
686  unknownNodesVis.markers[0].id = 0;
687  unknownNodesVis.markers[0].type = visualization_msgs::Marker::CUBE_LIST;
688  unknownNodesVis.markers[0].scale.x = size;
689  unknownNodesVis.markers[0].scale.y = size;
690  unknownNodesVis.markers[0].scale.z = size;
691  unknownNodesVis.markers[0].color = m_colorUnknown;
692 
693  if (unknownNodesVis.markers[0].points.size() > 0) {
694  unknownNodesVis.markers[0].action = visualization_msgs::Marker::ADD;
695  }
696  else {
697  unknownNodesVis.markers[0].action = visualization_msgs::Marker::DELETE;
698  }
699  m_umarkerPub.publish(unknownNodesVis);
700 
701  // publish unknown grid as pointcloud
702  sensor_msgs::PointCloud2 unknownRosCloud;
703  pcl::toROSMsg (unknownCloud, unknownRosCloud);
704  unknownRosCloud.header.frame_id = m_worldFrameId;
705  unknownRosCloud.header.stamp = rostime;
706  m_unknownPointCloudPub.publish(unknownRosCloud);
707 
708  // publish frontier grid as marker
709  if (publishFrontierMarkerArray) {
710  visualization_msgs::MarkerArray frontierNodesVis;
711  frontierNodesVis.markers.resize(1);
712  pcl::PointCloud<pcl::PointXYZ> frontierCloud;
714  // how many resolution-size grids are in one edge
715  int x_num = int(((m_occupancyMaxX - m_occupancyMinX) / resolution));
716  int y_num = int(((m_occupancyMaxY - m_occupancyMinY) / resolution));
717  int z_num = int(((m_occupancyMaxZ - m_occupancyMinZ) / resolution));
718  std::vector< std::vector< std::vector<int> > > check_unknown(x_num, std::vector< std::vector<int> >(y_num, std::vector<int>(z_num)));
719  std::vector< std::vector< std::vector<int> > > check_occupied(x_num, std::vector< std::vector<int> >(y_num, std::vector<int>(z_num)));
720  std::vector< std::vector< std::vector<int> > > check_frontier(x_num, std::vector< std::vector<int> >(y_num, std::vector<int>(z_num)));
721 
722  for (int i = 0; i < x_num; i++) {
723  for (int j = 0; j < y_num; j++) {
724  for (int k = 0; k < z_num; k++) {
725  check_unknown[i][j][k] = 0;
726  check_occupied[i][j][k] = 0;
727  check_frontier[i][j][k] = 0;
728  }
729  }
730  }
731 
732  // for all unknown grids, store its information to array
733  for (point3d_list::iterator it_unknown = unknownLeaves.begin();
734  it_unknown != unknownLeaves.end();
735  it_unknown++) {
736  // get center of unknown grids
737  double x_unknown = it_unknown->x();
738  double y_unknown = it_unknown->y();
739  double z_unknown = it_unknown->z();
740  int x_index = int(std::round((x_unknown - m_occupancyMinX) / resolution - 1));
741  int y_index = int(std::round((y_unknown - m_occupancyMinY) / resolution - 1));
742  int z_index = int(std::round((z_unknown - m_occupancyMinZ) / resolution - 1));
743  check_unknown[x_index][y_index][z_index] = 1;
744  }
745 
746  // for all occupied grids, store its information to array
747  for (int idx = 0; idx < occupiedNodesVis.markers.size(); idx++) {
748  double size_occupied = occupiedNodesVis.markers[idx].scale.x;
749  for (int id = 0; id < occupiedNodesVis.markers[idx].points.size(); id++) {
750  double x_occupied = occupiedNodesVis.markers[idx].points[id].x;
751  double y_occupied = occupiedNodesVis.markers[idx].points[id].y;
752  double z_occupied = occupiedNodesVis.markers[idx].points[id].z;
753  int x_min_index = std::round((x_occupied - (size_occupied / 2.0) - m_occupancyMinX) / resolution);
754  int y_min_index = std::round((y_occupied - (size_occupied / 2.0) - m_occupancyMinY) / resolution);
755  int z_min_index = std::round((z_occupied - (size_occupied / 2.0) - m_occupancyMinZ) / resolution);
756  for (int i = x_min_index; i < x_min_index + int(size_occupied/resolution); i++) {
757  for (int j = y_min_index; j < y_min_index + int(size_occupied/resolution); j++) {
758  for (int k = z_min_index; k < z_min_index + int(size_occupied/resolution); k++) {
759  check_occupied[i][j][k] = 1;
760  }
761  }
762  }
763  }
764  }
765 
766  // for all grids except occupied and unknown, (NOTE there are grids which are not free, nor occupied, nor unknown)
767  // check whether they are frontier, namely, adjecent to unknown grids
768  // NOTE all unknown grids are displaced half from the other grids
769  geometry_msgs::Point cubeCenter;
770  for (int i = 0; i < x_num; i++) {
771  for (int j = 0; j < y_num; j++) {
772  for (int k = 0; k < z_num-1; k++) {
773  for (int l = -1; l <= 1; l++) {
774  if ( i+l < 0 || x_num <= i+l ) continue;
775  for (int m = -1; m <= 1; m++) {
776  if ( j+m < 0 || y_num <= j+m ) continue;
777  for (int n = -1; n <= 1; n++) {
778  if ( k+n < 0 || z_num <= k+n ) continue;
779  if (l == 0 && m == 0 && n== 0) continue;
780  if (check_unknown[i+l][j+m][k+n] == 1 && check_unknown[i][j][k] == 0 && check_occupied[i][j][k] == 0 && check_frontier[i][j][k] == 0) {
781  check_frontier[i][j][k] = 1;
782  cubeCenter.x = (i+0.5)*resolution + m_occupancyMinX;
783  cubeCenter.y = (j+0.5)*resolution + m_occupancyMinY;
784  cubeCenter.z = (k+0.5)*resolution + m_occupancyMinZ;
785  if (m_useHeightMap) {
786  double minX, minY, minZ, maxX, maxY, maxZ;
787  m_octreeContact->getMetricMin(minX, minY, minZ);
788  m_octreeContact->getMetricMax(maxX, maxY, maxZ);
789  double h = (1.0 - std::min(std::max((cubeCenter.z-minZ)/ (maxZ - minZ), 0.0), 1.0)) *m_colorFactor;
790  frontierNodesVis.markers[0].colors.push_back(heightMapColor(h));
791  }
792  frontierNodesVis.markers[0].points.push_back(cubeCenter);
793  }
794  }
795  }
796  }
797  }
798  }
799  }
800 
801  // publish frontier grid as marker
803  frontierNodesVis.markers[0].header.frame_id = m_worldFrameId;
804  frontierNodesVis.markers[0].header.stamp = rostime;
805  frontierNodesVis.markers[0].ns = m_worldFrameId;
806  frontierNodesVis.markers[0].id = 0;
807  frontierNodesVis.markers[0].type = visualization_msgs::Marker::CUBE_LIST;
808  frontierNodesVis.markers[0].scale.x = size;
809  frontierNodesVis.markers[0].scale.y = size;
810  frontierNodesVis.markers[0].scale.z = size;
811  frontierNodesVis.markers[0].color = m_colorFrontier;
812 
813  if (frontierNodesVis.markers[0].points.size() > 0) {
814  frontierNodesVis.markers[0].action = visualization_msgs::Marker::ADD;
815  }
816  else {
817  frontierNodesVis.markers[0].action = visualization_msgs::Marker::DELETE;
818  }
819 
820  m_fromarkerPub.publish(frontierNodesVis);
821 
822  // publish frontier grid as pointcloud
823  sensor_msgs::PointCloud2 frontierRosCloud;
824  pcl::toROSMsg (frontierCloud, frontierRosCloud);
825  frontierRosCloud.header.frame_id = m_worldFrameId;
826  frontierRosCloud.header.stamp = rostime;
827  m_frontierPointCloudPub.publish(frontierRosCloud);
828  }
829  }
830 
831  // finish pointcloud:
832  if (publishPointCloud) {
833  sensor_msgs::PointCloud2 cloud;
834  pcl::toROSMsg (pclCloud, cloud);
835  cloud.header.frame_id = m_worldFrameId;
836  cloud.header.stamp = rostime;
838  }
839 
840  if (publishBinaryMap) {
841  publishBinaryOctoMap(rostime);
842  }
843 
844  if (publishFullMap) {
845  publishFullOctoMap(rostime);
846  }
847 
848  double totalElapsed = (ros::WallTime::now() - startTime).toSec();
849  ROS_DEBUG("Map publishing in OctomapServer took %f sec", totalElapsed);
850  }
851 
853  {
854  DiagnosticNodelet::onInit();
855  onInitPostProcess();
856  }
857 }
858 
XmlRpc::XmlRpcValue::size
int size() const
PLUGINLIB_EXPORT_CLASS
PLUGINLIB_EXPORT_CLASS(jsk_pcl_ros::OctomapServerContact, nodelet::Nodelet)
extract_top_polygon_likelihood.ex
ex
Definition: extract_top_polygon_likelihood.py:51
jsk_pcl_ros::OctomapServerContact::m_occupancyMinY
double m_occupancyMinY
Definition: octomap_server_contact.h:91
jsk_pcl_ros::OctomapServerContact::m_fromarkerPub
ros::Publisher m_fromarkerPub
Definition: octomap_server_contact.h:74
octomap::OcTreeContact
This is a inherited class of OcTree. The probability of contact sensor model is defined.
Definition: OcTreeContact.h:80
pcl_ros::transformAsMatrix
void transformAsMatrix(const geometry_msgs::Transform &bt, Eigen::Matrix4f &out_mat)
octomap_server::OctomapServer::m_occupancyMaxZ
double m_occupancyMaxZ
jsk_pcl_ros::OctomapServerContact::insertScanProximity
virtual void insertScanProximity(const tf::Point &sensorOriginTf, const PCLPointCloud &pc)
Definition: octomap_server_contact_nodelet.cpp:209
OccupancyOcTreeBase< OcTreeNode >::updateInnerOccupancy
void updateInnerOccupancy()
octomap_server::OctomapServer::handleNode
virtual void handleNode(const OcTreeT::iterator &it)
octomap_server::OctomapServer::m_latchedTopics
bool m_latchedTopics
octomap_server::OctomapServer::updateMaxKey
static void updateMaxKey(const octomap::OcTreeKey &in, octomap::OcTreeKey &max)
octomap_server_contact.h
l
long l
jsk_pcl_ros::OctomapServerContact::m_colorUnknown
std_msgs::ColorRGBA m_colorUnknown
Definition: octomap_server_contact.h:79
jsk_pcl_ros::OctomapServerContact::publishAll
virtual void publishAll(const ros::Time &rostime)
Definition: octomap_server_contact_nodelet.cpp:466
ROS_ERROR_STREAM
#define ROS_ERROR_STREAM(args)
boost::shared_ptr< robot_self_filter::SelfMaskNamedLink >
jsk_pcl_ros::OctomapServerContact::m_frontierPointCloudPub
ros::Publisher m_frontierPointCloudPub
Definition: octomap_server_contact.h:74
i
int i
octomap_server::OctomapServer::PCLPointCloud
pcl::PointCloud< pcl::PointXYZ > PCLPointCloud
jsk_pcl_ros::OctomapServerContact::m_tfPointProximitySub
tf::MessageFilter< sensor_msgs::PointCloud2 > * m_tfPointProximitySub
Definition: octomap_server_contact.h:73
OcTreeBaseImpl< OcTreeNode, AbstractOccupancyOcTree >::size
virtual size_t size() const
jsk_pcl_ros::OctomapServerContact::insertContactSensorCallback
virtual void insertContactSensorCallback(const jsk_recognition_msgs::ContactSensorArray::ConstPtr &msg)
Definition: octomap_server_contact_nodelet.cpp:459
jsk_pcl_ros::OctomapServerContact::onInit
virtual void onInit()
Definition: octomap_server_contact_nodelet.cpp:852
jsk_pcl_ros::OctomapServerContact::m_selfMask
boost::shared_ptr< robot_self_filter::SelfMaskNamedLink > m_selfMask
Definition: octomap_server_contact.h:96
octomap_server::OctomapServer::m_keyRay
octomap::KeyRay m_keyRay
octomap_server::OctomapServer::heightMapColor
static std_msgs::ColorRGBA heightMapColor(double h)
OcTreeBaseImpl< OcTreeNode, AbstractOccupancyOcTree >::computeRayKeys
bool computeRayKeys(const point3d &origin, const point3d &end, KeyRay &ray) const
jsk_pcl_ros::OctomapServerContact::m_unknownPointCloudPub
ros::Publisher m_unknownPointCloudPub
Definition: octomap_server_contact.h:71
OcTreeBaseImpl< OcTreeNode, AbstractOccupancyOcTree >::keyToCoord
point3d keyToCoord(const OcTreeKey &key) const
p
p
ros::NodeHandle::getParam
bool getParam(const std::string &key, bool &b) const
octomap_server::OctomapServer::m_filterSpeckles
bool m_filterSpeckles
jsk_pcl_ros::min
double min(const OneDataStat &d)
wrapper function for min method for boost::function
Definition: one_data_stat.h:126
octomap_server::OctomapServer::isSpeckleNode
bool isSpeckleNode(const octomap::OcTreeKey &key) const
rgb
rgb
ROS_DEBUG
#define ROS_DEBUG(...)
octomap_server::OctomapServer::handlePreNodeTraversal
virtual void handlePreNodeTraversal(const ros::Time &rostime)
OcTreeBaseImpl< OcTreeNode, AbstractOccupancyOcTree >::getUnknownLeafCenters
void getUnknownLeafCenters(point3d_list &node_centers, point3d pmin, point3d pmax, unsigned int depth=0) const
robot_self_filter::LinkInfo
OcTreeBaseImpl< OcTreeNode, AbstractOccupancyOcTree >::getMetricMax
virtual void getMetricMax(double &x, double &y, double &z)
OcTreeBaseImpl< OcTreeNode, AbstractOccupancyOcTree >::coordToKey
OcTreeKey coordToKey(const point3d &coord) const
attention_pose_set.x
x
Definition: attention_pose_set.py:18
octomap_server::OctomapServer::m_octree
OcTreeT * m_octree
octomap_server::OctomapServer::m_colorFactor
double m_colorFactor
tf::StampedTransform
pcl::fromROSMsg
void fromROSMsg(const sensor_msgs::PointCloud2 &cloud, pcl::PointCloud< T > &pcl_cloud)
ROS_DEBUG_STREAM
#define ROS_DEBUG_STREAM(args)
octomap_server::OctomapServer::m_publishFreeSpace
bool m_publishFreeSpace
ros::Publisher::publish
void publish(const boost::shared_ptr< M > &message) const
ros::NodeHandle::advertise
Publisher advertise(AdvertiseOptions &ops)
cloud
cloud
XmlRpc::XmlRpcValue::TypeStruct
TypeStruct
jsk_pcl_ros::OctomapServerContact::m_publishUnknownSpace
bool m_publishUnknownSpace
Definition: octomap_server_contact.h:82
octomap_server::OctomapServer::publishBinaryOctoMap
void publishBinaryOctoMap(const ros::Time &rostime=ros::Time::now()) const
message_filters::Subscriber< sensor_msgs::PointCloud2 >
octomath::Vector3
jsk_pcl_ros::OctomapServerContact::m_useContactSurface
bool m_useContactSurface
Definition: octomap_server_contact.h:94
pose
pose
octomap_server::OctomapServer::m_publish2DMap
bool m_publish2DMap
class_list_macros.h
OcTreeBaseImpl< OcTreeNode, AbstractOccupancyOcTree >::getResolution
double getResolution() const
octomap_server::OctomapServer::handleFreeNodeInBBX
virtual void handleFreeNodeInBBX(const OcTreeT::iterator &it)
octomap_server::OctomapServer::m_res
double m_res
tf::Point
tf::Vector3 Point
jsk_pcl_ros::OctomapServerContact::m_umarkerPub
ros::Publisher m_umarkerPub
Definition: octomap_server_contact.h:71
jsk_pcl_ros::OctomapServerContact::m_occupancyMinX
double m_occupancyMinX
Definition: octomap_server_contact.h:89
jsk_pcl_ros
Definition: add_color_from_image.h:51
octomap::OcTreeContact::getProbMissContactSensorLog
float getProbMissContactSensorLog() const
Definition: OcTreeContact.h:138
KeySet
unordered_ns::unordered_set< OcTreeKey, OcTreeKey::KeyHash > KeySet
max
max
NULL
#define NULL
octomap_server::OctomapServer::m_nh
ros::NodeHandle m_nh
octomap_server::OctomapServer::updateMinKey
static void updateMinKey(const octomap::OcTreeKey &in, octomap::OcTreeKey &min)
octomap_server::OctomapServer::m_fmarkerPub
ros::Publisher m_fmarkerPub
k
int k
ros::WallTime::now
static WallTime now()
jsk_pcl_ros::OctomapServerContact::~OctomapServerContact
virtual ~OctomapServerContact()
Definition: octomap_server_contact_nodelet.cpp:118
octomap_server::OctomapServer::handleFreeNode
virtual void handleFreeNode(const OcTreeT::iterator &it)
jsk_pcl_ros::OctomapServerContact::m_occupancyMaxY
double m_occupancyMaxY
Definition: octomap_server_contact.h:92
ROS_ERROR
#define ROS_ERROR(...)
jsk_pcl_ros::OctomapServerContact::m_pointProximitySub
message_filters::Subscriber< sensor_msgs::PointCloud2 > * m_pointProximitySub
Definition: octomap_server_contact.h:72
jsk_pcl_ros::OctomapServerContact::insertProximityCallback
virtual void insertProximityCallback(const sensor_msgs::PointCloud2::ConstPtr &cloud)
Definition: octomap_server_contact_nodelet.cpp:174
attention_pose_set.r
r
Definition: attention_pose_set.py:9
ros::NodeHandle::hasParam
bool hasParam(const std::string &key) const
_1
boost::arg< 1 > _1
robot_self_filter::LinkInfo::scale
double scale
ROS_WARN
#define ROS_WARN(...)
m
m
octomap::KeyRay::end
iterator end()
octomap_server::OctomapServer::m_colorFree
std_msgs::ColorRGBA m_colorFree
jsk_pcl_ros::OctomapServerContact::m_tfContactSensorSub
boost::shared_ptr< tf::MessageFilter< jsk_recognition_msgs::ContactSensorArray > > m_tfContactSensorSub
Definition: octomap_server_contact.h:76
octomap::OcTreeKey
octomap_server::OctomapServer::m_updateBBXMin
octomap::OcTreeKey m_updateBBXMin
octomap::OcTreeKey
OcTreeBaseImpl< OcTreeNode, AbstractOccupancyOcTree >::prune
virtual void prune()
jsk_pcl_ros::OctomapServerContact::m_maxRangeProximity
double m_maxRangeProximity
Definition: octomap_server_contact.h:87
end
end
ros::WallTime
octomap_server::OctomapServer::m_mapPub
ros::Publisher m_mapPub
jsk_pcl_ros::OctomapServerContact::m_colorFrontier
std_msgs::ColorRGBA m_colorFrontier
Definition: octomap_server_contact.h:80
OcTreeBaseImpl< OcTreeNode, AbstractOccupancyOcTree >::begin
iterator begin(unsigned char maxDepth=0) const
octomap_server::OctomapServer::m_pointCloudPub
ros::Publisher m_pointCloudPub
OcTreeBaseImpl< OcTreeNode, AbstractOccupancyOcTree >::coordToKeyChecked
bool coordToKeyChecked(const point3d &coord, OcTreeKey &key) const
XmlRpc::XmlRpcValue::getType
const Type & getType() const
octomap::AbstractOccupancyOcTree::isNodeOccupied
bool isNodeOccupied(const OcTreeNode &occupancyNode) const
point
std::chrono::system_clock::time_point point
XmlRpc::XmlRpcValue::TypeArray
TypeArray
jsk_pcl_ros::OctomapServerContact
Definition: octomap_server_contact.h:52
octomap_server::OctomapServer::isInUpdateBBX
bool isInUpdateBBX(const OcTreeT::iterator &it) const
message_filters::Subscriber::subscribe
void subscribe()
NODELET_INFO
#define NODELET_INFO(...)
point3d_list
std::list< octomath::Vector3 > point3d_list
octomap_server::OctomapServer::m_compressMap
bool m_compressMap
octomap_server::OctomapServer::m_updateBBXMax
octomap::OcTreeKey m_updateBBXMax
nodelet::Nodelet
octomap::OcTreeContact::getProbHitContactSensorLog
float getProbHitContactSensorLog() const
Definition: OcTreeContact.h:136
octomath::Vector3::y
float & y()
ros::Time
robot_self_filter::LinkInfo::padding
double padding
OcTreeBaseImpl< OcTreeNode, AbstractOccupancyOcTree >::getNodeSize
double getNodeSize(unsigned depth) const
octomap_server::OctomapServer::m_fullMapPub
ros::Publisher m_fullMapPub
octomap_server::OctomapServer::handleOccupiedNode
virtual void handleOccupiedNode(const OcTreeT::iterator &it)
std
octomap_server::OctomapServer::m_occupancyMinZ
double m_occupancyMinZ
tf::MessageFilter< sensor_msgs::PointCloud2 >
resolution
resolution
octomap_server::OctomapServer::m_treeDepth
unsigned m_treeDepth
OcTreeBaseImpl< OcTreeNode, AbstractOccupancyOcTree >::end
const iterator end() const
ros::NodeHandle::param
T param(const std::string &param_name, const T &default_val) const
pcl::toROSMsg
void toROSMsg(const pcl::PointCloud< T > &cloud, sensor_msgs::Image &msg)
octomap_server::OctomapServer
octomap_server::OctomapServer::m_tfListener
tf::TransformListener m_tfListener
octomap_server::OctomapServer::handleOccupiedNodeInBBX
virtual void handleOccupiedNodeInBBX(const OcTreeT::iterator &it)
octomap
octomap::KeyRay::begin
iterator begin()
ros::Publisher::getNumSubscribers
uint32_t getNumSubscribers() const
test_contact_sensor.datas
datas
Definition: test_contact_sensor.py:16
jsk_pcl_ros::OctomapServerContact::m_publishFrontierSpace
bool m_publishFrontierSpace
Definition: octomap_server_contact.h:85
attention_pose_set.y
y
Definition: attention_pose_set.py:19
tf::Transformer::lookupTransform
void lookupTransform(const std::string &target_frame, const ros::Time &target_time, const std::string &source_frame, const ros::Time &source_time, const std::string &fixed_frame, StampedTransform &transform) const
jsk_pcl_ros::OctomapServerContact::initContactSensor
virtual void initContactSensor(const ros::NodeHandle &privateNh)
Definition: octomap_server_contact_nodelet.cpp:121
tf2::TransformException
octomath::Vector3::z
float & z()
a
char a[26]
OccupancyOcTreeBase< OcTreeNode >::updateNode
virtual OcTreeNode * updateNode(const OcTreeKey &key, bool occupied, bool lazy_eval=false)
tf::createQuaternionMsgFromYaw
static geometry_msgs::Quaternion createQuaternionMsgFromYaw(double yaw)
jsk_pcl_ros::OctomapServerContact::m_offsetVisualizeUnknown
double m_offsetVisualizeUnknown
Definition: octomap_server_contact.h:83
octomap_server::OctomapServer::publishFullOctoMap
void publishFullOctoMap(const ros::Time &rostime=ros::Time::now()) const
octomap_server::OctomapServer::m_maxTreeDepth
unsigned m_maxTreeDepth
octomath::Vector3::x
float & x()
robot_self_filter::LinkInfo::name
std::string name
size
size
jsk_pcl_ros::OctomapServerContact::insertContactSensor
virtual void insertContactSensor(const jsk_recognition_msgs::ContactSensorArray::ConstPtr &msg)
Definition: octomap_server_contact_nodelet.cpp:315
pose_with_covariance_sample.msg
msg
Definition: pose_with_covariance_sample.py:22
n
GLfloat n[6][3]
octomap_server::OctomapServer::handleNodeInBBX
virtual void handleNodeInBBX(const OcTreeT::iterator &it)
octomap_server::OctomapServer::m_markerPub
ros::Publisher m_markerPub
octomap_server::OctomapServer::handlePostNodeTraversal
virtual void handlePostNodeTraversal(const ros::Time &rostime)
robot_self_filter::INSIDE
INSIDE
XmlRpc::XmlRpcValue
octomap_server::OctomapServer::m_worldFrameId
std::string m_worldFrameId
tf::Transform::getOrigin
TFSIMD_FORCE_INLINE Vector3 & getOrigin()
jsk_pcl_ros::OctomapServerContact::m_occupancyMaxX
double m_occupancyMaxX
Definition: octomap_server_contact.h:90
jsk_pcl_ros::OctomapServerContact::m_octreeContact
octomap::OcTreeContact * m_octreeContact
Definition: octomap_server_contact.h:98
ros::NodeHandle
octomap_server::OctomapServer::m_useHeightMap
bool m_useHeightMap
attention_pose_set.z
z
Definition: attention_pose_set.py:20
octomap_server::OctomapServer::m_color
std_msgs::ColorRGBA m_color
OcTreeBaseImpl< OcTreeNode, AbstractOccupancyOcTree >::getMetricMin
virtual void getMetricMin(double &x, double &y, double &z)
octomap_server::OctomapServer::m_binaryMapPub
ros::Publisher m_binaryMapPub
jsk_pcl_ros::OctomapServerContact::m_contactSensorSub
message_filters::Subscriber< jsk_recognition_msgs::ContactSensorArray > m_contactSensorSub
Definition: octomap_server_contact.h:75


jsk_pcl_ros
Author(s): Yohei Kakiuchi
autogenerated on Tue Jan 7 2025 04:05:45