30 #include <boost/bind.hpp> 32 #include <OgreManualObject.h> 33 #include <OgreMaterialManager.h> 34 #include <OgreRectangle2D.h> 35 #include <OgreRenderSystem.h> 36 #include <OgreRenderWindow.h> 38 #include <OgreSceneManager.h> 39 #include <OgreSceneNode.h> 40 #include <OgreTextureManager.h> 41 #include <OgreViewport.h> 42 #include <OgreTechnique.h> 43 #include <OgreCamera.h> 59 "Normalize Range",
true,
60 "If set to true, will try to estimate the range of possible values from the received images.",
70 new IntProperty(
"Median window", 5,
"Window size for median filter used for computin min/max.",
80 static uint32_t count = 0;
82 ss <<
"ImageDisplay" << count++;
83 img_scene_manager_ = Ogre::Root::getSingleton().createSceneManager(Ogre::ST_GENERIC, ss.str());
91 ss <<
"ImageDisplayObject" << count++;
94 screen_rect_->setRenderQueueGroup(Ogre::RENDER_QUEUE_OVERLAY - 1);
98 material_ = Ogre::MaterialManager::getSingleton().create(
99 ss.str(), Ogre::ResourceGroupManager::DEFAULT_RESOURCE_GROUP_NAME);
100 material_->setSceneBlending(Ogre::SBT_REPLACE);
105 material_->getTechnique(0)->setLightingEnabled(
false);
106 Ogre::TextureUnitState* tu =
material_->getTechnique(0)->getPass(0)->createTextureUnitState();
108 tu->setTextureFiltering(Ogre::TFO_NONE);
109 tu->setTextureAddressingMode(Ogre::TextureUnitState::TAM_CLAMP);
111 material_->setCullingMode(Ogre::CULL_NONE);
112 Ogre::AxisAlignedBox aabInf;
113 aabInf.setInfinite();
205 if (img_width != 0 && img_height != 0 && win_width != 0 && win_height != 0)
207 float img_aspect = img_width / img_height;
208 float win_aspect = win_width / win_height;
210 if (img_aspect > win_aspect)
213 -1.0
f * win_aspect / img_aspect,
false);
217 screen_rect_->setCorners(-1.0
f * img_aspect / win_aspect, 1.0
f, 1.0
f * img_aspect / win_aspect,
const Ogre::TexturePtr & getTexture()
void processMessage(const sensor_msgs::Image::ConstPtr &msg) override
Implement this to process the contents of a message.
RenderPanel * render_panel_
void initialize(Ogre::SceneManager *scene_manager, DisplayContext *manager)
void reset() override
Called to tell the display to clear its state.
DisplayContext * context_
This DisplayContext pointer is the main connection a Display has into the rest of rviz...
BoolProperty * normalize_property_
FloatProperty * max_property_
void setAutoRender(bool auto_render)
Ogre::Camera * getCamera() const
virtual void unsubscribe()
Ogre::Rectangle2D * screen_rect_
Ogre::SceneManager * img_scene_manager_
Property specialized to enforce floating point max/min.
void reset() override
Reset display.
Property specialized to provide max/min enforcement for integers.
void setNormalizeFloatImage(bool normalize, double min=0.0, double max=1.0)
void setMedianFrames(unsigned median_frames)
virtual void subscribe()
ROS topic management.
Display subclass for subscribing and displaying to image messages.
void addMessage(const sensor_msgs::Image::ConstPtr &image)
const std::string TYPE_32FC1
void setAssociatedWidget(QWidget *widget)
Associate the given widget with this Display.
IntProperty * median_buffer_size_property_
void onEnable() override
Derived classes override this to do the actual work of enabling themselves.
const std::string TYPE_16UC1
void onDisable() override
Derived classes override this to do the actual work of disabling themselves.
FloatProperty * min_property_
void onInitialize() override
Override this function to do subclass-specific initialization.
virtual int getInt() const
Return the internal property value as an integer.
BoolProperty(const QString &name=QString(), bool default_value=false, const QString &description=QString(), Property *parent=nullptr, const char *changed_slot=nullptr, QObject *receiver=nullptr)
virtual void setHidden(bool hidden)
Hide or show this property in any PropertyTreeWidget viewing its parent.
void onInitialize() override
Override this function to do subclass-specific initialization.
Ogre::SceneNode * img_scene_node_
virtual float getFloat() const
void update(float wall_dt, float ros_dt) override
Called periodically by the visualization manager.
Ogre::MaterialPtr material_
bool initialized() const
Returns true if the display has been initialized.
virtual bool getBool() const
#define PLUGINLIB_EXPORT_CLASS(class_type, base_class_type)
virtual void setStatus(StatusProperty::Level level, const QString &name, const QString &text)
Show status level and text. This is thread-safe.
void setOverlaysEnabled(bool overlays_enabled)
virtual void updateNormalizeOptions()
const std::string TYPE_16SC1