41 #include <octomap_msgs/Octomap.h> 51 OccupancyMapDisplay::OccupancyMapDisplay()
53 , octree_depth_ (max_octree_depth_)
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());
145 octomap =
dynamic_cast<OcTreeType*
>(tree);
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;
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;
void handleOctomapBinaryMessage(const octomap_msgs::OctomapConstPtr &msg)
void setStatusStd(StatusProperty::Level level, const std::string &name, const std::string &text)
static const std::size_t max_octree_depth_
octomap_rviz_plugin::TemplatedOccupancyMapDisplay< octomap::OcTreeStamped > OcTreeStampedMapDisplay
DisplayContext * context_
virtual int getInt() const
static octomap::AbstractOcTree * msgToMap(const Octomap &msg)
virtual void onInitialize()
virtual void setName(const QString &name)
virtual void handleOctomapBinaryMessage(const octomap_msgs::OctomapConstPtr &msg)=0
virtual void setDescription(const QString &description)
std::string getStdString()
void setMessageType(const QString &message_type)
rviz::IntProperty * tree_depth_property_
virtual ~OccupancyMapDisplay()
void incomingMap(const nav_msgs::OccupancyGrid::ConstPtr &msg)
octomap_rviz_plugin::TemplatedOccupancyMapDisplay< octomap::OcTree > OcTreeMapDisplay
RosTopicProperty * topic_property_
boost::shared_ptr< message_filters::Subscriber< octomap_msgs::Octomap > > sub_
virtual void queueRender()=0
ros::NodeHandle threaded_nh_
virtual void unsubscribe()
octomath::Vector3 point3d
unsigned int octree_depth_
virtual void onInitialize()
#define PLUGINLIB_EXPORT_CLASS(class_type, base_class_type)
virtual void setStatus(StatusProperty::Level level, const QString &name, const QString &text)