30 #include <boost/bind.hpp> 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> 68 void visit(Ogre::Renderable* rend,
71 Ogre::Any* =
nullptr)
override 87 : parent_(parent), manual_object_(nullptr), x_(x), y_(y), width_(width), height_(height)
90 static int material_count = 0;
92 ss <<
"MapMaterial" << material_count++;
93 material_ = Ogre::MaterialManager::getSingleton().getByName(
"rviz/Indexed8BitImage");
97 material_->getTechnique(0)->setLightingEnabled(
false);
99 material_->setCullingMode(Ogre::CULL_NONE);
102 static int map_count = 0;
103 std::stringstream ss2;
104 ss2 <<
"MapObject" << map_count++;
107 static int node_count = 0;
108 std::stringstream ss3;
109 ss3 <<
"NodeObject" << node_count++;
154 scene_node_->setPosition(x * resolution, y * resolution, 0);
155 scene_node_->setScale(width * resolution, height * resolution, 1.0);
175 material_->setSceneBlending(sceneBlending);
176 material_->setDepthWriteEnabled(depthWrite);
186 unsigned char* pixels =
new unsigned char[pixels_size];
187 memset(pixels, 255, pixels_size);
188 unsigned char* ptr = pixels;
192 for (
unsigned int yy =
y_; yy <
y_ +
height_; yy++)
194 int index = yy * fw +
x_;
195 int pixels_to_copy = std::min((
int)
width_, N - index);
197 ptr += pixels_to_copy;
198 if (index + pixels_to_copy >= N)
202 Ogre::DataStreamPtr pixel_stream;
203 pixel_stream.bind(
new Ogre::MemoryDataStream(pixels, pixels_size));
207 Ogre::TextureManager::getSingleton().remove(
texture_->getName());
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);
226 "Topic",
"", QString::fromStdString(ros::message_traits::datatype<nav_msgs::OccupancyGrid>()),
227 "nav_msgs::OccupancyGrid topic to subscribe to.",
this, SLOT(
updateTopic()));
242 "Draw Behind",
false,
243 "Rendering option, controls whether or not the map is always drawn behind everything else.",
this,
247 new FloatProperty(
"Resolution", 0,
"Resolution of the map. (not editable)",
this);
258 "Position of the bottom left corner of the map, in meters. (not editable)",
263 "Orientation of the map. (not editable)",
this);
270 "Use Timestamp",
false,
"Use map header timestamp when transforming",
this, SLOT(
transformMap()));
277 for (
unsigned i = 0; i <
swatches.size(); i++)
286 unsigned char* palette = OGRE_ALLOC_T(
unsigned char, 256 * 4, Ogre::MEMCATEGORY_GENERAL);
287 unsigned char* palette_ptr = palette;
289 for (
int i = 0; i <= 100; i++)
291 unsigned char v = 255 - (255 * i) / 100;
295 *palette_ptr++ = 255;
298 for (
int i = 101; i <= 127; i++)
301 *palette_ptr++ = 255;
303 *palette_ptr++ = 255;
306 for (
int i = 128; i <= 254; i++)
308 *palette_ptr++ = 255;
309 *palette_ptr++ = (255 * (i - 128)) / (254 - 128);
311 *palette_ptr++ = 255;
314 *palette_ptr++ = 0x70;
315 *palette_ptr++ = 0x89;
316 *palette_ptr++ = 0x86;
317 *palette_ptr++ = 255;
324 unsigned char* palette = OGRE_ALLOC_T(
unsigned char, 256 * 4, Ogre::MEMCATEGORY_GENERAL);
325 unsigned char* palette_ptr = palette;
334 for (
int i = 1; i <= 98; i++)
336 unsigned char v = (255 * i) / 100;
339 *palette_ptr++ = 255 - v;
340 *palette_ptr++ = 255;
344 *palette_ptr++ = 255;
345 *palette_ptr++ = 255;
346 *palette_ptr++ = 255;
348 *palette_ptr++ = 255;
350 *palette_ptr++ = 255;
351 *palette_ptr++ = 255;
353 for (
int i = 101; i <= 127; i++)
356 *palette_ptr++ = 255;
358 *palette_ptr++ = 255;
361 for (
int i = 128; i <= 254; i++)
363 *palette_ptr++ = 255;
364 *palette_ptr++ = (255 * (i - 128)) / (254 - 128);
366 *palette_ptr++ = 255;
369 *palette_ptr++ = 0x70;
370 *palette_ptr++ = 0x89;
371 *palette_ptr++ = 0x86;
372 *palette_ptr++ = 255;
379 unsigned char* palette = OGRE_ALLOC_T(
unsigned char, 256 * 4, Ogre::MEMCATEGORY_GENERAL);
380 unsigned char* palette_ptr = palette;
382 for (
int i = 0; i < 256; i++)
387 *palette_ptr++ = 255;
395 Ogre::DataStreamPtr palette_stream;
396 palette_stream.bind(
new Ogre::MemoryDataStream(palette_bytes, 256 * 4,
true));
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);
478 Ogre::SceneBlendType sceneBlending;
483 sceneBlending = Ogre::SBT_TRANSPARENT_ALPHA;
488 sceneBlending = Ogre::SBT_REPLACE;
494 for (
unsigned i = 0; i <
swatches.size(); i++)
496 swatches[i]->updateAlpha(sceneBlending, depthWrite, &alpha_setter);
506 for (
unsigned i = 0; i <
swatches.size(); i++)
507 swatches[i]->material_->setDepthWriteEnabled(!draw_under);
510 int group = draw_under ? Ogre::RENDER_QUEUE_4 : Ogre::RENDER_QUEUE_MAIN;
511 for (
unsigned i = 0; i <
swatches.size(); i++)
514 swatches[i]->manual_object_->setRenderQueueGroup(group);
534 for (
unsigned i = 0; i <
swatches.size(); i++)
537 swatches[i]->manual_object_->setVisible(
false);
539 if (!
swatches[i]->texture_.isNull())
541 Ogre::TextureManager::getSingleton().remove(
swatches[i]->texture_->getName());
575 if (update->x < 0 || update->y < 0 ||
current_map_.info.width < update->x + update->width ||
583 for (
size_t y = 0; y < update->height; y++)
586 &update->data[y * update->width], update->width);
602 for (
int i = 0; i < 4; i++)
604 ROS_INFO(
"Creating %d swatches", n_swatches);
605 for (
unsigned i = 0; i <
swatches.size(); i++)
614 for (
int i = 0; i < n_swatches; i++)
617 if (width - x - sw >= sw)
622 if (height - y - sh >= sh)
640 catch (Ogre::RenderingAPIException&)
642 ROS_WARN(
"Failed to create %d swatches", n_swatches);
662 "Message contained invalid floating point values (nans or infs)");
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.",
673 ROS_DEBUG_NAMED(
"quaternions",
"Map received on topic '%s' contains unnormalized quaternions.",
679 std::stringstream ss;
705 Ogre::Quaternion orientation;
714 bool map_status_set =
false;
715 if (width * height != static_cast<int>(
current_map_.data.size()))
717 std::stringstream ss;
718 ss <<
"Data size doesn't match width*height: width = " << width <<
", height = " << height
721 map_status_set =
true;
724 for (
size_t i = 0; i <
swatches.size(); i++)
728 Ogre::Pass* pass =
swatches[i]->material_->getTechnique(0)->getPass(0);
729 Ogre::TextureUnitState* tex_unit =
nullptr;
730 if (pass->getNumTextureUnitStates() > 0)
732 tex_unit = pass->getTextureUnitState(0);
736 tex_unit = pass->createTextureUnitState();
739 tex_unit->setTextureName(
swatches[i]->texture_->getName());
740 tex_unit->setTextureFiltering(Ogre::TFO_NONE);
741 swatches[i]->manual_object_->setVisible(
true);
766 for (
unsigned i = 0; i <
swatches.size(); i++)
768 Ogre::Pass* pass =
swatches[i]->material_->getTechnique(0)->getPass(0);
769 Ogre::TextureUnitState* palette_tex_unit =
nullptr;
770 if (pass->getNumTextureUnitStates() > 1)
772 palette_tex_unit = pass->getTextureUnitState(1);
776 palette_tex_unit = pass->createTextureUnitState();
779 palette_tex_unit->setTextureFiltering(Ogre::TFO_NONE);
799 Ogre::Vector3 position;
800 Ogre::Quaternion orientation;
806 ROS_DEBUG(
"Error transforming map '%s' from frame '%s' to frame '%s'", qPrintable(
getName()),
810 "No transform from [" + QString::fromStdString(
frame_) +
"] to [" +
fixed_frame_ +
"]");
unsigned char * makeCostmapPalette()
Ogre::TexturePtr makePaletteTexture(unsigned char *palette_bytes)
virtual void setString(const QString &str)
unsigned char * makeMapPalette()
Ogre::ManualObject * manual_object_
TransportHints & reliable()
virtual bool setVector(const Ogre::Vector3 &vector)
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...
std::vector< Ogre::TexturePtr > palette_textures_
QuaternionProperty * orientation_property_
std::vector< bool > color_scheme_transparency_
ros::NodeHandle update_nh_
A NodeHandle whose CallbackQueue is run from the main GUI thread (the "update" thread).
Ogre::TexturePtr texture_
FloatProperty * alpha_property_
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's data into current_map_ and call showMap().
unsigned char * makeRawPalette()
Ogre::MaterialPtr material_
Property specialized to enforce floating point max/min.
void setReadOnly(bool read_only) override
Overridden from Property to propagate read-only-ness to children.
std::string getTopicStd() const
void onEnable() override
Derived classes override this to do the actual work of enabling themselves.
Property specialized to provide max/min enforcement for integers.
ros::Subscriber update_sub_
Ogre::SceneNode * scene_node_
The Ogre::SceneNode to hold all 3D scene elements shown by this Display.
VectorProperty * position_property_
void setTopic(const QString &topic, const QString &datatype) override
Set the ROS topic to listen to for this display.
FloatProperty * resolution_property_
QString fixed_frame_
A convenience variable equal to context_->getFixedFrame().
#define ROS_DEBUG_NAMED(name,...)
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.
std::vector< Swatch * > swatches
void showMap()
Show current_map_ in the scene.
virtual QString getName() const
Return the name of this Property as a QString.
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_
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.
Displays a map along the XY plane.
RosTopicProperty * topic_property_
IntProperty * height_property_
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().
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_
BoolProperty * unreliable_property_
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.
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_
bool validateQuaternions(const visualization_msgs::InteractiveMarker &marker)
virtual float getFloat() const
void visit(Ogre::Renderable *rend, ushort, bool, Ogre::Any *=nullptr) override
Ogre::SceneNode * scene_node_
virtual QVariant getValue() const
Return the value of this Property as a QVariant. If the value has never been set, an invalid QVariant...
IntProperty * width_property_
void onInitialize() override
Override this function to do subclass-specific initialization.
void reset() override
Called to tell the display to clear its state.
virtual bool getBool() const
virtual void setReadOnly(bool read_only)
Prevent or allow users to edit this property from a PropertyTreeWidget.
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)
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.
nav_msgs::OccupancyGrid current_map_
Swatch(MapDisplay *parent, unsigned int x, unsigned int y, unsigned int width, unsigned int height, float resolution)
void mapUpdated()
Emitted when a new map is received.