41 #include <octomap_msgs/Octomap.h>
51 OccupancyMapDisplay::OccupancyMapDisplay()
62 "Defines the maximum tree depth",
103 if (!topicStr.empty())
115 setStatus(StatusProperty::Error,
"Topic", (std::string(
"Error subscribing: ") + e.what()).c_str());
130 setStatus(StatusProperty::Error,
"Topic", (std::string(
"Error unsubscribing: ") + e.what()).c_str());
135 template <
typename OcTreeType>
139 ROS_DEBUG(
"Received OctomapBinary message (size: %d bytes)", (
int)msg->data.size());
150 this->setStatusStd(StatusProperty::Error,
"Message",
"Failed to create octree structure");
155 double minX, minY, minZ, maxX, maxY, maxZ;
156 octomap->getMetricMin(minX, minY, minZ);
157 octomap->getMetricMax(maxX, maxY, maxZ);
160 unsigned int tree_depth =
octomap->getTreeDepth();
164 nav_msgs::OccupancyGrid::Ptr occupancy_map (
new nav_msgs::OccupancyGrid());
166 unsigned int width, height;
169 unsigned int ds_shift = tree_depth-octree_depth_;
171 occupancy_map->header = msg->header;
172 occupancy_map->info.resolution = res =
octomap->getNodeSize(octree_depth_);
173 occupancy_map->info.width = width = (maxX-minX) / res + 1;
174 occupancy_map->info.height = height = (maxY-minY) / res + 1;
175 occupancy_map->info.origin.position.x = minX - (res / (float)(1<<ds_shift) ) + res;
176 occupancy_map->info.origin.position.y = minY - (res / (float)(1<<ds_shift) );
178 occupancy_map->data.clear();
179 occupancy_map->data.resize(width*height, -1);
182 unsigned int treeDepth = std::min<unsigned int>(octree_depth_,
octomap->getTreeDepth());
183 for (
typename OcTreeType::iterator it =
octomap->begin(treeDepth), end =
octomap->end(); it != end; ++it)
185 bool occupied =
octomap->isNodeOccupied(*it);
186 int intSize = 1 << (octree_depth_ - it.getDepth());
190 for (
int dx = 0; dx < intSize; dx++)
192 for (
int dy = 0; dy < intSize; dy++)
194 int posX = std::max<int>(0, minKey[0] + dx - paddedMinKey[0]);
197 int posY = std::max<int>(0, minKey[1] + dy - paddedMinKey[1]);
200 int idx = width * posY + posX;
203 occupancy_map->data[idx] = 100;
204 else if (occupancy_map->data[idx] == -1)
206 occupancy_map->data[idx] = 0;
216 this->incomingMap(occupancy_map);