map_display.cpp
Go to the documentation of this file.
1 /*
2  * Copyright (c) 2008, 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 
30 #include <boost/bind.hpp>
31 
32 #include <OgreManualObject.h>
33 #include <OgreMaterialManager.h>
34 #include <OgreSceneManager.h>
35 #include <OgreSceneNode.h>
36 #include <OgreTextureManager.h>
37 #include <OgreTechnique.h>
38 #include <OgreSharedPtr.h>
39 
40 #include <ros/ros.h>
41 
42 #include "rviz/frame_manager.h"
44 #include "rviz/ogre_helpers/grid.h"
52 #include "rviz/validate_floats.h"
54 #include "rviz/display_context.h"
55 
56 #include "map_display.h"
57 
58 namespace rviz
59 {
60 // helper class to set alpha parameter on all renderables.
61 class AlphaSetter : public Ogre::Renderable::Visitor
62 {
63 public:
64  AlphaSetter(float alpha) : alpha_vec_(alpha, alpha, alpha, alpha)
65  {
66  }
67 
68  void visit(Ogre::Renderable* rend,
69  ushort /*lodIndex*/,
70  bool /*isDebug*/,
71  Ogre::Any* /*pAny*/ = nullptr) override
72  {
73  rend->setCustomParameter(ALPHA_PARAMETER, alpha_vec_);
74  }
75 
76 private:
77  Ogre::Vector4 alpha_vec_;
78 };
79 
80 
82  unsigned int x,
83  unsigned int y,
84  unsigned int width,
85  unsigned int height,
86  float resolution)
87  : parent_(parent), manual_object_(nullptr), x_(x), y_(y), width_(width), height_(height)
88 {
89  // Set up map material
90  static int material_count = 0;
91  std::stringstream ss;
92  ss << "MapMaterial" << material_count++;
93  material_ = Ogre::MaterialManager::getSingleton().getByName("rviz/Indexed8BitImage");
94  material_ = material_->clone(ss.str());
95 
96  material_->setReceiveShadows(false);
97  material_->getTechnique(0)->setLightingEnabled(false);
98  material_->setDepthBias(-16.0f, 0.0f);
99  material_->setCullingMode(Ogre::CULL_NONE);
100  material_->setDepthWriteEnabled(false);
101 
102  static int map_count = 0;
103  std::stringstream ss2;
104  ss2 << "MapObject" << map_count++;
105  manual_object_ = parent_->scene_manager_->createManualObject(ss2.str());
106 
107  static int node_count = 0;
108  std::stringstream ss3;
109  ss3 << "NodeObject" << node_count++;
110 
111  scene_node_ = parent_->scene_node_->createChildSceneNode(ss3.str());
112  scene_node_->attachObject(manual_object_);
113 
114  manual_object_->begin(material_->getName(), Ogre::RenderOperation::OT_TRIANGLE_LIST);
115  {
116  // First triangle
117  {
118  // Bottom left
119  manual_object_->position(0.0f, 0.0f, 0.0f);
120  manual_object_->textureCoord(0.0f, 0.0f);
121  manual_object_->normal(0.0f, 0.0f, 1.0f);
122 
123  // Top right
124  manual_object_->position(1.0f, 1.0f, 0.0f);
125  manual_object_->textureCoord(1.0f, 1.0f);
126  manual_object_->normal(0.0f, 0.0f, 1.0f);
127 
128  // Top left
129  manual_object_->position(0.0f, 1.0f, 0.0f);
130  manual_object_->textureCoord(0.0f, 1.0f);
131  manual_object_->normal(0.0f, 0.0f, 1.0f);
132  }
133 
134  // Second triangle
135  {
136  // Bottom left
137  manual_object_->position(0.0f, 0.0f, 0.0f);
138  manual_object_->textureCoord(0.0f, 0.0f);
139  manual_object_->normal(0.0f, 0.0f, 1.0f);
140 
141  // Bottom right
142  manual_object_->position(1.0f, 0.0f, 0.0f);
143  manual_object_->textureCoord(1.0f, 0.0f);
144  manual_object_->normal(0.0f, 0.0f, 1.0f);
145 
146  // Top right
147  manual_object_->position(1.0f, 1.0f, 0.0f);
148  manual_object_->textureCoord(1.0f, 1.0f);
149  manual_object_->normal(0.0f, 0.0f, 1.0f);
150  }
151  }
152  manual_object_->end();
153 
154  scene_node_->setPosition(x * resolution, y * resolution, 0);
155  scene_node_->setScale(width * resolution, height * resolution, 1.0);
156 
157  if (parent_->draw_under_property_->getValue().toBool())
158  {
159  manual_object_->setRenderQueueGroup(Ogre::RENDER_QUEUE_4);
160  }
161 
162  // don't show map until the plugin is actually enabled
163  manual_object_->setVisible(false);
164 }
165 
167 {
168  parent_->scene_manager_->destroyManualObject(manual_object_);
169 }
170 
171 void Swatch::updateAlpha(const Ogre::SceneBlendType sceneBlending,
172  bool depthWrite,
173  AlphaSetter* alpha_setter)
174 {
175  material_->setSceneBlending(sceneBlending);
176  material_->setDepthWriteEnabled(depthWrite);
177  if (manual_object_)
178  {
179  manual_object_->visitRenderables(alpha_setter);
180  }
181 }
182 
184 {
185  unsigned int pixels_size = width_ * height_;
186  unsigned char* pixels = new unsigned char[pixels_size];
187  memset(pixels, 255, pixels_size);
188  unsigned char* ptr = pixels;
189  int N = parent_->current_map_.data.size();
190  unsigned int fw = parent_->current_map_.info.width;
191 
192  for (unsigned int yy = y_; yy < y_ + height_; yy++)
193  {
194  int index = yy * fw + x_;
195  int pixels_to_copy = std::min((int)width_, N - index);
196  memcpy(ptr, &parent_->current_map_.data[index], pixels_to_copy);
197  ptr += pixels_to_copy;
198  if (index + pixels_to_copy >= N)
199  break;
200  }
201 
202  Ogre::DataStreamPtr pixel_stream;
203  pixel_stream.bind(new Ogre::MemoryDataStream(pixels, pixels_size));
204 
205  if (!texture_.isNull())
206  {
207  Ogre::TextureManager::getSingleton().remove(texture_->getName());
208  texture_.setNull();
209  }
210 
211  static int tex_count = 0;
212  std::stringstream ss;
213  ss << "MapTexture" << tex_count++;
214  texture_ = Ogre::TextureManager::getSingleton().loadRawData(
215  ss.str(), Ogre::ResourceGroupManager::DEFAULT_RESOURCE_GROUP_NAME, pixel_stream, width_, height_,
216  Ogre::PF_L8, Ogre::TEX_TYPE_2D, 0);
217 
218  delete[] pixels;
219 }
220 
221 
222 MapDisplay::MapDisplay() : Display(), loaded_(false), resolution_(0.0f), width_(0), height_(0)
223 {
224  connect(this, SIGNAL(mapUpdated()), this, SLOT(showMap()));
226  "Topic", "", QString::fromStdString(ros::message_traits::datatype<nav_msgs::OccupancyGrid>()),
227  "nav_msgs::OccupancyGrid topic to subscribe to.", this, SLOT(updateTopic()));
228 
229  alpha_property_ = new FloatProperty("Alpha", 0.7, "Amount of transparency to apply to the map.", this,
230  SLOT(updateAlpha()));
233 
234  color_scheme_property_ = new EnumProperty("Color Scheme", "map", "How to color the occupancy values.",
235  this, SLOT(updatePalette()));
236  // Option values here must correspond to indices in palette_textures_ array in onInitialize() below.
238  color_scheme_property_->addOption("costmap", 1);
240 
242  "Draw Behind", false,
243  "Rendering option, controls whether or not the map is always drawn behind everything else.", this,
244  SLOT(updateDrawUnder()));
245 
247  new FloatProperty("Resolution", 0, "Resolution of the map. (not editable)", this);
249 
250  width_property_ = new IntProperty("Width", 0, "Width of the map, in meters. (not editable)", this);
252 
253  height_property_ = new IntProperty("Height", 0, "Height of the map, in meters. (not editable)", this);
255 
257  new VectorProperty("Position", Ogre::Vector3::ZERO,
258  "Position of the bottom left corner of the map, in meters. (not editable)",
259  this);
261 
262  orientation_property_ = new QuaternionProperty("Orientation", Ogre::Quaternion::IDENTITY,
263  "Orientation of the map. (not editable)", this);
265 
267  new BoolProperty("Unreliable", false, "Prefer UDP topic transport", this, SLOT(updateTopic()));
268 
270  "Use Timestamp", false, "Use map header timestamp when transforming", this, SLOT(transformMap()));
271 }
272 
274 {
275  unsubscribe();
276  clear();
277  for (unsigned i = 0; i < swatches.size(); i++)
278  {
279  delete swatches[i];
280  }
281  swatches.clear();
282 }
283 
284 unsigned char* makeMapPalette()
285 {
286  unsigned char* palette = OGRE_ALLOC_T(unsigned char, 256 * 4, Ogre::MEMCATEGORY_GENERAL);
287  unsigned char* palette_ptr = palette;
288  // Standard gray map palette values
289  for (int i = 0; i <= 100; i++)
290  {
291  unsigned char v = 255 - (255 * i) / 100;
292  *palette_ptr++ = v; // red
293  *palette_ptr++ = v; // green
294  *palette_ptr++ = v; // blue
295  *palette_ptr++ = 255; // alpha
296  }
297  // illegal positive values in green
298  for (int i = 101; i <= 127; i++)
299  {
300  *palette_ptr++ = 0; // red
301  *palette_ptr++ = 255; // green
302  *palette_ptr++ = 0; // blue
303  *palette_ptr++ = 255; // alpha
304  }
305  // illegal negative (char) values in shades of red/yellow
306  for (int i = 128; i <= 254; i++)
307  {
308  *palette_ptr++ = 255; // red
309  *palette_ptr++ = (255 * (i - 128)) / (254 - 128); // green
310  *palette_ptr++ = 0; // blue
311  *palette_ptr++ = 255; // alpha
312  }
313  // legal -1 value is tasteful blueish greenish grayish color
314  *palette_ptr++ = 0x70; // red
315  *palette_ptr++ = 0x89; // green
316  *palette_ptr++ = 0x86; // blue
317  *palette_ptr++ = 255; // alpha
318 
319  return palette;
320 }
321 
322 unsigned char* makeCostmapPalette()
323 {
324  unsigned char* palette = OGRE_ALLOC_T(unsigned char, 256 * 4, Ogre::MEMCATEGORY_GENERAL);
325  unsigned char* palette_ptr = palette;
326 
327  // zero values have alpha=0
328  *palette_ptr++ = 0; // red
329  *palette_ptr++ = 0; // green
330  *palette_ptr++ = 0; // blue
331  *palette_ptr++ = 0; // alpha
332 
333  // Blue to red spectrum for most normal cost values
334  for (int i = 1; i <= 98; i++)
335  {
336  unsigned char v = (255 * i) / 100;
337  *palette_ptr++ = v; // red
338  *palette_ptr++ = 0; // green
339  *palette_ptr++ = 255 - v; // blue
340  *palette_ptr++ = 255; // alpha
341  }
342  // inscribed obstacle values (99) in cyan
343  *palette_ptr++ = 0; // red
344  *palette_ptr++ = 255; // green
345  *palette_ptr++ = 255; // blue
346  *palette_ptr++ = 255; // alpha
347  // lethal obstacle values (100) in purple
348  *palette_ptr++ = 255; // red
349  *palette_ptr++ = 0; // green
350  *palette_ptr++ = 255; // blue
351  *palette_ptr++ = 255; // alpha
352  // illegal positive values in green
353  for (int i = 101; i <= 127; i++)
354  {
355  *palette_ptr++ = 0; // red
356  *palette_ptr++ = 255; // green
357  *palette_ptr++ = 0; // blue
358  *palette_ptr++ = 255; // alpha
359  }
360  // illegal negative (char) values in shades of red/yellow
361  for (int i = 128; i <= 254; i++)
362  {
363  *palette_ptr++ = 255; // red
364  *palette_ptr++ = (255 * (i - 128)) / (254 - 128); // green
365  *palette_ptr++ = 0; // blue
366  *palette_ptr++ = 255; // alpha
367  }
368  // legal -1 value is tasteful blueish greenish grayish color
369  *palette_ptr++ = 0x70; // red
370  *palette_ptr++ = 0x89; // green
371  *palette_ptr++ = 0x86; // blue
372  *palette_ptr++ = 255; // alpha
373 
374  return palette;
375 }
376 
377 unsigned char* makeRawPalette()
378 {
379  unsigned char* palette = OGRE_ALLOC_T(unsigned char, 256 * 4, Ogre::MEMCATEGORY_GENERAL);
380  unsigned char* palette_ptr = palette;
381  // Standard gray map palette values
382  for (int i = 0; i < 256; i++)
383  {
384  *palette_ptr++ = i; // red
385  *palette_ptr++ = i; // green
386  *palette_ptr++ = i; // blue
387  *palette_ptr++ = 255; // alpha
388  }
389 
390  return palette;
391 }
392 
393 Ogre::TexturePtr makePaletteTexture(unsigned char* palette_bytes)
394 {
395  Ogre::DataStreamPtr palette_stream;
396  palette_stream.bind(new Ogre::MemoryDataStream(palette_bytes, 256 * 4, true));
397 
398  static int palette_tex_count = 0;
399  std::stringstream ss;
400  ss << "MapPaletteTexture" << palette_tex_count++;
401  return Ogre::TextureManager::getSingleton().loadRawData(
402  ss.str(), Ogre::ResourceGroupManager::DEFAULT_RESOURCE_GROUP_NAME, palette_stream, 256, 1,
403  Ogre::PF_BYTE_RGBA, Ogre::TEX_TYPE_1D, 0);
404 }
405 
407 {
408  // Order of palette textures here must match option indices for color_scheme_property_ above.
410  color_scheme_transparency_.push_back(false);
412  color_scheme_transparency_.push_back(true);
414  color_scheme_transparency_.push_back(true);
415 }
416 
418 {
419  subscribe();
420 }
421 
423 {
424  unsubscribe();
425  clear();
426 }
427 
429 {
430  if (!isEnabled())
431  {
432  return;
433  }
434 
435  if (!topic_property_->getTopic().isEmpty())
436  {
437  try
438  {
440  {
442  this, ros::TransportHints().unreliable());
443  }
444  else
445  {
447  this, ros::TransportHints().reliable());
448  }
449  setStatus(StatusProperty::Ok, "Topic", "OK");
450  }
451  catch (ros::Exception& e)
452  {
453  setStatus(StatusProperty::Error, "Topic", QString("Error subscribing: ") + e.what());
454  }
455 
456  try
457  {
460  setStatus(StatusProperty::Ok, "Update Topic", "OK");
461  }
462  catch (ros::Exception& e)
463  {
464  setStatus(StatusProperty::Error, "Update Topic", QString("Error subscribing: ") + e.what());
465  }
466  }
467 }
468 
470 {
471  map_sub_.shutdown();
473 }
474 
476 {
477  float alpha = alpha_property_->getFloat();
478  Ogre::SceneBlendType sceneBlending;
479  bool depthWrite;
480 
482  {
483  sceneBlending = Ogre::SBT_TRANSPARENT_ALPHA;
484  depthWrite = false;
485  }
486  else
487  {
488  sceneBlending = Ogre::SBT_REPLACE;
489  depthWrite = !draw_under_property_->getValue().toBool();
490  }
491 
492  AlphaSetter alpha_setter(alpha);
493 
494  for (unsigned i = 0; i < swatches.size(); i++)
495  {
496  swatches[i]->updateAlpha(sceneBlending, depthWrite, &alpha_setter);
497  }
498 }
499 
501 {
502  bool draw_under = draw_under_property_->getValue().toBool();
503 
504  if (alpha_property_->getFloat() >= 0.9998)
505  {
506  for (unsigned i = 0; i < swatches.size(); i++)
507  swatches[i]->material_->setDepthWriteEnabled(!draw_under);
508  }
509 
510  int group = draw_under ? Ogre::RENDER_QUEUE_4 : Ogre::RENDER_QUEUE_MAIN;
511  for (unsigned i = 0; i < swatches.size(); i++)
512  {
513  if (swatches[i]->manual_object_)
514  swatches[i]->manual_object_->setRenderQueueGroup(group);
515  }
516 }
517 
519 {
520  unsubscribe();
521  subscribe();
522  clear();
523 }
524 
526 {
527  setStatus(StatusProperty::Warn, "Message", "No map received");
528 
529  if (!loaded_)
530  {
531  return;
532  }
533 
534  for (unsigned i = 0; i < swatches.size(); i++)
535  {
536  if (swatches[i]->manual_object_)
537  swatches[i]->manual_object_->setVisible(false);
538 
539  if (!swatches[i]->texture_.isNull())
540  {
541  Ogre::TextureManager::getSingleton().remove(swatches[i]->texture_->getName());
542  swatches[i]->texture_.setNull();
543  }
544  }
545 
546  loaded_ = false;
547 }
548 
549 bool validateFloats(const nav_msgs::OccupancyGrid& msg)
550 {
551  bool valid = true;
552  valid = valid && validateFloats(msg.info.resolution);
553  valid = valid && validateFloats(msg.info.origin);
554  return valid;
555 }
556 
557 void MapDisplay::incomingMap(const nav_msgs::OccupancyGrid::ConstPtr& msg)
558 {
559  current_map_ = *msg;
560  // updated via signal in case ros spinner is in a different thread
561  Q_EMIT mapUpdated();
562  loaded_ = true;
563 }
564 
565 
566 void MapDisplay::incomingUpdate(const map_msgs::OccupancyGridUpdate::ConstPtr& update)
567 {
568  // Only update the map if we have gotten a full one first.
569  if (!loaded_)
570  {
571  return;
572  }
573 
574  // Reject updates which have any out-of-bounds data.
575  if (update->x < 0 || update->y < 0 || current_map_.info.width < update->x + update->width ||
576  current_map_.info.height < update->y + update->height)
577  {
578  setStatus(StatusProperty::Error, "Update", "Update area outside of original map area.");
579  return;
580  }
581 
582  // Copy the incoming data into current_map_'s data.
583  for (size_t y = 0; y < update->height; y++)
584  {
585  memcpy(&current_map_.data[(update->y + y) * current_map_.info.width + update->x],
586  &update->data[y * update->width], update->width);
587  }
588  // updated via signal in case ros spinner is in a different thread
589  Q_EMIT mapUpdated();
590 }
591 
593 {
594  int width = current_map_.info.width;
595  int height = current_map_.info.height;
596  float resolution = current_map_.info.resolution;
597 
598  int sw = width;
599  int sh = height;
600  int n_swatches = 1;
601 
602  for (int i = 0; i < 4; i++)
603  {
604  ROS_INFO("Creating %d swatches", n_swatches);
605  for (unsigned i = 0; i < swatches.size(); i++)
606  {
607  delete swatches[i];
608  }
609  swatches.clear();
610  try
611  {
612  int x = 0;
613  int y = 0;
614  for (int i = 0; i < n_swatches; i++)
615  {
616  int tw, th;
617  if (width - x - sw >= sw)
618  tw = sw;
619  else
620  tw = width - x;
621 
622  if (height - y - sh >= sh)
623  th = sh;
624  else
625  th = height - y;
626 
627  swatches.push_back(new Swatch(this, x, y, tw, th, resolution));
628  swatches[i]->updateData();
629 
630  x += tw;
631  if (x >= width)
632  {
633  x = 0;
634  y += sh;
635  }
636  }
637  updateAlpha();
638  return;
639  }
640  catch (Ogre::RenderingAPIException&)
641  {
642  ROS_WARN("Failed to create %d swatches", n_swatches);
643  if (sw > sh)
644  sw /= 2;
645  else
646  sh /= 2;
647  n_swatches *= 2;
648  }
649  }
650 }
651 
653 {
654  if (current_map_.data.empty())
655  {
656  return;
657  }
658 
660  {
662  "Message contained invalid floating point values (nans or infs)");
663  return;
664  }
665 
666  if (!validateQuaternions(current_map_.info.origin))
667  {
668  ROS_WARN_ONCE_NAMED("quaternions",
669  "Map received on topic '%s' contains unnormalized quaternions. "
670  "This warning will only be output once but may be true for others; "
671  "enable DEBUG messages for ros.rviz.quaternions to see more details.",
672  topic_property_->getTopicStd().c_str());
673  ROS_DEBUG_NAMED("quaternions", "Map received on topic '%s' contains unnormalized quaternions.",
674  topic_property_->getTopicStd().c_str());
675  }
676 
677  if (current_map_.info.width * current_map_.info.height == 0)
678  {
679  std::stringstream ss;
680  ss << "Map is zero-sized (" << current_map_.info.width << "x" << current_map_.info.height << ")";
681  setStatus(StatusProperty::Error, "Map", QString::fromStdString(ss.str()));
682  return;
683  }
684 
685  setStatus(StatusProperty::Ok, "Message", "Map received");
686 
687  ROS_DEBUG("Received a %d X %d map @ %.3f m/pix\n", current_map_.info.width, current_map_.info.height,
688  current_map_.info.resolution);
689 
690  float resolution = current_map_.info.resolution;
691 
692  int width = current_map_.info.width;
693  int height = current_map_.info.height;
694 
695  if (width != width_ || height != height_ || resolution_ != resolution)
696  {
697  createSwatches();
698  width_ = width;
699  height_ = height;
700  resolution_ = resolution;
701  }
702 
703  Ogre::Vector3 position(current_map_.info.origin.position.x, current_map_.info.origin.position.y,
704  current_map_.info.origin.position.z);
705  Ogre::Quaternion orientation;
706  normalizeQuaternion(current_map_.info.origin.orientation, orientation);
707 
708  frame_ = current_map_.header.frame_id;
709  if (frame_.empty())
710  {
711  frame_ = "/map";
712  }
713 
714  bool map_status_set = false;
715  if (width * height != static_cast<int>(current_map_.data.size()))
716  {
717  std::stringstream ss;
718  ss << "Data size doesn't match width*height: width = " << width << ", height = " << height
719  << ", data size = " << current_map_.data.size();
720  setStatus(StatusProperty::Error, "Map", QString::fromStdString(ss.str()));
721  map_status_set = true;
722  }
723 
724  for (size_t i = 0; i < swatches.size(); i++)
725  {
726  swatches[i]->updateData();
727 
728  Ogre::Pass* pass = swatches[i]->material_->getTechnique(0)->getPass(0);
729  Ogre::TextureUnitState* tex_unit = nullptr;
730  if (pass->getNumTextureUnitStates() > 0)
731  {
732  tex_unit = pass->getTextureUnitState(0);
733  }
734  else
735  {
736  tex_unit = pass->createTextureUnitState();
737  }
738 
739  tex_unit->setTextureName(swatches[i]->texture_->getName());
740  tex_unit->setTextureFiltering(Ogre::TFO_NONE);
741  swatches[i]->manual_object_->setVisible(true);
742  }
743 
744 
745  if (!map_status_set)
746  {
747  setStatus(StatusProperty::Ok, "Map", "Map OK");
748  }
749  updatePalette();
750 
751  resolution_property_->setValue(resolution);
752  width_property_->setValue(width);
753  height_property_->setValue(height);
754  position_property_->setVector(position);
755  orientation_property_->setQuaternion(orientation);
756 
757  transformMap();
758 
760 }
761 
763 {
764  int palette_index = color_scheme_property_->getOptionInt();
765 
766  for (unsigned i = 0; i < swatches.size(); i++)
767  {
768  Ogre::Pass* pass = swatches[i]->material_->getTechnique(0)->getPass(0);
769  Ogre::TextureUnitState* palette_tex_unit = nullptr;
770  if (pass->getNumTextureUnitStates() > 1)
771  {
772  palette_tex_unit = pass->getTextureUnitState(1);
773  }
774  else
775  {
776  palette_tex_unit = pass->createTextureUnitState();
777  }
778  palette_tex_unit->setTextureName(palette_textures_[palette_index]->getName());
779  palette_tex_unit->setTextureFiltering(Ogre::TFO_NONE);
780  }
781 
782  updateAlpha();
783 }
784 
786 {
787  if (!loaded_)
788  {
789  return;
790  }
791 
792  ros::Time transform_time;
793 
795  {
796  transform_time = current_map_.header.stamp;
797  }
798 
799  Ogre::Vector3 position;
800  Ogre::Quaternion orientation;
801  if (!context_->getFrameManager()->transform(frame_, transform_time, current_map_.info.origin, position,
802  orientation) &&
803  !context_->getFrameManager()->transform(frame_, ros::Time(0), current_map_.info.origin, position,
804  orientation))
805  {
806  ROS_DEBUG("Error transforming map '%s' from frame '%s' to frame '%s'", qPrintable(getName()),
807  frame_.c_str(), qPrintable(fixed_frame_));
808 
809  setStatus(StatusProperty::Error, "Transform",
810  "No transform from [" + QString::fromStdString(frame_) + "] to [" + fixed_frame_ + "]");
811  }
812  else
813  {
814  setStatus(StatusProperty::Ok, "Transform", "Transform OK");
815  }
816 
817  scene_node_->setPosition(position);
818  scene_node_->setOrientation(orientation);
819 }
820 
822 {
823  transformMap();
824 }
825 
827 {
828  Display::reset();
829 
830  clear();
831  // Force resubscription so that the map will be re-sent
832  updateTopic();
833 }
834 
835 void MapDisplay::setTopic(const QString& topic, const QString& /*datatype*/)
836 {
837  topic_property_->setString(topic);
838 }
839 
840 void MapDisplay::update(float /*wall_dt*/, float /*ros_dt*/)
841 {
842  transformMap();
843 }
844 
845 } // namespace rviz
846 
#define ALPHA_PARAMETER
void setMin(float min)
void updateData()
std::string frame_
Definition: map_display.h:166
unsigned char * makeCostmapPalette()
Ogre::TexturePtr makePaletteTexture(unsigned char *palette_bytes)
virtual void setString(const QString &str)
void setMax(float max)
unsigned char * makeMapPalette()
Ogre::ManualObject * manual_object_
Definition: map_display.h:85
TransportHints & reliable()
virtual bool setVector(const Ogre::Vector3 &vector)
f
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
DisplayContext * context_
This DisplayContext pointer is the main connection a Display has into the rest of rviz...
Definition: display.h:287
std::vector< Ogre::TexturePtr > palette_textures_
Definition: map_display.h:158
QuaternionProperty * orientation_property_
Definition: map_display.h:177
virtual void subscribe()
std::vector< bool > color_scheme_transparency_
Definition: map_display.h:159
ros::NodeHandle update_nh_
A NodeHandle whose CallbackQueue is run from the main GUI thread (the "update" thread).
Definition: display.h:300
Ogre::TexturePtr texture_
Definition: map_display.h:86
MapDisplay * parent_
Definition: map_display.h:84
FloatProperty * alpha_property_
Definition: map_display.h:178
void setReadOnly(bool read_only) override
Overridden from Property to propagate read-only-ness to children.
void incomingUpdate(const map_msgs::OccupancyGridUpdate::ConstPtr &update)
Copy update&#39;s data into current_map_ and call showMap().
unsigned char * makeRawPalette()
Ogre::MaterialPtr material_
Definition: map_display.h:87
Property specialized to enforce floating point max/min.
#define ROS_WARN(...)
void setReadOnly(bool read_only) override
Overridden from Property to propagate read-only-ness to children.
std::string getTopicStd() const
AlphaSetter(float alpha)
Definition: map_display.cpp:64
void onEnable() override
Derived classes override this to do the actual work of enabling themselves.
Property specialized to provide max/min enforcement for integers.
Definition: int_property.h:37
ros::Subscriber update_sub_
Definition: map_display.h:170
Ogre::SceneNode * scene_node_
The Ogre::SceneNode to hold all 3D scene elements shown by this Display.
Definition: display.h:295
VectorProperty * position_property_
Definition: map_display.h:176
void setTopic(const QString &topic, const QString &datatype) override
Set the ROS topic to listen to for this display.
FloatProperty * resolution_property_
Definition: map_display.h:173
QString fixed_frame_
A convenience variable equal to context_->getFixedFrame().
Definition: display.h:312
unsigned int x_
Definition: map_display.h:89
#define ROS_DEBUG_NAMED(name,...)
unsigned int y_
Definition: map_display.h:89
void update(float wall_dt, float ros_dt) override
Called periodically by the visualization manager.
TransportHints & unreliable()
virtual void unsubscribe()
bool validateFloats(const sensor_msgs::CameraInfo &msg)
virtual void addOption(const QString &option, int value=0)
bool setValue(const QVariant &new_value) override
Set the new value for this property. Returns true if the new value is different from the old value...
virtual void reset()
Called to tell the display to clear its state.
Definition: display.cpp:287
#define ROS_INFO(...)
std::vector< Swatch * > swatches
Definition: map_display.h:157
void showMap()
Show current_map_ in the scene.
virtual QString getName() const
Return the name of this Property as a QString.
Definition: property.cpp:164
Ogre::Vector4 alpha_vec_
Definition: map_display.cpp:77
virtual bool setQuaternion(const Ogre::Quaternion &quaternion)
void updateAlpha(const Ogre::SceneBlendType sceneBlending, bool depthWrite, AlphaSetter *alpha_setter)
void incomingMap(const nav_msgs::OccupancyGrid::ConstPtr &msg)
Copy msg into current_map_ and call showMap().
bool transform(const Header &header, const geometry_msgs::Pose &pose, Ogre::Vector3 &position, Ogre::Quaternion &orientation)
Transform a pose from a frame into the fixed frame.
virtual FrameManager * getFrameManager() const =0
Return the FrameManager instance.
EnumProperty * color_scheme_property_
Definition: map_display.h:180
Property(const QString &name=QString(), const QVariant default_value=QVariant(), const QString &description=QString(), Property *parent=nullptr, const char *changed_slot=nullptr, QObject *receiver=nullptr)
Constructor.
Definition: property.cpp:58
Displays a map along the XY plane.
Definition: map_display.h:97
RosTopicProperty * topic_property_
Definition: map_display.h:172
unsigned int height_
Definition: map_display.h:89
IntProperty * height_property_
Definition: map_display.h:175
friend class Swatch
Definition: map_display.h:99
float normalizeQuaternion(float &w, float &x, float &y, float &z)
#define ROS_WARN_ONCE_NAMED(name,...)
Ogre::SceneManager * scene_manager_
A convenience variable equal to context_->getSceneManager().
Definition: display.h:292
BoolProperty(const QString &name=QString(), bool default_value=false, const QString &description=QString(), Property *parent=nullptr, const char *changed_slot=nullptr, QObject *receiver=nullptr)
Property * draw_under_property_
Definition: map_display.h:179
BoolProperty * unreliable_property_
Definition: map_display.h:182
virtual void queueRender()=0
Queues a render. Multiple calls before a render happens will only cause a single render.
bool isEnabled() const
Return true if this Display is enabled, false if not.
Definition: display.cpp:268
ros::Subscriber map_sub_
Definition: map_display.h:169
bool setValue(const QVariant &new_value) override
Set the new value for this property. Returns true if the new value is different from the old value...
BoolProperty * transform_timestamp_property_
Definition: map_display.h:183
bool validateQuaternions(const visualization_msgs::InteractiveMarker &marker)
virtual float getFloat() const
unsigned int width_
Definition: map_display.h:89
void visit(Ogre::Renderable *rend, ushort, bool, Ogre::Any *=nullptr) override
Definition: map_display.cpp:68
Ogre::SceneNode * scene_node_
Definition: map_display.h:88
virtual QVariant getValue() const
Return the value of this Property as a QVariant. If the value has never been set, an invalid QVariant...
Definition: property.cpp:150
IntProperty * width_property_
Definition: map_display.h:174
void onInitialize() override
Override this function to do subclass-specific initialization.
void reset() override
Called to tell the display to clear its state.
~MapDisplay() override
virtual bool getBool() const
virtual void setReadOnly(bool read_only)
Prevent or allow users to edit this property from a PropertyTreeWidget.
Definition: property.h:436
virtual int getOptionInt()
Return the int value of the currently-chosen option, or 0 if the current option string does not have ...
void onDisable() override
Derived classes override this to do the actual work of disabling themselves.
#define PLUGINLIB_EXPORT_CLASS(class_type, base_class_type)
Enum property.
Definition: enum_property.h:46
void fixedFrameChanged() override
Called by setFixedFrame(). Override to respond to changes to fixed_frame_.
virtual void setStatus(StatusProperty::Level level, const QString &name, const QString &text)
Show status level and text. This is thread-safe.
Definition: display.cpp:175
nav_msgs::OccupancyGrid current_map_
Definition: map_display.h:167
Swatch(MapDisplay *parent, unsigned int x, unsigned int y, unsigned int width, unsigned int height, float resolution)
Definition: map_display.cpp:81
void mapUpdated()
Emitted when a new map is received.
#define ROS_DEBUG(...)


rviz
Author(s): Dave Hershberger, David Gossow, Josh Faust
autogenerated on Sat May 27 2023 02:06:24