36 #include <boost/bind.hpp> 38 #include <OgreManualObject.h> 39 #include <OgreMaterialManager.h> 40 #include <OgreRectangle2D.h> 41 #include <OgreRenderSystem.h> 42 #include <OgreRenderWindow.h> 43 #include <OgreSceneManager.h> 44 #include <OgreSceneNode.h> 45 #include <OgreTextureManager.h> 46 #include <OgreViewport.h> 47 #include <OgreTechnique.h> 48 #include <OgreCamera.h> 49 #include <OgrePixelFormat.h> 50 #include <OGRE/OgreHardwarePixelBuffer.h> 51 #include <OGRE/OgreTechnique.h> 92 , caminfo_tf_filter_( 0 )
93 , new_caminfo_( false )
94 , force_render_( false )
98 "Render the image behind all other geometry or overlay it on top, or both.",
105 "The amount of transparency to apply to the camera image when rendered as overlay.",
112 "Set a zoom factor below 1 to see a larger part of the world, above 1 to magnify the image.",
118 "width of overlay image",
121 "height of overlay image",
124 "left positoin of overlay image",
127 "top positoin of overlay image",
166 #if ROS_VERSION_MINIMUM(1, 15, 0) // noetic and greater 180 static int count = 0;
182 ss <<
"OverlayCameraDisplayObject" << count++;
189 bg_material_ = Ogre::MaterialManager::getSingleton().create( ss.str(), Ogre::ResourceGroupManager::DEFAULT_RESOURCE_GROUP_NAME );
195 bg_material_->getTechnique(0)->setLightingEnabled(
false);
196 Ogre::TextureUnitState* tu =
bg_material_->getTechnique(0)->getPass(0)->createTextureUnitState();
198 tu->setTextureFiltering( Ogre::TFO_NONE );
199 tu->setAlphaOperation( Ogre::LBX_SOURCE1, Ogre::LBS_MANUAL, Ogre::LBS_CURRENT, 0.0 );
204 Ogre::AxisAlignedBox aabInf;
205 aabInf.setInfinite();
212 bg_scene_node_->setVisible(
false);
222 fg_material_->setSceneBlending( Ogre::SBT_TRANSPARENT_ALPHA );
259 "Changes the visibility of other Displays in the camera view.");
338 Ogre::Pass* pass =
fg_material_->getTechnique( 0 )->getPass( 0 );
339 if( pass->getNumTextureUnitStates() > 0 )
341 Ogre::TextureUnitState* tex_unit = pass->getTextureUnitState( 0 );
342 tex_unit->setAlphaOperation( Ogre::LBX_MODULATE, Ogre::LBS_MANUAL, Ogre::LBS_CURRENT, alpha );
346 fg_material_->setAmbient( Ogre::ColourValue( 0.0
f, 1.0
f, 1.0
f, alpha ));
347 fg_material_->setDiffuse( Ogre::ColourValue( 0.0
f, 1.0
f, 1.0
f, alpha ));
376 "No CameraInfo received on [" + QString::fromStdString(
caminfo_sub_.
getTopic() ) +
"]. Topic may not exist.");
399 static int count = 0;
401 ss <<
"OverlayImageDisplayObject" << count++;
415 int width = rt->getWidth();
416 int height = rt->getHeight();
417 Ogre::uchar *
data =
new Ogre::uchar[width * height * 3];
418 Ogre::PixelBox pb(width, height, 1, Ogre::PF_BYTE_RGB, data);
419 rt->copyContentsToMemory(pb);
423 for (
int i = 0; i <
overlay_->getTextureWidth(); i++) {
424 for (
int j = 0; j <
overlay_->getTextureHeight(); j++) {
425 Ogre::ColourValue c = pb.getColourAt(i, j, 0);
426 QColor color(c.r * 255, c.g * 255, c.b * 255,
texture_alpha_ * 255);
427 Hud.setPixel(i, j, color.rgba());
436 sensor_msgs::CameraInfo::ConstPtr info;
437 sensor_msgs::Image::ConstPtr image;
445 if( !info || !image )
459 rviz_time != image->header.stamp )
461 std::ostringstream
s;
462 s <<
"Time-syncing active and no image at timestamp " << rviz_time.
toSec() <<
".";
467 Ogre::Vector3 position;
468 Ogre::Quaternion orientation;
474 orientation = orientation * Ogre::Quaternion( Ogre::Degree( 180 ), Ogre::Vector3::UNIT_X );
476 float img_width = info->width;
477 float img_height = info->height;
482 ROS_DEBUG(
"Malformed CameraInfo on camera [%s], width = 0", qPrintable(
getName() ));
488 ROS_DEBUG(
"Malformed CameraInfo on camera [%s], height = 0", qPrintable(
getName() ));
492 if( img_height == 0.0 || img_width == 0.0 )
495 "Could not determine width/height of image due to malformed CameraInfo (either width or height is 0)" );
499 double fx = info->P[0];
500 double fy = info->P[5];
505 float zoom_y = zoom_x;
508 if( win_width != 0 && win_height != 0 )
510 float img_aspect = (img_width/fx) / (img_height/fy);
511 float win_aspect = win_width / win_height;
513 if ( img_aspect > win_aspect )
515 zoom_y = zoom_y / img_aspect * win_aspect;
519 zoom_x = zoom_x / win_aspect * img_aspect;
524 double tx = -1 * (info->P[3] / fx);
525 Ogre::Vector3 right = orientation * Ogre::Vector3::UNIT_X;
526 position = position + (right * tx);
528 double ty = -1 * (info->P[7] / fy);
529 Ogre::Vector3 down = orientation * Ogre::Vector3::UNIT_Y;
530 position = position + (down * ty);
542 double cx = info->P[2];
543 double cy = info->P[6];
545 double far_plane = 100;
546 double near_plane = 0.01;
548 Ogre::Matrix4 proj_matrix;
549 proj_matrix = Ogre::Matrix4::ZERO;
551 proj_matrix[0][0]= 2.0 * fx/img_width * zoom_x;
552 proj_matrix[1][1]= 2.0 * fy/img_height * zoom_y;
554 proj_matrix[0][2]= 2.0 * (0.5 - cx/img_width) * zoom_x;
555 proj_matrix[1][2]= 2.0 * (cy/img_height - 0.5) * zoom_y;
557 proj_matrix[2][2]= -(far_plane+near_plane) / (far_plane-near_plane);
558 proj_matrix[2][3]= -2.0*far_plane*near_plane / (far_plane-near_plane);
560 proj_matrix[3][2]= -1;
576 Ogre::AxisAlignedBox aabInf;
577 aabInf.setInfinite();
Ogre::Rectangle2D * bg_screen_rect_
std::string getTopic() const
const Ogre::TexturePtr & getTexture()
rviz::IntProperty * width_property_
void initialize(Ogre::SceneManager *scene_manager, DisplayContext *manager)
FloatProperty * alpha_property_
EnumProperty * image_position_property_
virtual void preRenderTargetUpdate(const Ogre::RenderTargetEvent &evt)
virtual tf::TransformListener * getTFClient() const =0
rviz::IntProperty * height_property_
virtual QImage getQImage(unsigned int width, unsigned int height)
PLUGINLIB_EXPORT_CLASS(jsk_rviz_plugins::PictogramArrayDisplay, rviz::Display)
DisplayContext * context_
Ogre::MaterialPtr bg_material_
void setAutoRender(bool auto_render)
virtual int getInt() const
Ogre::Rectangle2D * fg_screen_rect_
ros::NodeHandle update_nh_
virtual float getFloat() const
virtual void unsubscribe()
DisplayGroupVisibilityProperty * visibility_property_
virtual ~OverlayCameraDisplay()
static const QString BOTH
Ogre::SceneNode * scene_node_
virtual void onInitialize()
virtual void fixedFrameChanged()
virtual DisplayGroup * getRootDisplayGroup() const =0
virtual void setPosition(const Ogre::Vector3 &position)
rviz::IntProperty * left_property_
virtual void fixedFrameChanged()
virtual void setQueueSize(uint32_t new_queue_size)
virtual void setIcon(const QIcon &icon)
virtual void postRenderTargetUpdate(const Ogre::RenderTargetEvent &evt)
IntProperty * queue_size_property_
virtual void addOption(const QString &option, int value=0)
rviz::FloatProperty * texture_alpha_property_
sensor_msgs::CameraInfo::ConstPtr current_caminfo_
void enableTFFilter(std::string &targetFrame)
static const QString BACKGROUND
Ogre::SceneNode * bg_scene_node_
virtual void processMessage(const sensor_msgs::Image::ConstPtr &msg)
void addMessage(const sensor_msgs::Image::ConstPtr &image)
message_filters::Subscriber< sensor_msgs::CameraInfo > caminfo_sub_
virtual BitAllocator * visibilityBits()=0
boost::mutex caminfo_mutex_
bool validateFloats(const sensor_msgs::CameraInfo &msg)
FloatProperty * zoom_property_
virtual void updateQueueSize()
void caminfoCallback(const sensor_msgs::CameraInfo::ConstPtr &msg)
virtual FrameManager * getFrameManager() const =0
RenderPanel * render_panel_
Ogre::MaterialPtr fg_material_
Ogre::SceneNode * fg_scene_node_
bool validateFloats(const visualization_msgs::InteractiveMarker &msg)
IMAGE_TRANSPORT_DECL std::string getCameraInfoTopic(const std::string &base_topic)
Ogre::SceneManager * scene_manager_
virtual void onInitialize()
virtual void updateQueueSize()
virtual Ogre::SceneManager * getSceneManager() const =0
virtual void queueRender()=0
Ogre::Viewport * getViewport() const
RosTopicProperty * topic_property_
void updateTextureAlpha()
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)
Ogre::Camera * getCamera() const
virtual void addChild(Property *child, int index=-1)
bool getTransform(const Header &header, Ogre::Vector3 &position, Ogre::Quaternion &orientation)
OverlayObject::Ptr overlay_
virtual void setOrientation(const Ogre::Quaternion &orientation)
void setTargetFrame(const std::string &target_frame)
tf::MessageFilter< sensor_msgs::CameraInfo > * caminfo_tf_filter_
static const QString OVERLAY
const sensor_msgs::Image::ConstPtr & getImage()
std::string getTopicStd() const
void freeBits(uint32_t bits)
QPixmap loadPixmap(QString url, bool fill_cache)
rviz::IntProperty * top_property_
virtual void setStatus(StatusProperty::Level level, const QString &name, const QString &text)
virtual QString getName() const
void setOverlaysEnabled(bool overlays_enabled)
virtual void update(float wall_dt, float ros_dt)
Connection registerCallback(const C &callback)