Go to the documentation of this file.
30 #include <boost/bind/bind.hpp>
32 #include <OgreManualObject.h>
33 #include <OgreMaterialManager.h>
34 #include <OgreRectangle2D.h>
35 #include <OgreRenderSystem.h>
36 #include <OgreRenderWindow.h>
37 #include <OgreSceneManager.h>
38 #include <OgreSceneNode.h>
39 #include <OgreTextureManager.h>
40 #include <OgreViewport.h>
41 #include <OgreTechnique.h>
42 #include <OgreCamera.h>
83 :
ImageDisplayBase(), texture_(), render_panel_(nullptr), caminfo_ok_(false), force_render_(false)
87 "Render the image behind all other geometry or overlay it on top, or both.",
this,
95 "The amount of transparency to apply to the camera image when rendered as overlay.",
this,
102 "Set a zoom factor below 1 to see a larger part of the world, above 1 to magnify the image.",
this,
135 static int count = 0;
137 ss <<
"CameraDisplayObject" << count++;
144 bg_material_ = Ogre::MaterialManager::getSingleton().create(
145 ss.str(), Ogre::ResourceGroupManager::DEFAULT_RESOURCE_GROUP_NAME);
151 bg_material_->getTechnique(0)->setLightingEnabled(
false);
152 Ogre::TextureUnitState* tu =
bg_material_->getTechnique(0)->getPass(0)->createTextureUnitState();
154 tu->setTextureFiltering(Ogre::TFO_NONE);
155 tu->setTextureAddressingMode(Ogre::TextureUnitState::TAM_CLAMP);
156 tu->setAlphaOperation(Ogre::LBX_SOURCE1, Ogre::LBS_MANUAL, Ogre::LBS_CURRENT, 0.0);
161 Ogre::AxisAlignedBox aabInf;
162 aabInf.setInfinite();
179 fg_material_->setSceneBlending(Ogre::SBT_TRANSPARENT_ALPHA);
197 dock->addMaximizeButton();
209 "Changes the visibility of other Displays in the camera view.");
258 const std::string caminfo_topic =
281 Ogre::Pass* pass =
fg_material_->getTechnique(0)->getPass(0);
282 if (pass->getNumTextureUnitStates() > 0)
284 Ogre::TextureUnitState* tex_unit = pass->getTextureUnitState(0);
285 tex_unit->setAlphaOperation(Ogre::LBX_MODULATE, Ogre::LBS_MANUAL, Ogre::LBS_CURRENT, alpha);
328 sensor_msgs::CameraInfo::ConstPtr info;
329 sensor_msgs::Image::ConstPtr image;
342 if (image->header.frame_id != info->header.frame_id)
344 QString(
"Image frame (%1) doesn't match camera frame (%2)")
345 .arg(QString::fromStdString(image->header.frame_id),
346 QString::fromStdString(info->header.frame_id)));
353 "Contains invalid floating point values (nans or infs)");
360 rviz_time != image->header.stamp)
362 std::ostringstream
s;
363 s <<
"Time-syncing active and no image at timestamp " << rviz_time.
toSec() <<
".";
368 Ogre::Vector3 position;
369 Ogre::Quaternion orientation;
377 orientation = orientation * Ogre::Quaternion(Ogre::Degree(180), Ogre::Vector3::UNIT_X);
379 float img_width = info->width;
380 float img_height = info->height;
385 ROS_DEBUG(
"Malformed CameraInfo on camera [%s], width = 0", qPrintable(
getName()));
391 ROS_DEBUG(
"Malformed CameraInfo on camera [%s], height = 0", qPrintable(
getName()));
395 if (img_height == 0.0 || img_width == 0.0)
398 "Could not determine width/height of image due to malformed CameraInfo "
399 "(either width or height is 0)");
403 double fx = info->P[0];
404 double fy = info->P[5];
409 float zoom_y = zoom_x;
412 if (win_width != 0 && win_height != 0)
414 float img_aspect = (img_width / fx) / (img_height / fy);
415 float win_aspect = win_width / win_height;
417 if (img_aspect > win_aspect)
419 zoom_y = zoom_y / img_aspect * win_aspect;
423 zoom_x = zoom_x / win_aspect * img_aspect;
428 double tx = -1 * (info->P[3] / fx);
429 Ogre::Vector3 right = orientation * Ogre::Vector3::UNIT_X;
430 position = position + (right * tx);
432 double ty = -1 * (info->P[7] / fy);
433 Ogre::Vector3 down = orientation * Ogre::Vector3::UNIT_Y;
434 position = position + (down * ty);
439 "CameraInfo/P resulted in an invalid position calculation (nans or infs)");
447 double cx = info->P[2];
448 double cy = info->P[6];
450 double far_plane = 100;
451 double near_plane = 0.01;
453 Ogre::Matrix4 proj_matrix;
454 proj_matrix = Ogre::Matrix4::ZERO;
456 proj_matrix[0][0] = 2.0 * fx / img_width * zoom_x;
457 proj_matrix[1][1] = 2.0 * fy / img_height * zoom_y;
459 proj_matrix[0][2] = 2.0 * (0.5 - cx / img_width) * zoom_x;
460 proj_matrix[1][2] = 2.0 * (cy / img_height - 0.5) * zoom_y;
462 proj_matrix[2][2] = -(far_plane + near_plane) / (far_plane - near_plane);
463 proj_matrix[2][3] = -2.0 * far_plane * near_plane / (far_plane - near_plane);
465 proj_matrix[3][2] = -1;
476 double x_corner_start, y_corner_start, x_corner_end, y_corner_end;
478 if (info->roi.height != 0 || info->roi.width != 0)
481 x_corner_start = (2.0 * info->roi.x_offset / info->width - 1.0) * zoom_x;
482 y_corner_start = (-2.0 * info->roi.y_offset / info->height + 1.0) * zoom_y;
483 x_corner_end = x_corner_start + (2.0 * info->roi.width / info->width) * zoom_x;
484 y_corner_end = y_corner_start - (2.0 * info->roi.height / info->height) * zoom_y;
488 x_corner_start = -1.0f * zoom_x;
489 y_corner_start = 1.0f * zoom_y;
490 x_corner_end = 1.0f * zoom_x;
491 y_corner_end = -1.0f * zoom_y;
494 bg_screen_rect_->setCorners(x_corner_start, y_corner_start, x_corner_end, y_corner_end);
495 fg_screen_rect_->setCorners(x_corner_start, y_corner_start, x_corner_end, y_corner_end);
497 Ogre::AxisAlignedBox aabInf;
498 aabInf.setInfinite();
539 "No CameraInfo received on [" + QString::fromStdString(caminfo_topic) +
540 "].\nTopic may not exist.");
void processMessage(const sensor_msgs::Image::ConstPtr &msg) override
Implement this to process the contents of a message.
bool isEnabled() const
Return true if this Display is enabled, false if not.
uint32_t allocBit()
Return a uint32 with a single bit "on" (previously unused), or a 0 if all bits are already allocated.
IMAGE_TRANSPORT_DECL std::string getCameraInfoTopic(const std::string &base_topic)
void fixedFrameChanged() override
Called by setFixedFrame(). Override to respond to changes to fixed_frame_.
void onInitialize() override
Override this function to do subclass-specific initialization.
void enableTFFilter(std::string &targetFrame)
Enabling TF filtering by defining a target frame.
virtual void queueRender()=0
Queues a render. Multiple calls before a render happens will only cause a single render.
virtual void deleteStatus(const QString &name)
Delete the status entry with the given name. This is thread-safe.
bool initialized() const
Returns true if the display has been initialized.
void postRenderTargetUpdate(const Ogre::RenderTargetEvent &evt) override
void fixedFrameChanged() override
Called by setFixedFrame(). Override to respond to changes to fixed_frame_.
virtual void unsubscribe()
Ogre::Camera * getCamera() const
Ogre::MaterialPtr fg_material_
void preRenderTargetUpdate(const Ogre::RenderTargetEvent &evt) override
static const QString BACKGROUND
bool validateFloats(const sensor_msgs::CameraInfo &msg)
virtual void addChild(Property *child, int index=-1)
Add a child property.
void onInitialize() override
Override this function to do subclass-specific initialization.
QString fixed_frame_
A convenience variable equal to context_->getFixedFrame().
void processCamInfoMessage(const sensor_msgs::CameraInfo::ConstPtr &msg)
void setMaterial(Ogre::SimpleRenderable &renderable, const std::string &material_name)
QPixmap loadPixmap(const QString &url, bool fill_cache)
Ogre::SceneNode * fg_scene_node_
virtual Ogre::SceneManager * getSceneManager() const =0
Returns the Ogre::SceneManager used for the main RenderPanel.
RenderPanel * render_panel_
Property specialized to enforce floating point max/min.
ros::Time getTime()
Get current time, depending on the sync mode.
void subscribe() override
ROS topic management.
virtual void setStatus(StatusProperty::Level level, const QString &name, const QString &text)
Show status level and text. This is thread-safe.
static const QString OVERLAY
boost::mutex caminfo_mutex_
void removeAndDestroyChildNode(Ogre::SceneNode *parent, Ogre::SceneNode *child)
void initialize(Ogre::SceneManager *scene_manager, DisplayContext *manager)
void unsubscribe() override
#define PLUGINLIB_EXPORT_CLASS(class_type, base_class_type)
virtual float getFloat() const
virtual void addOption(const QString &option, int value=0)
~CameraDisplay() override
Ogre::SceneNode * scene_node_
The Ogre::SceneNode to hold all 3D scene elements shown by this Display.
void onDisable() override
Derived classes override this to do the actual work of disabling themselves.
Ogre::SceneManager * scene_manager_
A convenience variable equal to context_->getSceneManager().
DisplayGroupVisibilityProperty * visibility_property_
void addMessage(const sensor_msgs::Image::ConstPtr &image)
Subscriber subscribe(const std::string &topic, uint32_t queue_size, const boost::function< void(C)> &callback, const VoidConstPtr &tracked_object=VoidConstPtr(), const TransportHints &transport_hints=TransportHints())
virtual DisplayGroup * getRootDisplayGroup() const =0
virtual FrameManager * getFrameManager() const =0
Return the FrameManager instance.
An object that displays a set of X/Y/Z axes, with X=Red, Y=Green, Z=Blue.
std::string getTopicStd() const
void reset() override
Called to tell the display to clear its state.
virtual BitAllocator * visibilityBits()=0
Display subclass for subscribing and displaying to image messages.
FloatProperty * alpha_property_
PanelDockWidget * getAssociatedWidgetPanel()
Return the panel containing the associated widget, or NULL if there is none.
bool getTransform(const Header &header, Ogre::Vector3 &position, Ogre::Quaternion &orientation)
Return the pose for a header, relative to the fixed frame, in Ogre classes.
virtual QString getName() const
Return the name of this Property as a QString.
DisplayContext * context_
This DisplayContext pointer is the main connection a Display has into the rest of rviz....
const sensor_msgs::Image::ConstPtr & getImage()
ros::Subscriber caminfo_sub_
void update(float wall_dt, float ros_dt) override
Called periodically by the visualization manager.
Ogre::Rectangle2D * bg_screen_rect_
void reset() override
Reset display.
virtual void updateQueueSize()
Update queue size of tf filter
virtual void setIcon(const QIcon &icon)
Set the icon to be displayed next to the property.
Ogre::MaterialPtr bg_material_
void setPosition(const Ogre::Vector3 &position) override
Set the position of this object.
Ogre::Rectangle2D * fg_screen_rect_
void setAutoRender(bool auto_render)
void setAssociatedWidget(QWidget *widget)
Associate the given widget with this Display.
void setOverlaysEnabled(bool overlays_enabled)
static const QString BOTH
const Ogre::TexturePtr & getTexture()
void setOrientation(const Ogre::Quaternion &orientation) override
Set the orientation of the object.
sensor_msgs::CameraInfo::ConstPtr current_caminfo_
RosTopicProperty * topic_property_
Ogre::Viewport * getViewport() const
void updateQueueSize() override
EnumProperty * image_position_property_
void freeBits(uint32_t bits)
Free the given bits.
ros::NodeHandle update_nh_
A NodeHandle whose CallbackQueue is run from the main GUI thread (the "update" thread).
void onEnable() override
Derived classes override this to do the actual work of enabling themselves.
Ogre::SceneNode * bg_scene_node_
virtual void subscribe()
ROS topic management.
FloatProperty * zoom_property_
rviz
Author(s): Dave Hershberger, David Gossow, Josh Faust, William Woodall
autogenerated on Fri Aug 2 2024 08:43:09