36 #include <boost/bind.hpp>
37 #include <boost/shared_ptr.hpp>
39 #include <OGRE/OgreSceneNode.h>
40 #include <OGRE/OgreSceneManager.h>
51 #include <octomap_msgs/Octomap.h>
78 OccupancyGridDisplay::OccupancyGridDisplay() :
80 new_points_received_(false),
81 messages_received_(0),
88 QString::fromStdString(ros::message_traits::datatype<octomap_msgs::Octomap>()),
89 "octomap_msgs::Octomap topic to subscribe to (binary or full probability map)",
95 "Advanced: set the size of the incoming message queue. Increasing this "
96 "is useful if your incoming TF data is delayed significantly from your"
97 " image data, but it can greatly increase memory usage if the messages are big.",
103 "Select voxel type.",
112 "Select voxel coloring mode",
127 "Defines the maximum tree depth",
133 std::numeric_limits<double>::infinity(),
134 "Defines the maximum height to display",
139 -std::numeric_limits<double>::infinity(),
140 "Defines the minimum height to display",
147 boost::mutex::scoped_lock lock(
mutex_);
156 std::stringstream sname;
157 sname <<
"PointCloud Nr." << i;
159 cloud_[i]->setName(sname.str());
171 for (std::vector<rviz::PointCloud*>::iterator it =
cloud_.begin(); it !=
cloud_.end(); ++it) {
213 if (!topicStr.empty())
225 setStatus(StatusProperty::Error,
"Topic", (std::string(
"Error subscribing: ") + e.what()).c_str());
241 setStatus(StatusProperty::Error,
"Topic", (std::string(
"Error unsubscribing: ") + e.what()).c_str());
256 double h = (1.0 - std::min(std::max((z_pos - min_z) / (max_z - min_z), 0.0), 1.0)) * color_factor;
327 boost::mutex::scoped_lock lock(
mutex_);
330 for (
size_t i = 0; i <
cloud_.size(); ++i)
340 boost::mutex::scoped_lock lock(
mutex_);
347 cloud_[i]->setDimensions(size, size, size);
362 setStatus(StatusProperty::Ok,
"Messages", QString(
"0 binary octomap messages received"));
373 template <
typename OcTreeType>
377 setStatus(StatusProperty::Warn,
"Messages", QString(
"Cannot verify octomap type"));
384 if(type_id ==
"OcTreeStamped")
return true;
390 if(type_id ==
"OcTree")
return true;
397 if(type_id ==
"ColorOcTree")
return true;
401 template <
typename OcTreeType>
403 typename OcTreeType::NodeType& node,
404 double minZ,
double maxZ)
407 float cell_probability;
408 switch (octree_color_mode)
411 setStatus(StatusProperty::Error,
"Messages", QString(
"Cannot extract color"));
414 setColor(newPoint.position.z, minZ, maxZ, color_factor_, newPoint);
417 cell_probability = node.getOccupancy();
418 newPoint.setColor((1.0
f-cell_probability), cell_probability, 0.0);
429 double minZ,
double maxZ)
431 float cell_probability;
433 switch (octree_color_mode)
437 const float b2f = 1./256.;
439 newPoint.setColor(b2f*color.
r, b2f*color.
g, b2f*color.
b, node.getOccupancy());
443 setColor(newPoint.position.z, minZ, maxZ, color_factor_, newPoint);
446 cell_probability = node.getOccupancy();
447 newPoint.setColor((1.0
f-cell_probability), cell_probability, 0.0);
459 Ogre::Quaternion orient;
470 template <
typename OcTreeType>
473 ++messages_received_;
474 setStatus(StatusProperty::Ok,
"Messages", QString::number(messages_received_) +
" octomap messages received");
475 setStatusStd(StatusProperty::Ok,
"Type", msg->id.c_str());
476 if(!checkType(msg->id)){
477 setStatusStd(StatusProperty::Error,
"Message",
"Wrong octomap type. Use a different display type.");
481 ROS_DEBUG(
"Received OctomapBinary message (size: %d bytes)", (
int)msg->data.size());
483 header_ = msg->header;
484 if (!updateFromTF()) {
485 std::stringstream ss;
486 ss <<
"Failed to transform from frame [" << header_.frame_id <<
"] to frame ["
487 << context_->getFrameManager()->getFixedFrame() <<
"]";
488 setStatusStd(StatusProperty::Error,
"Message", ss.str());
498 setStatusStd(StatusProperty::Error,
"Message",
"Wrong octomap type. Use a different display type.");
503 setStatusStd(StatusProperty::Error,
"Message",
"Failed to deserialize octree message.");
508 tree_depth_property_->setMax(
octomap->getTreeDepth());
511 double minX, minY, minZ, maxX, maxY, maxZ;
512 octomap->getMetricMin(minX, minY, minZ);
513 octomap->getMetricMax(maxX, maxY, maxZ);
518 point_buf_[i].clear();
519 box_size_[i] =
octomap->getNodeSize(i + 1);
522 size_t pointCount = 0;
525 unsigned int treeDepth = std::min<unsigned int>(tree_depth_property_->getInt(),
octomap->getTreeDepth());
526 double maxHeight = std::min<double>(max_height_property_->getFloat(), maxZ);
527 double minHeight = std::max<double>(min_height_property_->getFloat(), minZ);
528 int stepSize = 1 << (
octomap->getTreeDepth() - treeDepth);
529 for (
typename OcTreeType::iterator it =
octomap->begin(treeDepth), end =
octomap->end(); it != end; ++it)
531 if(it.getZ() <= maxHeight && it.getZ() >= minHeight)
533 int render_mode_mask = octree_render_property_->getOptionInt();
535 bool display_voxel =
false;
538 if (((
int)
octomap->isNodeOccupied(*it) + 1) & render_mode_mask)
541 bool allNeighborsFound =
true;
548 int diffBase = (it.getDepth() <
octomap->getTreeDepth()) ? 1 << (
octomap->getTreeDepth() - it.getDepth() - 1) : 1;
549 int diff[2] = {-((it.getDepth() ==
octomap->getTreeDepth()) ? diffBase : diffBase + 1), diffBase};
552 for (
unsigned int idxCase = 0; idxCase < 3; ++idxCase)
554 int idx_0 = idxCase % 3;
555 int idx_1 = (idxCase + 1) % 3;
556 int idx_2 = (idxCase + 2) % 3;
558 for (
int i = 0; allNeighborsFound && i < 2; ++i)
560 key[idx_0] = nKey[idx_0] + diff[i];
562 for (key[idx_1] = nKey[idx_1] + diff[0] + 1; allNeighborsFound && key[idx_1] < nKey[idx_1] + diff[1]; key[idx_1] += stepSize)
564 for (key[idx_2] = nKey[idx_2] + diff[0] + 1; allNeighborsFound && key[idx_2] < nKey[idx_2] + diff[1]; key[idx_2] += stepSize)
566 typename OcTreeType::NodeType* node =
octomap->search(key, treeDepth);
569 if (!(node && ((((
int)
octomap->isNodeOccupied(node)) + 1) & render_mode_mask)))
572 allNeighborsFound =
false;
579 display_voxel |= !allNeighborsFound;
585 PointCloud::Point newPoint;
587 newPoint.position.x = it.getX();
588 newPoint.position.y = it.getY();
589 newPoint.position.z = it.getZ();
593 setVoxelColor(newPoint, *it, minZ, maxZ);
595 unsigned int depth = it.getDepth();
596 point_buf_[depth - 1].push_back(newPoint);
606 boost::mutex::scoped_lock lock(mutex_);
608 new_points_received_ =
true;
611 new_points_[i].
swap(point_buf_[i]);