00001 
00002 
00003 
00004 
00005 
00006 
00007 
00008 
00009 
00010 
00011 
00012 
00013 
00014 
00015 
00016 
00017 
00018 
00019 
00020 
00021 
00022 
00023 
00024 
00025 
00026 
00027 
00028 
00029 
00030 
00031 
00032 
00033 
00034 
00035 
00036 #include <rviz/uniform_string_stream.h>
00037 #include <image_transport/image_transport.h>
00038 #include "camera_info_display.h"
00039 #include <OGRE/OgreMaterialManager.h>
00040 #include <OGRE/OgreMaterial.h>
00041 #include <OGRE/OgreBlendMode.h>
00042 #include <QImage>
00043 #include <OGRE/OgreHardwarePixelBuffer.h>
00044 
00045 namespace jsk_rviz_plugins
00046 {
00047   TrianglePolygon::TrianglePolygon(
00048     Ogre::SceneManager* manager,
00049     Ogre::SceneNode* node,
00050     const cv::Point3d& O,
00051     const cv::Point3d& A,
00052     const cv::Point3d& B,
00053     const std::string& name,
00054     const Ogre::ColourValue& color,
00055     bool use_color,
00056     bool upper_triangle)
00057   {
00058     
00059 
00060     manual_ = manager->createManualObject();
00061     manual_->clear();
00062     manual_->begin(name,
00063                    Ogre::RenderOperation::OT_TRIANGLE_STRIP);
00064     manual_->position(O.x, O.y, O.z);
00065     if (upper_triangle) {
00066       manual_->textureCoord(0, 0);
00067     }
00068     else {
00069       manual_->textureCoord(1, 0);
00070     }
00071     if (use_color) {
00072       manual_->colour(color);
00073     }
00074     manual_->position(A.x, A.y, A.z);
00075     if (upper_triangle) {
00076       manual_->textureCoord(1, 0);
00077     }
00078     else {
00079       manual_->textureCoord(1, 1);
00080     }
00081     if (use_color) {
00082       manual_->colour(color);
00083     }
00084     manual_->position(B.x, B.y, B.z);
00085     if (upper_triangle) {
00086       manual_->textureCoord(0, 1);
00087     }
00088     else {
00089       manual_->textureCoord(0, 1);
00090     }
00091     if (use_color) {
00092       manual_->colour(color);
00093     }
00094     manual_->end();
00095     node->attachObject(manual_);
00096   }
00097 
00098   TrianglePolygon::~TrianglePolygon()
00099   {
00100     manual_->detachFromParent();
00101     
00102   }
00103 
00104   CameraInfoDisplay::CameraInfoDisplay(): image_updated_(true)
00105   {
00107     
00109     far_clip_distance_property_ = new rviz::FloatProperty(
00110       "far clip",
00111       1.0,
00112       "far clip distance from the origin of camera info",
00113       this, SLOT(updateFarClipDistance()));
00114     show_edges_property_ = new rviz::BoolProperty(
00115       "show edges",
00116       true,
00117       "show edges of the region of the camera info",
00118       this, SLOT(updateShowEdges()));
00119     show_polygons_property_ = new rviz::BoolProperty(
00120       "show polygons",
00121       true,
00122       "show polygons of the region of the camera info",
00123       this, SLOT(updateShowPolygons()));
00124     not_show_side_polygons_property_ = new rviz::BoolProperty(
00125       "not show side polygons",
00126       true,
00127       "do not show polygons of the region of the camera info",
00128       this, SLOT(updateNotShowSidePolygons()));
00129     use_image_property_ = new rviz::BoolProperty(
00130       "use image",
00131       false,
00132       "use image as texture",
00133       this, SLOT(updateUseImage()));
00134     image_topic_property_ = new rviz::RosTopicProperty(
00135       "Image Topic", "",
00136       ros::message_traits::datatype<sensor_msgs::Image>(),
00137       "sensor_msgs::Image topic to subscribe to.",
00138       this, SLOT( updateImageTopic() ));
00139     image_topic_property_->hide();
00140     image_transport_hints_property_ = new ImageTransportHintsProperty(
00141       "transport hints",
00142       "transport hint for image subscription",
00143       this, SLOT( updateImageTopic() ));
00144     image_transport_hints_property_->hide();
00145 
00146     color_property_ = new rviz::ColorProperty(
00147       "color",
00148       QColor(85, 255, 255),
00149       "color of CameraInfo",
00150       this, SLOT(updateColor()));
00151     edge_color_property_ = new rviz::ColorProperty(
00152       "edge color",
00153       QColor(125, 125, 125),
00154       "edge color of CameraInfo",
00155       this, SLOT(updateEdgeColor()));
00156     alpha_property_ = new rviz::FloatProperty(
00157       "alpha",
00158       0.5,
00159       "alpha blending value",
00160       this, SLOT(updateAlpha()));
00161   }
00162 
00163   CameraInfoDisplay::~CameraInfoDisplay()
00164   {
00165     if (edges_) {
00166       edges_->clear();
00167     }
00168     polygons_.clear();
00169     delete far_clip_distance_property_;
00170     delete color_property_;
00171     delete alpha_property_;
00172     delete show_polygons_property_;
00173     delete edge_color_property_;
00174   }
00175 
00176   void CameraInfoDisplay::reset()
00177   {
00178     MFDClass::reset();
00179     if (edges_) {
00180       edges_->clear();
00181     }
00182     polygons_.clear();
00183     camera_info_ = sensor_msgs::CameraInfo::ConstPtr(); 
00184   }
00185 
00186   void CameraInfoDisplay::onInitialize()
00187   {
00188     MFDClass::onInitialize();
00189     scene_node_ = scene_manager_->getRootSceneNode()->createChildSceneNode();
00190     updateColor();
00191     updateAlpha();
00192     updateFarClipDistance();
00193     updateShowPolygons();
00194     updateNotShowSidePolygons();
00195     updateShowEdges();
00196     updateImageTopic();
00197     updateUseImage();
00198     updateEdgeColor();
00199   }
00200 
00201   void CameraInfoDisplay::processMessage(
00202     const sensor_msgs::CameraInfo::ConstPtr& msg)
00203   {
00204     if (!isSameCameraInfo(msg)) {
00205       createCameraInfoShapes(msg);
00206     }
00207     
00208      Ogre::Vector3 position;
00209      Ogre::Quaternion quaternion;
00210      if(!context_->getFrameManager()->getTransform(msg->header.frame_id,
00211                                                    msg->header.stamp,
00212                                                    position,
00213                                                    quaternion)) {
00214        ROS_ERROR( "Error transforming pose '%s' from frame '%s' to frame '%s'",
00215                   qPrintable( getName() ), msg->header.frame_id.c_str(),
00216                   qPrintable( fixed_frame_ ));
00217      }
00218      scene_node_->setPosition(position);
00219      scene_node_->setOrientation(quaternion);
00220      camera_info_ = msg;        
00221   }
00222 
00223   void CameraInfoDisplay::update(float wall_dt, float ros_dt)
00224   {
00225     boost::mutex::scoped_lock lock(mutex_);
00226     if (image_updated_) {
00227       ROS_DEBUG("image updated");
00228       if (!bottom_texture_.isNull()) {
00229         drawImageTexture();
00230         image_updated_ = false;
00231       }
00232     }
00233   }
00234 
00235   bool CameraInfoDisplay::isSameCameraInfo(
00236     const sensor_msgs::CameraInfo::ConstPtr& msg)
00237   {
00238     if (camera_info_) {
00239       bool meta_same_p =
00240         msg->header.frame_id == camera_info_->header.frame_id &&
00241         msg->height == camera_info_->height &&
00242         msg->width == camera_info_->width &&
00243         msg->distortion_model == camera_info_->distortion_model;
00244       if (meta_same_p) {
00245         for (size_t i = 0; i < msg->P.size(); i++) {
00246           if (msg->P[i] != camera_info_->P[i]) {
00247             return false;
00248           }
00249         }
00250         return true;
00251       }
00252       else {
00253         return false;
00254       }
00255     }
00256     else {
00257       return false;
00258     }
00259   }
00260 
00261   void CameraInfoDisplay::addPointToEdge(
00262     const cv::Point3d& point)
00263   {
00264     Ogre::Vector3 p;
00265     p[0] = point.x;
00266     p[1] = point.y;
00267     p[2] = point.z;
00268     edges_->addPoint(p);
00269   }
00270 
00271   void CameraInfoDisplay::addPolygon(
00272     const cv::Point3d& O, const cv::Point3d& A, const cv::Point3d& B, std::string name, bool use_color, bool upper_triangle)
00273   {
00274     Ogre::ColourValue color = rviz::qtToOgre(color_);
00275     color.a = alpha_;
00276     TrianglePolygon::Ptr triangle (new TrianglePolygon(
00277                                      scene_manager_,
00278                                      scene_node_,
00279                                      O, A, B, name,
00280                                      color,
00281                                      use_color,
00282                                      upper_triangle));
00283     polygons_.push_back(triangle);
00284   }
00285 
00286   void CameraInfoDisplay::createTextureForBottom(int width, int height)
00287   {
00288     if (bottom_texture_.isNull()
00289         || bottom_texture_->getWidth() != width
00290         || bottom_texture_->getHeight() != height) {
00291       static uint32_t count = 0;
00292       rviz::UniformStringStream ss;
00293       ss << "CameraInfoDisplayPolygonBottom" << count++;
00294       material_bottom_
00295         = Ogre::MaterialManager::getSingleton().create(
00296           ss.str(),
00297           Ogre::ResourceGroupManager::DEFAULT_RESOURCE_GROUP_NAME);
00298       bottom_texture_ = Ogre::TextureManager::getSingleton().createManual(
00299         material_bottom_->getName() + "Texture",        
00300         Ogre::ResourceGroupManager::DEFAULT_RESOURCE_GROUP_NAME,
00301         Ogre::TEX_TYPE_2D, width, height, 0, Ogre::PF_A8R8G8B8, Ogre::TU_DEFAULT);
00302       material_bottom_->getTechnique(0)->getPass(0)->setColourWriteEnabled(true);
00303       Ogre::ColourValue color = rviz::qtToOgre(color_);
00304       color.a = alpha_;
00305       material_bottom_->getTechnique(0)->getPass(0)->setAmbient(color);
00306       material_bottom_->setReceiveShadows(false);
00307       material_bottom_->getTechnique(0)->setLightingEnabled(true);
00308       material_bottom_->getTechnique(0)->getPass(0)->setCullingMode(Ogre::CULL_NONE);
00309       material_bottom_->getTechnique(0)->getPass(0)->setLightingEnabled(false);
00310       material_bottom_->getTechnique(0)->getPass(0)->setDepthWriteEnabled(false);
00311       material_bottom_->getTechnique(0)->getPass(0)->setDepthCheckEnabled(true);
00312 
00313       material_bottom_->getTechnique(0)->getPass(0)->setVertexColourTracking(Ogre::TVC_DIFFUSE);
00314       material_bottom_->getTechnique(0)->getPass(0)->createTextureUnitState(bottom_texture_->getName());
00315       material_bottom_->getTechnique(0)->getPass(0)->setSceneBlending(Ogre::SBT_TRANSPARENT_ALPHA);
00316     }
00317   }
00318 
00319   void CameraInfoDisplay::prepareMaterial()
00320   {
00321     if (texture_.isNull()) {
00322       
00323       static uint32_t count = 0;
00324       rviz::UniformStringStream ss;
00325       ss << "CameraInfoDisplayPolygon" << count++;
00326       material_
00327         = Ogre::MaterialManager::getSingleton().create(
00328           ss.str(),
00329           Ogre::ResourceGroupManager::DEFAULT_RESOURCE_GROUP_NAME);
00330       texture_ = Ogre::TextureManager::getSingleton().createManual(
00331         material_->getName() + "Texture",        
00332         Ogre::ResourceGroupManager::DEFAULT_RESOURCE_GROUP_NAME,
00333         Ogre::TEX_TYPE_2D, 1, 1, 0, Ogre::PF_A8R8G8B8, Ogre::TU_DEFAULT);
00334       material_->getTechnique(0)->getPass(0)->setColourWriteEnabled(true);
00335       Ogre::ColourValue color = rviz::qtToOgre(color_);
00336       color.a = alpha_;
00337       material_->getTechnique(0)->getPass(0)->setAmbient(color);
00338       material_->setReceiveShadows(false);
00339       material_->getTechnique(0)->setLightingEnabled(true);
00340       material_->getTechnique(0)->getPass(0)->setCullingMode(Ogre::CULL_NONE);
00341       material_->getTechnique(0)->getPass(0)->setLightingEnabled(false);
00342       material_->getTechnique(0)->getPass(0)->setDepthWriteEnabled(false);
00343       material_->getTechnique(0)->getPass(0)->setDepthCheckEnabled(true);
00344 
00345       material_->getTechnique(0)->getPass(0)->setVertexColourTracking(Ogre::TVC_DIFFUSE);
00346       material_->getTechnique(0)->getPass(0)->createTextureUnitState(texture_->getName());
00347       material_->getTechnique(0)->getPass(0)->setSceneBlending(Ogre::SBT_TRANSPARENT_ALPHA);
00348       createTextureForBottom(640, 480);
00349     }
00350   }
00351 
00352   void CameraInfoDisplay::subscribeImage(std::string topic)
00353   {
00354 
00355     image_sub_.shutdown();
00356     if (topic.empty()) {
00357       ROS_WARN("topic name is empty");
00358     }
00359     ros::NodeHandle nh;
00360     image_transport::ImageTransport it(nh);
00361     image_sub_ = it.subscribe(topic, 1, &CameraInfoDisplay::imageCallback, this,
00362                               image_transport_hints_property_->getTransportHints());
00363   }
00364 
00365   void CameraInfoDisplay::drawImageTexture()
00366   {
00367     bottom_texture_->getBuffer()->lock( Ogre::HardwareBuffer::HBL_NORMAL );
00368     const Ogre::PixelBox& pixelBox
00369       = bottom_texture_->getBuffer()->getCurrentLock();
00370     Ogre::uint8* pDest = static_cast<Ogre::uint8*> (pixelBox.data);
00371 
00372     
00373     
00374     if (use_image_ && !image_.empty() &&
00375         bottom_texture_->getHeight() == image_.rows &&
00376         bottom_texture_->getWidth() == image_.cols) {
00377       ROS_DEBUG("bottom_texture_->getHeight(): %u", bottom_texture_->getHeight());
00378       ROS_DEBUG("bottom_texture_->getWidth(): %u", bottom_texture_->getWidth());
00379       ROS_DEBUG("image_.rows: %d", image_.rows);
00380       ROS_DEBUG("image_.cols: %d", image_.cols);
00381 
00382       std::vector<cv::Mat> splitted;
00383       cv::split(image_, splitted);
00384       
00385       std::swap(splitted[0], splitted[2]);
00386       cv::Mat alpha(image_.rows, image_.cols, CV_8U, cv::Scalar(alpha_ * 255.0));
00387       splitted.push_back(alpha);
00388       cv::Mat boxMat(image_.rows, image_.cols, CV_8UC4, pDest);
00389       cv::merge(splitted, boxMat);
00390     } else {
00391       memset(pDest, 0, bottom_texture_->getWidth() * bottom_texture_->getHeight());
00392       QImage Hud(pDest, bottom_texture_->getWidth(), bottom_texture_->getHeight(), QImage::Format_ARGB32);
00393       for (size_t j = 0; j < bottom_texture_->getHeight(); j++) {
00394         for (size_t i = 0; i < bottom_texture_->getWidth(); i++) {
00395           Hud.setPixel(i, j, color_.rgba());
00396         }
00397       }
00398     }
00399     bottom_texture_->getBuffer()->unlock();
00400   }
00401 
00402   
00403   void CameraInfoDisplay::imageCallback(
00404       const sensor_msgs::Image::ConstPtr& msg)
00405   {
00406     boost::mutex::scoped_lock lock(mutex_);
00407     cv_bridge::CvImagePtr cv_ptr;
00408     try
00409     {
00410       cv_ptr = cv_bridge::toCvCopy(msg, sensor_msgs::image_encodings::RGB8);
00411       image_ = cv_ptr->image;
00412       
00413       if (bottom_texture_.isNull()
00414           || bottom_texture_->getWidth() != image_.cols
00415           || bottom_texture_->getHeight() != image_.rows) {
00416         createTextureForBottom(image_.cols, image_.rows);
00417         if (camera_info_) {
00418           createCameraInfoShapes(camera_info_);
00419         }
00420       }
00421       image_updated_ = true;
00422     }
00423     catch (cv_bridge::Exception& e)
00424     {
00425       ROS_ERROR("cv_bridge exception: %s", e.what());
00426     }
00427   }
00428 
00429   void CameraInfoDisplay::createCameraInfoShapes(
00430     const sensor_msgs::CameraInfo::ConstPtr& msg)
00431   {
00432     polygons_.clear();
00433     if (edges_) {
00434       edges_->clear();
00435     }
00436     image_geometry::PinholeCameraModel model;
00437     bool model_success_p = model.fromCameraInfo(msg);
00438     if (!model_success_p) {
00439       setStatus(rviz::StatusProperty::Error, "Camera Info", "Failed to create camera model from msg");
00440       ROS_ERROR("failed to create camera model");
00441       return;
00442     }
00443     
00444     if (model.fx() == 0.0 || model.fy() == 0.0) {
00445       setStatus(rviz::StatusProperty::Error, "Camera Info", "Invalid intrinsic matrix");
00446       ROS_ERROR_STREAM("camera model have invalid intrinsic matrix " << model.intrinsicMatrix());
00447       return;
00448     }
00449     setStatus(rviz::StatusProperty::Ok, "Camera Info", "OK");
00450 
00452     
00454     if (!edges_) {
00455       edges_.reset(new rviz::BillboardLine(context_->getSceneManager(),
00456                                            scene_node_));
00457       edges_->setLineWidth(0.01);
00458     }
00459 
00460     cv::Point2d a(0, 0), b(msg->width, 0),
00461       c(msg->width, msg->height), d(0, msg->height);
00462     
00463     cv::Point3d A = model.projectPixelTo3dRay(a);
00464     cv::Point3d B = model.projectPixelTo3dRay(b);
00465     cv::Point3d C = model.projectPixelTo3dRay(c);
00466     cv::Point3d D = model.projectPixelTo3dRay(d);
00467 
00468     cv::Point3d scaled_A = A * far_clip_distance_;
00469     cv::Point3d scaled_B = B * far_clip_distance_;
00470     cv::Point3d scaled_C = C * far_clip_distance_;
00471     cv::Point3d scaled_D = D * far_clip_distance_;
00472 
00473     cv::Point3d O(0, 0, 0);
00474 
00476     
00478     if (show_polygons_) {
00480       
00482       Ogre::ColourValue color = rviz::qtToOgre(color_);
00483       color.a = alpha_;
00484       prepareMaterial();
00485       if (!not_show_side_polygons_) {
00486         material_->getTechnique(0)->getPass(0)->setAmbient(color);
00487         {
00488           texture_->getBuffer()->lock( Ogre::HardwareBuffer::HBL_NORMAL );
00489           const Ogre::PixelBox& pixelBox
00490             = texture_->getBuffer()->getCurrentLock();
00491           Ogre::uint8* pDest = static_cast<Ogre::uint8*> (pixelBox.data);
00492           memset(pDest, 0, 1);
00493           QImage Hud(pDest, 1, 1, QImage::Format_ARGB32 );
00494           Hud.setPixel(0, 0, color_.rgba());
00495           texture_->getBuffer()->unlock();
00496         }
00497         addPolygon(O, scaled_B, scaled_A, material_->getName(), true, true);
00498         addPolygon(O, scaled_C, scaled_B, material_->getName(), true, true);
00499         addPolygon(O, scaled_D, scaled_C, material_->getName(), true, true);
00500         addPolygon(O, scaled_A, scaled_D, material_->getName(), true, true);
00501       }
00502       
00503       drawImageTexture();
00504 
00505       addPolygon(scaled_A, scaled_B, scaled_D, material_bottom_->getName(), false, true);
00506       addPolygon(scaled_B, scaled_C, scaled_D, material_bottom_->getName(), false, false);
00507     }
00509     
00511     if (show_edges_) {
00512       edges_->clear();
00513       edges_->setMaxPointsPerLine(2);
00514       edges_->setNumLines(8);
00515       edges_->setColor(edge_color_.red() / 255.0,
00516                        edge_color_.green() / 255.0,
00517                        edge_color_.blue() / 255.0,
00518                        alpha_);
00519       addPointToEdge(O); addPointToEdge(scaled_A); edges_->newLine();
00520       addPointToEdge(O); addPointToEdge(scaled_B); edges_->newLine();
00521       addPointToEdge(O); addPointToEdge(scaled_C); edges_->newLine();
00522       addPointToEdge(O); addPointToEdge(scaled_D); edges_->newLine();
00523       addPointToEdge(scaled_A); addPointToEdge(scaled_B); edges_->newLine();
00524       addPointToEdge(scaled_B); addPointToEdge(scaled_C); edges_->newLine();
00525       addPointToEdge(scaled_C); addPointToEdge(scaled_D); edges_->newLine();
00526       addPointToEdge(scaled_D); addPointToEdge(scaled_A);
00527     }
00528   }
00529 
00531   
00533   void CameraInfoDisplay::updateColor()
00534   {
00535     color_ = color_property_->getColor();
00536     if (camera_info_) {
00537       createCameraInfoShapes(camera_info_);
00538     }
00539   }
00540 
00541   void CameraInfoDisplay::updateEdgeColor()
00542   {
00543     edge_color_ = edge_color_property_->getColor();
00544     if (camera_info_) {
00545       createCameraInfoShapes(camera_info_);
00546     }
00547   }
00548 
00549   void CameraInfoDisplay::updateAlpha()
00550   {
00551     alpha_ = alpha_property_->getFloat();
00552     if (camera_info_) {
00553       createCameraInfoShapes(camera_info_);
00554     }
00555   }
00556 
00557   void CameraInfoDisplay::updateFarClipDistance()
00558   {
00559     far_clip_distance_ = far_clip_distance_property_->getFloat();
00560     if (camera_info_) {
00561       createCameraInfoShapes(camera_info_);
00562     }
00563   }
00564 
00565   void CameraInfoDisplay::updateShowPolygons()
00566   {
00567     show_polygons_ = show_polygons_property_->getBool();
00568     if (show_polygons_) {
00569       not_show_side_polygons_property_->show();
00570     }
00571     else {
00572       not_show_side_polygons_property_->hide();
00573     }
00574     if (camera_info_) {
00575       createCameraInfoShapes(camera_info_);
00576     }
00577   }
00578 
00579   void CameraInfoDisplay::updateShowEdges()
00580   {
00581     show_edges_ = show_edges_property_->getBool();
00582     if (camera_info_) {
00583       createCameraInfoShapes(camera_info_);
00584     }
00585   }
00586 
00587   void CameraInfoDisplay::updateImageTopic()
00588   {
00589     if (use_image_) {
00590       std::string topic = image_topic_property_->getStdString();
00591       subscribeImage(topic);
00592     } else {
00593       image_sub_.shutdown();
00594       
00595       image_updated_ = true;
00596     }
00597   }
00598 
00599   void CameraInfoDisplay::updateUseImage()
00600   {
00601     use_image_ = use_image_property_->getBool();
00602     if (use_image_) {
00603       image_topic_property_->show();
00604       image_transport_hints_property_->show();
00605     }
00606     else {
00607       image_topic_property_->hide();
00608       image_transport_hints_property_->hide();
00609     }
00610     updateImageTopic();
00611   }
00612   void CameraInfoDisplay::updateNotShowSidePolygons()
00613   {
00614     not_show_side_polygons_ = not_show_side_polygons_property_->getBool();
00615     if (camera_info_) {
00616       createCameraInfoShapes(camera_info_);
00617     }
00618   }
00619 }
00620 
00621 
00622 #include <pluginlib/class_list_macros.h>
00623 PLUGINLIB_EXPORT_CLASS( jsk_rviz_plugins::CameraInfoDisplay, rviz::Display )