Go to the documentation of this file.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 #include "bounding_box_display_common.h"
00036 #include "bounding_box_display.h"
00037 #include <jsk_topic_tools/color_utils.h>
00038
00039 namespace jsk_rviz_plugins
00040 {
00041
00042 BoundingBoxDisplay::BoundingBoxDisplay()
00043 {
00044 coloring_property_ = new rviz::EnumProperty(
00045 "coloring", "Flat color",
00046 "coloring method",
00047 this, SLOT(updateColoring()));
00048 coloring_property_->addOption("Flat color", 0);
00049 coloring_property_->addOption("Label", 1);
00050 coloring_property_->addOption("Value", 2);
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 BoundingBoxDisplay::~BoundingBoxDisplay()
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 BoundingBoxDisplay::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 BoundingBoxDisplay::updateLineWidth()
00097 {
00098 line_width_ = line_width_property_->getFloat();
00099 if (latest_msg_) {
00100 processMessage(latest_msg_);
00101 }
00102 }
00103
00104 void BoundingBoxDisplay::updateColor()
00105 {
00106 color_ = color_property_->getColor();
00107 if (latest_msg_) {
00108 processMessage(latest_msg_);
00109 }
00110 }
00111
00112 void BoundingBoxDisplay::updateAlpha()
00113 {
00114 alpha_ = alpha_property_->getFloat();
00115 if (latest_msg_) {
00116 processMessage(latest_msg_);
00117 }
00118 }
00119
00120 void BoundingBoxDisplay::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 if (latest_msg_) {
00130 processMessage(latest_msg_);
00131 }
00132 }
00133
00134 void BoundingBoxDisplay::updateColoring()
00135 {
00136 if (coloring_property_->getOptionInt() == 0) {
00137 coloring_method_ = "flat";
00138 color_property_->show();
00139 }
00140 else if (coloring_property_->getOptionInt() == 1) {
00141 coloring_method_ = "label";
00142 color_property_->hide();
00143 }
00144 else if (coloring_property_->getOptionInt() == 2) {
00145 coloring_method_ = "value";
00146 color_property_->hide();
00147 }
00148
00149 if (latest_msg_) {
00150 processMessage(latest_msg_);
00151 }
00152 }
00153
00154 void BoundingBoxDisplay::updateShowCoords()
00155 {
00156 show_coords_ = show_coords_property_->getBool();
00157
00158 if (!show_coords_) {
00159 hideCoords();
00160 }
00161 else if (latest_msg_) {
00162 processMessage(latest_msg_);
00163 }
00164 }
00165
00166 void BoundingBoxDisplay::reset()
00167 {
00168 MFDClass::reset();
00169 shapes_.clear();
00170 edges_.clear();
00171 coords_nodes_.clear();
00172 coords_objects_.clear();
00173 latest_msg_.reset();
00174 }
00175
00176 void BoundingBoxDisplay::processMessage(
00177 const jsk_recognition_msgs::BoundingBox::ConstPtr& msg)
00178 {
00179
00180 latest_msg_ = msg;
00181
00182
00183 jsk_recognition_msgs::BoundingBoxArrayPtr bbox_array_msg(new jsk_recognition_msgs::BoundingBoxArray);
00184 bbox_array_msg->header = msg->header;
00185 std::vector<jsk_recognition_msgs::BoundingBox> boxes;
00186 boxes.push_back(*msg);
00187 bbox_array_msg->boxes = boxes;
00188
00189 if (!only_edge_) {
00190 showBoxes(bbox_array_msg);
00191 }
00192 else {
00193 showEdges(bbox_array_msg);
00194 }
00195
00196 if (show_coords_) {
00197 showCoords(bbox_array_msg);
00198 }
00199 else {
00200 hideCoords();
00201 }
00202 }
00203
00204 }
00205
00206 #include <pluginlib/class_list_macros.h>
00207 PLUGINLIB_EXPORT_CLASS(jsk_rviz_plugins::BoundingBoxDisplay, rviz::Display)