bounding_box_array_display.cpp
Go to the documentation of this file.
00001 /*********************************************************************
00002  * Software License Agreement (BSD License)
00003  *
00004  *  Copyright (c) 2013, Ryohei Ueda and JSK Lab
00005  *  All rights reserved.
00006  *
00007  *  Redistribution and use in source and binary forms, with or without
00008  *  modification, are permitted provided that the following conditions
00009  *  are met:
00010  *
00011  *   * Redistributions of source code must retain the above copyright
00012  *     notice, this list of conditions and the following disclaimer.
00013  *   * Redistributions in binary form must reproduce the above
00014  *     copyright notice, this list of conditions and the following
00015  *     disclaimer in the documentation and/o2r other materials provided
00016  *     with the distribution.
00017  *   * Neither the name of the JSK Lab nor the names of its
00018  *     contributors may be used to endorse or promote products derived
00019  *     from this software without specific prior written permission.
00020  *
00021  *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00022  *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00023  *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00024  *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00025  *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00026  *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00027  *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00028  *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00029  *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00030  *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00031  *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00032  *  POSSIBILITY OF SUCH DAMAGE.
00033  *********************************************************************/
00034 
00035 #include "bounding_box_display_common.h"
00036 #include "bounding_box_array_display.h"
00037 #include <jsk_topic_tools/color_utils.h>
00038 
00039 namespace jsk_rviz_plugins
00040 {
00041 
00042   BoundingBoxArrayDisplay::BoundingBoxArrayDisplay()
00043   {
00044     coloring_property_ = new rviz::EnumProperty(
00045       "coloring", "Auto",
00046       "coloring method",
00047       this, SLOT(updateColoring()));
00048     coloring_property_->addOption("Flat color", 1);
00049     coloring_property_->addOption("Label", 2);
00050     coloring_property_->addOption("Value", 3);
00051 
00052     color_property_ = new rviz::ColorProperty(
00053       "color", QColor(25, 255, 0),
00054       "color to draw the bounding boxes",
00055       this, SLOT(updateColor()));
00056     alpha_property_ = new rviz::FloatProperty(
00057       "alpha", 0.8,
00058       "alpha value to draw the bounding boxes",
00059       this, SLOT(updateAlpha()));
00060     only_edge_property_ = new rviz::BoolProperty(
00061       "only edge", false,
00062       "show only the edges of the boxes",
00063       this, SLOT(updateOnlyEdge()));
00064     line_width_property_ = new rviz::FloatProperty(
00065       "line width", 0.005,
00066       "line width of the edges",
00067       this, SLOT(updateLineWidth()));
00068     show_coords_property_ = new rviz::BoolProperty(
00069       "show coords", false,
00070       "show coordinate of bounding box",
00071       this, SLOT(updateShowCoords()));
00072   }
00073 
00074   BoundingBoxArrayDisplay::~BoundingBoxArrayDisplay()
00075   {
00076     delete color_property_;
00077     delete alpha_property_;
00078     delete only_edge_property_;
00079     delete coloring_property_;
00080     delete show_coords_property_;
00081   }
00082 
00083   void BoundingBoxArrayDisplay::onInitialize()
00084   {
00085     MFDClass::onInitialize();
00086     scene_node_ = scene_manager_->getRootSceneNode()->createChildSceneNode();
00087 
00088     updateColor();
00089     updateAlpha();
00090     updateOnlyEdge();
00091     updateColoring();
00092     updateLineWidth();
00093     updateShowCoords();
00094   }
00095 
00096   void BoundingBoxArrayDisplay::updateLineWidth()
00097   {
00098     line_width_ = line_width_property_->getFloat();
00099     if (latest_msg_) {
00100       processMessage(latest_msg_);
00101     }
00102   }
00103 
00104   void BoundingBoxArrayDisplay::updateColor()
00105   {
00106     color_ = color_property_->getColor();
00107     if (latest_msg_) {
00108       processMessage(latest_msg_);
00109     }
00110   }
00111 
00112   void BoundingBoxArrayDisplay::updateAlpha()
00113   {
00114     alpha_ = alpha_property_->getFloat();
00115     if (latest_msg_) {
00116       processMessage(latest_msg_);
00117     }
00118   }
00119 
00120   void BoundingBoxArrayDisplay::updateOnlyEdge()
00121   {
00122     only_edge_ = only_edge_property_->getBool();
00123     if (only_edge_) {
00124       line_width_property_->show();
00125     }
00126     else {
00127       line_width_property_->hide();;
00128     }
00129     // Imediately apply attribute
00130     if (latest_msg_) {
00131       if (only_edge_) {
00132         showEdges(latest_msg_);
00133       }
00134       else {
00135         showBoxes(latest_msg_);
00136       }
00137     }
00138   }
00139 
00140   void BoundingBoxArrayDisplay::updateColoring()
00141   {
00142     if (coloring_property_->getOptionInt() == 0) {
00143       coloring_method_ = "auto";
00144       color_property_->hide();
00145     }
00146     else if (coloring_property_->getOptionInt() == 1) {
00147       coloring_method_ = "flat";
00148       color_property_->show();
00149     }
00150     else if (coloring_property_->getOptionInt() == 2) {
00151       coloring_method_ = "label";
00152       color_property_->hide();
00153     }
00154     else if (coloring_property_->getOptionInt() == 3) {
00155       coloring_method_ = "value";
00156       color_property_->hide();
00157     }
00158 
00159     if (latest_msg_) {
00160       processMessage(latest_msg_);
00161     }
00162   }
00163 
00164   void BoundingBoxArrayDisplay::updateShowCoords()
00165   {
00166     show_coords_ = show_coords_property_->getBool();
00167     // Immediately apply show_coords attribute
00168     if (!show_coords_) {
00169       hideCoords();
00170     }
00171     else if (show_coords_ && latest_msg_) {
00172       showCoords(latest_msg_);
00173     }
00174   }
00175 
00176   void BoundingBoxArrayDisplay::reset()
00177   {
00178     MFDClass::reset();
00179     shapes_.clear();
00180     edges_.clear();
00181     coords_nodes_.clear();
00182     coords_objects_.clear();
00183     latest_msg_.reset();
00184   }
00185 
00186   void BoundingBoxArrayDisplay::processMessage(
00187     const jsk_recognition_msgs::BoundingBoxArray::ConstPtr& msg)
00188   {
00189     // Store latest message
00190     latest_msg_ = msg;
00191 
00192     if (!only_edge_) {
00193       showBoxes(msg);
00194     }
00195     else {
00196       showEdges(msg);
00197     }
00198 
00199     if (show_coords_) {
00200       showCoords(msg);
00201     }
00202     else {
00203       hideCoords();
00204     }
00205   }
00206 
00207 }  // namespace jsk_rviz_plugins
00208 
00209 #include <pluginlib/class_list_macros.h>
00210 PLUGINLIB_EXPORT_CLASS(jsk_rviz_plugins::BoundingBoxArrayDisplay, rviz::Display)


jsk_rviz_plugins
Author(s): Kei Okada , Yohei Kakiuchi , Shohei Fujii , Ryohei Ueda
autogenerated on Wed May 1 2019 02:40:22