polygon_array_display.cpp
Go to the documentation of this file.
00001 // -*- mode: c++ -*-
00002 /*********************************************************************
00003  * Software License Agreement (BSD License)
00004  *
00005  *  Copyright (c) 2015, JSK Lab
00006  *  All rights reserved.
00007  *
00008  *  Redistribution and use in source and binary forms, with or without
00009  *  modification, are permitted provided that the following conditions
00010  *  are met:
00011  *
00012  *   * Redistributions of source code must retain the above copyright
00013  *     notice, this list of conditions and the following disclaimer.
00014  *   * Redistributions in binary form must reproduce the above
00015  *     copyright notice, this list of conditions and the following
00016  *     disclaimer in the documentation and/o2r other materials provided
00017  *     with the distribution.
00018  *   * Neither the name of the JSK Lab nor the names of its
00019  *     contributors may be used to endorse or promote products derived
00020  *     from this software without specific prior written permission.
00021  *
00022  *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00023  *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00024  *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00025  *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00026  *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00027  *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00028  *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00029  *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00030  *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00031  *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00032  *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00033  *  POSSIBILITY OF SUCH DAMAGE.
00034  *********************************************************************/
00035 
00036 #define BOOST_PARAMETER_MAX_ARITY 7
00037 
00038 #include "polygon_array_display.h"
00039 #include "rviz/properties/parse_color.h"
00040 #include <rviz/validate_floats.h>
00041 #include <jsk_topic_tools/color_utils.h>
00042 #include <jsk_recognition_utils/geo/polygon.h>
00043 
00044 namespace jsk_rviz_plugins
00045 {
00046   PolygonArrayDisplay::PolygonArrayDisplay()
00047   {
00048     coloring_property_ = new rviz::EnumProperty(
00049       "coloring", "Auto",
00050       "coloring method",
00051       this, SLOT(updateColoring()));
00052     coloring_property_->addOption("Auto", 0);
00053     coloring_property_->addOption("Flat color", 1);
00054     coloring_property_->addOption("Liekelihood", 2);
00055     coloring_property_->addOption("Label", 3);
00056     color_property_ = new rviz::ColorProperty(
00057       "Color", QColor(25, 255, 0),
00058       "Color to draw the polygons.",
00059       this, SLOT(queueRender()));
00060     alpha_property_ = new rviz::FloatProperty(
00061       "Alpha", 1.0,
00062       "Amount of transparency to apply to the polygon.",
00063       this, SLOT(queueRender()));
00064     only_border_property_ = new rviz::BoolProperty(
00065       "only border", true,
00066       "only shows the borders of polygons",
00067       this, SLOT(updateOnlyBorder()));
00068     show_normal_property_ = new rviz::BoolProperty(
00069       "show normal", true,
00070       "show normal direction",
00071       this, SLOT(updateShowNormal()));
00072     normal_length_property_ = new rviz::FloatProperty(
00073       "normal length", 0.1,
00074       "normal length",
00075       this, SLOT(updateNormalLength()));
00076     normal_length_property_->setMin(0);
00077     //only_border_ = true;
00078     alpha_property_->setMin(0);
00079     alpha_property_->setMax(1);
00080   }
00081   
00082   PolygonArrayDisplay::~PolygonArrayDisplay()
00083   {
00084     delete alpha_property_;
00085     delete color_property_;
00086     delete only_border_property_;
00087     delete coloring_property_;
00088     delete show_normal_property_;
00089     delete normal_length_property_;
00090     for (size_t i = 0; i < lines_.size(); i++) {
00091       delete lines_[i];
00092     }
00093     
00094     for (size_t i = 0; i < materials_.size(); i++) {
00095       materials_[i]->unload();
00096       Ogre::MaterialManager::getSingleton().remove(materials_[i]->getName());
00097     }
00098     
00099     for (size_t i = 0; i < manual_objects_.size(); i++) {
00100       scene_manager_->destroyManualObject(manual_objects_[i]);
00101       scene_manager_->destroySceneNode(scene_nodes_[i]);
00102     }
00103   }
00104   
00105   void PolygonArrayDisplay::onInitialize()
00106   {
00107     MFDClass::onInitialize();
00108     updateOnlyBorder();
00109     updateColoring();
00110     updateShowNormal();
00111     updateNormalLength();
00112   }
00113 
00114   void PolygonArrayDisplay::allocateMaterials(int num)
00115   {
00116     if (only_border_) {
00117       return;
00118     }
00119     static uint32_t count = 0;
00120     
00121     if (num > materials_.size()) {
00122       for (size_t i = materials_.size(); num > i; i++) {
00123         std::stringstream ss;
00124         ss << "PolygonArrayMaterial" << count++;
00125         Ogre::MaterialPtr material
00126           = Ogre::MaterialManager::getSingleton().create(ss.str(), "rviz");
00127         material->setReceiveShadows(false);
00128         material->getTechnique(0)->setLightingEnabled(true);
00129         material->getTechnique(0)->setAmbient(0.5, 0.5, 0.5);
00130         materials_.push_back(material);
00131       }
00132     }
00133   }
00134   
00135   bool validateFloats(const jsk_recognition_msgs::PolygonArray& msg)
00136   {
00137     for (size_t i = 0; i < msg.polygons.size(); i++) {
00138       if (!rviz::validateFloats(msg.polygons[i].polygon.points))
00139         return false;
00140     }
00141     return true;
00142   }
00143   
00144   void PolygonArrayDisplay::reset()
00145   {
00146     MFDClass::reset();
00147     for (size_t i = 0; i < manual_objects_.size(); i++) {
00148       manual_objects_[i]->clear();
00149     }
00150   }
00151 
00152   void PolygonArrayDisplay::updateSceneNodes(
00153     const jsk_recognition_msgs::PolygonArray::ConstPtr& msg)
00154   {
00155     int scale_factor = 2;
00156     if (only_border_) {
00157       scale_factor = 1;
00158     }
00159     if (msg->polygons.size() * scale_factor > manual_objects_.size()) {
00160       for (size_t i = manual_objects_.size();
00161            i < msg->polygons.size() * scale_factor;
00162            i++) {
00163         Ogre::SceneNode* scene_node
00164           = scene_node_->createChildSceneNode();
00165         Ogre::ManualObject* manual_object
00166           = scene_manager_->createManualObject();
00167         manual_object->setDynamic(true);
00168         scene_node->attachObject(manual_object);
00169         manual_objects_.push_back(manual_object);
00170         scene_nodes_.push_back(scene_node);
00171       }
00172     }
00173     else if (msg->polygons.size() * scale_factor < manual_objects_.size()) {
00174       for (size_t i = msg->polygons.size() * scale_factor;
00175            i < manual_objects_.size(); i++) {
00176         manual_objects_[i]->setVisible(false);
00177       }
00178     }
00179     // arrow nodes
00180     if (msg->polygons.size() > arrow_objects_.size()) {
00181       for (size_t i = arrow_objects_.size(); i < msg->polygons.size(); i++) {
00182         Ogre::SceneNode* scene_node = scene_node_->createChildSceneNode();
00183         ArrowPtr arrow (new rviz::Arrow(scene_manager_, scene_node));
00184         scene_node->setVisible(false);
00185         arrow_objects_.push_back(arrow);
00186         arrow_nodes_.push_back(scene_node);
00187       }
00188     }
00189     else if (msg->polygons.size() < manual_objects_.size()) {
00190       for (size_t i = msg->polygons.size(); i < arrow_nodes_.size(); i++) {
00191         //arrow_objects_[i]->setVisible(false);
00192         arrow_nodes_[i]->setVisible(false);
00193       }
00194     }
00195   }
00196 
00197   void PolygonArrayDisplay::updateLines(int num)
00198   {
00199     if (num > lines_.size()) {
00200       for (size_t i = lines_.size(); i < num; i++) {
00201         rviz::BillboardLine* line
00202           = new rviz::BillboardLine(context_->getSceneManager(),
00203                                     scene_nodes_[i]);
00204         line->setLineWidth(0.01);
00205         line->setNumLines(1);
00206         lines_.push_back(line);
00207       }
00208     }
00209     for (size_t i = 0; i < lines_.size(); i++) {
00210       lines_[i]->clear();
00211     }
00212   }
00213   
00214   Ogre::ColourValue PolygonArrayDisplay::getColor(size_t index)
00215   {
00216     Ogre::ColourValue color;
00217     if (coloring_method_ == "auto") {
00218       std_msgs::ColorRGBA ros_color = jsk_topic_tools::colorCategory20(index);
00219       color.r = ros_color.r;
00220       color.g = ros_color.g;
00221       color.b = ros_color.b;
00222       color.a = ros_color.a;
00223     }
00224     else if (coloring_method_ == "flat") {
00225       color = rviz::qtToOgre(color_property_->getColor());
00226     }
00227     else if (coloring_method_ == "likelihood") {
00228       if (latest_msg_->likelihood.size() < index) {
00229         setStatus(rviz::StatusProperty::Error,
00230                   "Topic",
00231                   "Message does not have lieklihood fields");
00232       }
00233       else {
00234         std_msgs::ColorRGBA ros_color
00235           = jsk_topic_tools::heatColor(latest_msg_->likelihood[index]);
00236         color.r = ros_color.r;
00237         color.g = ros_color.g;
00238         color.b = ros_color.b;
00239         color.a = ros_color.a;
00240       }
00241     }
00242     else if (coloring_method_ == "label") {
00243       if (latest_msg_->labels.size() < index) {
00244         setStatus(rviz::StatusProperty::Error,
00245                   "Topic",
00246                   "Message does not have lebels fields");
00247       }
00248       else {
00249         std_msgs::ColorRGBA ros_color
00250           = jsk_topic_tools::colorCategory20(latest_msg_->labels[index]);
00251         color.r = ros_color.r;
00252         color.g = ros_color.g;
00253         color.b = ros_color.b;
00254         color.a = ros_color.a;
00255       }
00256     }
00257     color.a = alpha_property_->getFloat();
00258     return color;
00259   }
00260 
00261   void PolygonArrayDisplay::processLine(
00262     const size_t i,
00263     const geometry_msgs::PolygonStamped& polygon)
00264   {
00265     Ogre::SceneNode* scene_node = scene_nodes_[i];
00266     //Ogre::ManualObject* manual_object = manual_objects_[i];
00267     Ogre::Vector3 position;
00268     Ogre::Quaternion orientation;
00269     if(!context_->getFrameManager()->getTransform(
00270          polygon.header, position, orientation)) {
00271       ROS_DEBUG("Error transforming from frame '%s' to frame '%s'",
00272                  polygon.header.frame_id.c_str(), qPrintable(fixed_frame_));
00273     }
00274     scene_node->setPosition(position);
00275     scene_node->setOrientation(orientation);
00276     rviz::BillboardLine* line = lines_[i];
00277     line->clear();
00278     line->setMaxPointsPerLine(polygon.polygon.points.size() + 1);
00279         
00280     Ogre::ColourValue color = getColor(i);
00281     line->setColor(color.r, color.g, color.b, color.a);
00282 
00283     for (size_t i = 0; i < polygon.polygon.points.size(); ++i) {
00284       Ogre::Vector3 step_position;
00285       step_position.x = polygon.polygon.points[i].x;
00286       step_position.y = polygon.polygon.points[i].y;
00287       step_position.z = polygon.polygon.points[i].z;
00288       line->addPoint(step_position);
00289     }
00290     Ogre::Vector3 step_position;
00291     step_position.x = polygon.polygon.points[0].x;
00292     step_position.y = polygon.polygon.points[0].y;
00293     step_position.z = polygon.polygon.points[0].z;
00294     line->addPoint(step_position);
00295   }
00296 
00297   void PolygonArrayDisplay::processPolygonMaterial(const size_t i)
00298   {
00299     Ogre::ColourValue color = getColor(i);
00300     materials_[i]->getTechnique(0)->setAmbient(color * 0.5);
00301     materials_[i]->getTechnique(0)->setDiffuse(color);
00302     if (color.a < 0.9998) {
00303       materials_[i]->getTechnique(0)->setSceneBlending(
00304         Ogre::SBT_TRANSPARENT_ALPHA);
00305       materials_[i]->getTechnique(0)->setDepthWriteEnabled(false);
00306     }
00307     else {
00308       materials_[i]->getTechnique(0)->setSceneBlending(Ogre::SBT_REPLACE);
00309       materials_[i]->getTechnique(0)->setDepthWriteEnabled(true);
00310     }
00311       
00312     materials_[i]->getTechnique(0)->setAmbient(color * 0.5);
00313     materials_[i]->getTechnique(0)->setDiffuse(color);
00314   }
00315 
00316   void PolygonArrayDisplay::processPolygon(
00317     const size_t i, const geometry_msgs::PolygonStamped& polygon)
00318   {
00319     Ogre::Vector3 position;
00320     Ogre::Quaternion orientation;
00321     if(!context_->getFrameManager()->getTransform(
00322          polygon.header, position, orientation)) {
00323       ROS_DEBUG("Error transforming from frame '%s' to frame '%s'",
00324                  polygon.header.frame_id.c_str(), qPrintable(fixed_frame_));
00325       return;
00326     }
00327     
00328     {
00329       Ogre::SceneNode* scene_node = scene_nodes_[i * 2];
00330       Ogre::ManualObject* manual_object = manual_objects_[i * 2];
00331       scene_node->setPosition(position);
00332       scene_node->setOrientation(orientation);
00333       manual_object->clear();
00334       manual_object->setVisible(true);
00335       
00336       jsk_recognition_utils::Polygon geo_polygon
00337         = jsk_recognition_utils::Polygon::fromROSMsg(polygon.polygon);
00338       std::vector<jsk_recognition_utils::Polygon::Ptr>
00339         triangles = geo_polygon.decomposeToTriangles();
00340         
00341       uint32_t num_points = 0;
00342       for (size_t j = 0; j < triangles.size(); j++) {
00343         num_points += triangles[j]->getNumVertices();
00344       }
00345       if(num_points > 0) {
00346         manual_object->estimateVertexCount(num_points * 2);
00347         manual_object->begin(
00348           materials_[i]->getName(), Ogre::RenderOperation::OT_TRIANGLE_LIST);
00349         for (size_t ii = 0; ii < triangles.size(); ii++) {
00350           jsk_recognition_utils::Polygon::Ptr triangle = triangles[ii];
00351           size_t num_vertices = triangle->getNumVertices();
00352           for (size_t j = 0; j < num_vertices; j++) {
00353             Eigen::Vector3f v = triangle->getVertex(j);
00354             manual_object->position(v[0], v[1], v[2]);
00355           }
00356           for (int j = num_vertices - 1; j >= 0; j--) {
00357             Eigen::Vector3f v = triangle->getVertex(j);
00358             manual_object->position(v[0], v[1], v[2]);
00359           }
00360         }
00361         manual_object->end();
00362       }
00363     }
00364   }
00365   
00366   void PolygonArrayDisplay::processNormal(
00367     const size_t i, const geometry_msgs::PolygonStamped& polygon)
00368   {
00369     Ogre::SceneNode* scene_node = arrow_nodes_[i];
00370     scene_node->setVisible(true);
00371     ArrowPtr arrow = arrow_objects_[i];
00372     Ogre::Vector3 position;
00373     Ogre::Quaternion orientation;
00374     if(!context_->getFrameManager()->getTransform(
00375          polygon.header, position, orientation)) {
00376       ROS_DEBUG("Error transforming from frame '%s' to frame '%s'",
00377                  polygon.header.frame_id.c_str(), qPrintable(fixed_frame_));
00378       return;
00379     }
00380     scene_node->setPosition(position);
00381     scene_node->setOrientation(orientation); // scene node is at frame pose
00382     jsk_recognition_utils::Polygon geo_polygon
00383       = jsk_recognition_utils::Polygon::fromROSMsg(polygon.polygon);
00384     jsk_recognition_utils::Vertices vertices
00385       = geo_polygon.getVertices();
00386     Eigen::Vector3f centroid(0, 0, 0); // should be replaced by centroid method
00387     if (vertices.size() == 0) {
00388       ROS_ERROR("the size of vertices is 0");
00389     }
00390     else {
00391       for (size_t j = 0; j < vertices.size(); j++) {
00392         centroid = vertices[j] + centroid;
00393       }
00394       centroid = centroid / vertices.size();
00395     }
00396     Ogre::Vector3 pos(centroid[0], centroid[1], centroid[2]);
00397     Eigen::Vector3f normal = geo_polygon.getNormal();
00398     Ogre::Vector3 direction(normal[0], normal[1], normal[2]);
00399     if (isnan(direction[0]) || isnan(direction[1]) || isnan(direction[2])) {
00400       ROS_ERROR("failed to compute normal direction");
00401       Ogre::Vector3 zeroscale(0, 0, 0);
00402       arrow->setScale(zeroscale);
00403       return;
00404     }
00405     Ogre::Vector3 scale(normal_length_, normal_length_, normal_length_);
00406     arrow->setPosition(pos);
00407     arrow->setDirection(direction);
00408     
00409     arrow->setScale(scale);
00410     arrow->setColor(getColor(i));
00411   }
00412   
00413   void PolygonArrayDisplay::processMessage(
00414     const jsk_recognition_msgs::PolygonArray::ConstPtr& msg)
00415   {
00416     if (!validateFloats(*msg)) {
00417       setStatus(rviz::StatusProperty::Error,
00418                 "Topic",
00419                 "Message contained invalid floating point values"
00420                 "(nans or infs)");
00421       return;
00422     }
00423     setStatus(rviz::StatusProperty::Ok,
00424               "Topic",
00425               "ok");
00426     latest_msg_ = msg;
00427     // create nodes and manual objects
00428     updateSceneNodes(msg);
00429     allocateMaterials(msg->polygons.size());
00430     updateLines(msg->polygons.size());
00431     if (only_border_) {
00432       // use line_
00433       for (size_t i = 0; i < manual_objects_.size(); i++) {
00434         manual_objects_[i]->setVisible(false);
00435       }
00436       for (size_t i = 0; i < msg->polygons.size(); i++) {
00437         geometry_msgs::PolygonStamped polygon = msg->polygons[i];
00438         if (polygon.polygon.points.size() >= 3) {
00439           processLine(i, polygon);
00440         }
00441       }
00442     }
00443     else {
00444       for (size_t i = 0; i < msg->polygons.size(); i++) {
00445         processPolygonMaterial(i);
00446       }
00447       
00448       for (size_t i = 0; i < msg->polygons.size(); i++) {
00449         geometry_msgs::PolygonStamped polygon = msg->polygons[i];
00450         processPolygon(i, polygon);
00451       }
00452     }
00453 
00454     if (show_normal_) {
00455       for (size_t i = 0; i < msg->polygons.size(); i++) {
00456         geometry_msgs::PolygonStamped polygon = msg->polygons[i];
00457         processNormal(i, polygon);
00458       }
00459     }
00460   }
00461 
00462   void PolygonArrayDisplay::updateColoring()
00463   {
00464     if (coloring_property_->getOptionInt() == 0) {
00465       coloring_method_ = "auto";
00466       color_property_->hide();
00467     }
00468     else if (coloring_property_->getOptionInt() == 1) {
00469       coloring_method_ = "flat";
00470       color_property_->show();
00471     }
00472     else if (coloring_property_->getOptionInt() == 2) {
00473       coloring_method_ = "likelihood";
00474       color_property_->hide();
00475     }
00476     else if (coloring_property_->getOptionInt() == 3) {
00477       coloring_method_ = "label";
00478       color_property_->hide();
00479     }
00480   }
00481 
00482   void PolygonArrayDisplay::updateOnlyBorder()
00483   {
00484     only_border_ = only_border_property_->getBool();
00485   }
00486 
00487   void PolygonArrayDisplay::updateShowNormal()
00488   {
00489     show_normal_ = show_normal_property_->getBool();
00490     if (show_normal_) {
00491       normal_length_property_->show();
00492     }
00493     else {
00494       normal_length_property_->hide();
00495       for (size_t i = 0; i < arrow_nodes_.size(); i++) {
00496         arrow_nodes_[i]->setVisible(false);
00497       }
00498     }
00499   }
00500 
00501   void PolygonArrayDisplay::updateNormalLength()
00502   {
00503     normal_length_ = normal_length_property_->getFloat();
00504   }
00505 }
00506 
00507 #include <pluginlib/class_list_macros.h>
00508 PLUGINLIB_EXPORT_CLASS(jsk_rviz_plugins::PolygonArrayDisplay, rviz::Display)


jsk_rviz_plugins
Author(s): Kei Okada , Yohei Kakiuchi , Shohei Fujii , Ryohei Ueda
autogenerated on Sun Sep 13 2015 22:29:03