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> 37 #include <OgreSceneManager.h> 38 #include <OgreSceneNode.h> 39 #include <OgreTextureManager.h> 40 #include <OgreViewport.h> 41 #include <OgreTechnique.h> 42 #include <OgreCamera.h> 81 :
ImageDisplayBase(), texture_(), render_panel_(nullptr), caminfo_ok_(false), force_render_(false)
85 "Render the image behind all other geometry or overlay it on top, or both.",
this,
93 "The amount of transparency to apply to the camera image when rendered as overlay.",
this,
100 "Set a zoom factor below 1 to see a larger part of the world, above 1 to magnify the image.",
this,
133 static int count = 0;
135 ss <<
"CameraDisplayObject" << count++;
142 bg_material_ = Ogre::MaterialManager::getSingleton().create(
143 ss.str(), Ogre::ResourceGroupManager::DEFAULT_RESOURCE_GROUP_NAME);
149 bg_material_->getTechnique(0)->setLightingEnabled(
false);
150 Ogre::TextureUnitState* tu =
bg_material_->getTechnique(0)->getPass(0)->createTextureUnitState();
152 tu->setTextureFiltering(Ogre::TFO_NONE);
153 tu->setTextureAddressingMode(Ogre::TextureUnitState::TAM_CLAMP);
154 tu->setAlphaOperation(Ogre::LBX_SOURCE1, Ogre::LBS_MANUAL, Ogre::LBS_CURRENT, 0.0);
159 Ogre::AxisAlignedBox aabInf;
160 aabInf.setInfinite();
177 fg_material_->setSceneBlending(Ogre::SBT_TRANSPARENT_ALPHA);
207 "Changes the visibility of other Displays in the camera view.");
256 const std::string caminfo_topic =
279 Ogre::Pass* pass =
fg_material_->getTechnique(0)->getPass(0);
280 if (pass->getNumTextureUnitStates() > 0)
282 Ogre::TextureUnitState* tex_unit = pass->getTextureUnitState(0);
283 tex_unit->setAlphaOperation(Ogre::LBX_MODULATE, Ogre::LBS_MANUAL, Ogre::LBS_CURRENT, alpha);
335 sensor_msgs::CameraInfo::ConstPtr info;
336 sensor_msgs::Image::ConstPtr image;
349 if (image->header.frame_id != info->header.frame_id)
351 QString(
"Image frame (%1) doesn't match camera frame (%2)")
352 .arg(QString::fromStdString(image->header.frame_id),
353 QString::fromStdString(info->header.frame_id)));
360 "Contains invalid floating point values (nans or infs)");
367 rviz_time != image->header.stamp)
369 std::ostringstream
s;
370 s <<
"Time-syncing active and no image at timestamp " << rviz_time.
toSec() <<
".";
375 Ogre::Vector3 position;
376 Ogre::Quaternion orientation;
384 orientation = orientation * Ogre::Quaternion(Ogre::Degree(180), Ogre::Vector3::UNIT_X);
386 float img_width = info->width;
387 float img_height = info->height;
392 ROS_DEBUG(
"Malformed CameraInfo on camera [%s], width = 0", qPrintable(
getName()));
398 ROS_DEBUG(
"Malformed CameraInfo on camera [%s], height = 0", qPrintable(
getName()));
402 if (img_height == 0.0 || img_width == 0.0)
405 "Could not determine width/height of image due to malformed CameraInfo " 406 "(either width or height is 0)");
410 double fx = info->P[0];
411 double fy = info->P[5];
416 float zoom_y = zoom_x;
419 if (win_width != 0 && win_height != 0)
421 float img_aspect = (img_width / fx) / (img_height / fy);
422 float win_aspect = win_width / win_height;
424 if (img_aspect > win_aspect)
426 zoom_y = zoom_y / img_aspect * win_aspect;
430 zoom_x = zoom_x / win_aspect * img_aspect;
435 double tx = -1 * (info->P[3] / fx);
436 Ogre::Vector3 right = orientation * Ogre::Vector3::UNIT_X;
437 position = position + (right * tx);
439 double ty = -1 * (info->P[7] / fy);
440 Ogre::Vector3 down = orientation * Ogre::Vector3::UNIT_Y;
441 position = position + (down * ty);
446 "CameraInfo/P resulted in an invalid position calculation (nans or infs)");
454 double cx = info->P[2];
455 double cy = info->P[6];
457 double far_plane = 100;
458 double near_plane = 0.01;
460 Ogre::Matrix4 proj_matrix;
461 proj_matrix = Ogre::Matrix4::ZERO;
463 proj_matrix[0][0] = 2.0 * fx / img_width * zoom_x;
464 proj_matrix[1][1] = 2.0 * fy / img_height * zoom_y;
466 proj_matrix[0][2] = 2.0 * (0.5 - cx / img_width) * zoom_x;
467 proj_matrix[1][2] = 2.0 * (cy / img_height - 0.5) * zoom_y;
469 proj_matrix[2][2] = -(far_plane + near_plane) / (far_plane - near_plane);
470 proj_matrix[2][3] = -2.0 * far_plane * near_plane / (far_plane - near_plane);
472 proj_matrix[3][2] = -1;
483 double x_corner_start, y_corner_start, x_corner_end, y_corner_end;
485 if (info->roi.height != 0 || info->roi.width != 0)
488 x_corner_start = (2.0 * info->roi.x_offset / info->width - 1.0) * zoom_x;
489 y_corner_start = (-2.0 * info->roi.y_offset / info->height + 1.0) * zoom_y;
490 x_corner_end = x_corner_start + (2.0 * info->roi.width / info->width) * zoom_x;
491 y_corner_end = y_corner_start - (2.0 * info->roi.height / info->height) * zoom_y;
495 x_corner_start = -1.0f * zoom_x;
496 y_corner_start = 1.0f * zoom_y;
497 x_corner_end = 1.0f * zoom_x;
498 y_corner_end = -1.0f * zoom_y;
501 bg_screen_rect_->setCorners(x_corner_start, y_corner_start, x_corner_end, y_corner_end);
502 fg_screen_rect_->setCorners(x_corner_start, y_corner_start, x_corner_end, y_corner_end);
504 Ogre::AxisAlignedBox aabInf;
505 aabInf.setInfinite();
547 "No CameraInfo received on [" + QString::fromStdString(caminfo_topic) +
548 "].\nTopic may not exist.");
FloatProperty * alpha_property_
const Ogre::TexturePtr & getTexture()
void onEnable() override
Derived classes override this to do the actual work of enabling themselves.
void setOrientation(const Ogre::Quaternion &orientation) override
Set the orientation of the object.
sensor_msgs::CameraInfo::ConstPtr current_caminfo_
void update(float wall_dt, float ros_dt) override
Called periodically by the visualization manager.
Ogre::SceneNode * bg_scene_node_
void initialize(Ogre::SceneManager *scene_manager, DisplayContext *manager)
static const QString OVERLAY
static const QString BOTH
DisplayContext * context_
This DisplayContext pointer is the main connection a Display has into the rest of rviz...
void setAutoRender(bool auto_render)
Ogre::Camera * getCamera() const
ros::NodeHandle update_nh_
A NodeHandle whose CallbackQueue is run from the main GUI thread (the "update" thread).
RenderPanel * render_panel_
void onDisable() override
Derived classes override this to do the actual work of disabling themselves.
Ogre::SceneNode * fg_scene_node_
virtual void unsubscribe()
void subscribe() override
ROS topic management.
Property specialized to enforce floating point max/min.
ros::Time getTime()
Get current time, depending on the sync mode.
std::string getTopicStd() const
boost::mutex caminfo_mutex_
void reset() override
Reset display.
Ogre::SceneNode * scene_node_
The Ogre::SceneNode to hold all 3D scene elements shown by this Display.
void postRenderTargetUpdate(const Ogre::RenderTargetEvent &evt) override
virtual DisplayGroup * getRootDisplayGroup() const =0
QString fixed_frame_
A convenience variable equal to context_->getFixedFrame().
virtual void setIcon(const QIcon &icon)
Set the icon to be displayed next to the property.
EnumProperty * image_position_property_
bool validateFloats(const sensor_msgs::CameraInfo &msg)
virtual void addOption(const QString &option, int value=0)
virtual void subscribe()
ROS topic management.
void unsubscribe() override
Display subclass for subscribing and displaying to image messages.
void enableTFFilter(std::string &targetFrame)
Enabling TF filtering by defining a target frame.
void onInitialize() override
Override this function to do subclass-specific initialization.
void preRenderTargetUpdate(const Ogre::RenderTargetEvent &evt) override
void reset() override
Called to tell the display to clear its state.
void addMessage(const sensor_msgs::Image::ConstPtr &image)
virtual BitAllocator * visibilityBits()=0
void setAssociatedWidget(QWidget *widget)
Associate the given widget with this Display.
Ogre::Rectangle2D * fg_screen_rect_
virtual QString getName() const
Return the name of this Property as a QString.
virtual void updateQueueSize()
Update queue size of tf filter.
Ogre::Viewport * getViewport() const
virtual FrameManager * getFrameManager() const =0
Return the FrameManager instance.
DisplayGroupVisibilityProperty * visibility_property_
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.
IMAGE_TRANSPORT_DECL std::string getCameraInfoTopic(const std::string &base_topic)
An object that displays a set of X/Y/Z axes, with X=Red, Y=Green, Z=Blue.
Ogre::SceneManager * scene_manager_
A convenience variable equal to context_->getSceneManager().
void setPosition(const Ogre::Vector3 &position) override
Set the position of this object.
FloatProperty * zoom_property_
virtual Ogre::SceneManager * getSceneManager() const =0
Returns the Ogre::SceneManager used for the main RenderPanel.
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.
RosTopicProperty * topic_property_
void updateQueueSize() override
void subscribe(ros::NodeHandle &nh, const std::string &topic, uint32_t queue_size, const ros::TransportHints &transport_hints=ros::TransportHints(), ros::CallbackQueueInterface *callback_queue=0)
virtual float getFloat() const
virtual void addChild(Property *child, int index=-1)
Add a child property.
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.
Ogre::MaterialPtr fg_material_
void fixedFrameChanged() override
Called by setFixedFrame(). Override to respond to changes to fixed_frame_.
static const QString BACKGROUND
virtual void deleteStatus(const QString &name)
Delete the status entry with the given name. This is thread-safe.
Ogre::Rectangle2D * bg_screen_rect_
bool initialized() const
Returns true if the display has been initialized.
const sensor_msgs::Image::ConstPtr & getImage()
message_filters::Subscriber< sensor_msgs::CameraInfo > caminfo_sub_
Ogre::MaterialPtr bg_material_
void freeBits(uint32_t bits)
Free the given bits.
#define PLUGINLIB_EXPORT_CLASS(class_type, base_class_type)
QPixmap loadPixmap(QString url, bool fill_cache)
virtual void setStatus(StatusProperty::Level level, const QString &name, const QString &text)
Show status level and text. This is thread-safe.
void caminfoCallback(const sensor_msgs::CameraInfo::ConstPtr &msg)
void processMessage(const sensor_msgs::Image::ConstPtr &msg) override
Implement this to process the contents of a message.
void setOverlaysEnabled(bool overlays_enabled)
~CameraDisplay() override
Connection registerCallback(const C &callback)
uint32_t allocBit()
Return a uint32 with a single bit "on" (previously unused), or a 0 if all bits are already allocated...