occupancy_map_display.cpp
Go to the documentation of this file.
1 /*
2  * Copyright (c) 2013, Willow Garage, Inc.
3  * All rights reserved.
4  *
5  * Redistribution and use in source and binary forms, with or without
6  * modification, are permitted provided that the following conditions are met:
7  *
8  * * Redistributions of source code must retain the above copyright
9  * notice, this list of conditions and the following disclaimer.
10  * * Redistributions in binary form must reproduce the above copyright
11  * notice, this list of conditions and the following disclaimer in the
12  * documentation and/or other materials provided with the distribution.
13  * * Neither the name of the Willow Garage, Inc. nor the names of its
14  * contributors may be used to endorse or promote products derived from
15  * this software without specific prior written permission.
16  *
17  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
18  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
19  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
20  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
21  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
22  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
23  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
24  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
25  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
26  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
27  * POSSIBILITY OF SUCH DAMAGE.
28  *
29  * Author: Julius Kammerl (jkammerl@willowgarage.com)
30  *
31  */
32 
33 
35 
39 
40 #include <octomap/octomap.h>
41 #include <octomap_msgs/Octomap.h>
43 
44 using namespace rviz;
45 
46 namespace octomap_rviz_plugin
47 {
48 
49 static const std::size_t max_octree_depth_ = sizeof(unsigned short) * 8;
50 
51 OccupancyMapDisplay::OccupancyMapDisplay()
52  : rviz::MapDisplay()
53  , octree_depth_ (max_octree_depth_)
54 {
55 
56  topic_property_->setName("Octomap Binary Topic");
57  topic_property_->setMessageType(QString::fromStdString(ros::message_traits::datatype<octomap_msgs::Octomap>()));
58  topic_property_->setDescription("octomap_msgs::OctomapBinary topic to subscribe to.");
59 
60  tree_depth_property_ = new IntProperty("Max. Octree Depth",
62  "Defines the maximum tree depth",
63  this,
64  SLOT (updateTreeDepth() ));
65 }
66 
68 {
69  unsubscribe();
70 }
71 
73 {
75 }
76 
78 {
80 }
81 
83 {
84  unsubscribe();
85  reset();
86  subscribe();
88 }
89 
91 {
92  if (!isEnabled())
93  {
94  return;
95  }
96 
97  try
98  {
99  unsubscribe();
100 
101  const std::string& topicStr = topic_property_->getStdString();
102 
103  if (!topicStr.empty())
104  {
105 
107 
108  sub_->subscribe(threaded_nh_, topicStr, 5);
109  sub_->registerCallback(boost::bind(&OccupancyMapDisplay::handleOctomapBinaryMessage, this, _1));
110 
111  }
112  }
113  catch (ros::Exception& e)
114  {
115  setStatus(StatusProperty::Error, "Topic", (std::string("Error subscribing: ") + e.what()).c_str());
116  }
117 }
118 
120 {
121  clear();
122 
123  try
124  {
125  // reset filters
126  sub_.reset();
127  }
128  catch (ros::Exception& e)
129  {
130  setStatus(StatusProperty::Error, "Topic", (std::string("Error unsubscribing: ") + e.what()).c_str());
131  }
132 }
133 
134 
135 template <typename OcTreeType>
136 void TemplatedOccupancyMapDisplay<OcTreeType>::handleOctomapBinaryMessage(const octomap_msgs::OctomapConstPtr& msg)
137 {
138 
139  ROS_DEBUG("Received OctomapBinary message (size: %d bytes)", (int)msg->data.size());
140 
141  // creating octree
142  OcTreeType* octomap = NULL;
144  if (tree){
145  octomap = dynamic_cast<OcTreeType*>(tree);
146  }
147 
148  if (!octomap)
149  {
150  this->setStatusStd(StatusProperty::Error, "Message", "Failed to create octree structure");
151  return;
152  }
153 
154  // get dimensions of octree
155  double minX, minY, minZ, maxX, maxY, maxZ;
156  octomap->getMetricMin(minX, minY, minZ);
157  octomap->getMetricMax(maxX, maxY, maxZ);
158  octomap::point3d minPt = octomap::point3d(minX, minY, minZ);
159 
160  unsigned int tree_depth = octomap->getTreeDepth();
161 
162  octomap::OcTreeKey paddedMinKey = octomap->coordToKey(minPt);
163 
164  nav_msgs::OccupancyGrid::Ptr occupancy_map (new nav_msgs::OccupancyGrid());
165 
166  unsigned int width, height;
167  double res;
168 
169  unsigned int ds_shift = tree_depth-octree_depth_;
170 
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) );
177 
178  occupancy_map->data.clear();
179  occupancy_map->data.resize(width*height, -1);
180 
181  // traverse all leafs in the tree:
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)
184  {
185  bool occupied = octomap->isNodeOccupied(*it);
186  int intSize = 1 << (octree_depth_ - it.getDepth());
187 
188  octomap::OcTreeKey minKey=it.getIndexKey();
189 
190  for (int dx = 0; dx < intSize; dx++)
191  {
192  for (int dy = 0; dy < intSize; dy++)
193  {
194  int posX = std::max<int>(0, minKey[0] + dx - paddedMinKey[0]);
195  posX>>=ds_shift;
196 
197  int posY = std::max<int>(0, minKey[1] + dy - paddedMinKey[1]);
198  posY>>=ds_shift;
199 
200  int idx = width * posY + posX;
201 
202  if (occupied)
203  occupancy_map->data[idx] = 100;
204  else if (occupancy_map->data[idx] == -1)
205  {
206  occupancy_map->data[idx] = 0;
207  }
208 
209  }
210  }
211 
212  }
213 
214  delete octomap;
215 
216  this->incomingMap(occupancy_map);
217 }
218 
219 } // namespace rviz
220 
224 
226 PLUGINLIB_EXPORT_CLASS( OcTreeStampedMapDisplay, rviz::Display)
void handleOctomapBinaryMessage(const octomap_msgs::OctomapConstPtr &msg)
#define NULL
void setStatusStd(StatusProperty::Level level, const std::string &name, const std::string &text)
virtual void reset()
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()
bool isEnabled() const
void setMessageType(const QString &message_type)
void incomingMap(const nav_msgs::OccupancyGrid::ConstPtr &msg)
tree
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_
octomath::Vector3 point3d
#define PLUGINLIB_EXPORT_CLASS(class_type, base_class_type)
virtual void setStatus(StatusProperty::Level level, const QString &name, const QString &text)
#define ROS_DEBUG(...)


octomap_rviz_plugins
Author(s): Julius Kammerl
autogenerated on Wed Jan 20 2021 03:10:00