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 
00036 #include "people_position_measurement_array_display.h"
00037 #include <rviz/uniform_string_stream.h>
00038 #include <rviz/view_manager.h>
00039 #include <rviz/render_panel.h>
00040 #include <OGRE/OgreCamera.h>
00041 #include <QPainter>
00042 #include <rviz/ogre_helpers/render_system.h>
00043 #include <OGRE/OgreRenderSystem.h>
00044 
00045 #include <algorithm>
00046 #include <boost/lambda/lambda.hpp>
00047 
00048 namespace jsk_rviz_plugins
00049 {
00050   PeoplePositionMeasurementArrayDisplay::PeoplePositionMeasurementArrayDisplay()
00051   {
00052     size_property_ = new rviz::FloatProperty("size", 0.3,
00053                                              "size of the visualizer", this,
00054                                              SLOT(updateSize()));
00055     timeout_property_ = new rviz::FloatProperty(
00056       "timeout", 10.0, "timeout seconds", this, SLOT(updateTimeout()));
00057     anonymous_property_ = new rviz::BoolProperty(
00058       "anonymous", false,
00059       "anonymous",
00060       this, SLOT(updateAnonymous()));
00061     text_property_ = new rviz::StringProperty(
00062       "text", "person found here person found here",
00063       "text to rotate",
00064       this, SLOT(updateText()));
00065   }
00066 
00067   
00068   PeoplePositionMeasurementArrayDisplay::~PeoplePositionMeasurementArrayDisplay()
00069   {
00070     delete size_property_;
00071   }
00072 
00073   void PeoplePositionMeasurementArrayDisplay::onInitialize()
00074   {
00075     MFDClass::onInitialize();
00076     scene_node_ = scene_manager_->getRootSceneNode()->createChildSceneNode();
00077     updateSize();
00078     updateTimeout();
00079     updateAnonymous();
00080     updateText();
00081   }
00082 
00083   void PeoplePositionMeasurementArrayDisplay::clearObjects()
00084   {
00085     faces_.clear();
00086     visualizers_.clear();
00087   }
00088   
00089   void PeoplePositionMeasurementArrayDisplay::reset()
00090   {
00091     MFDClass::reset();
00092     clearObjects();
00093   }
00094 
00095   void PeoplePositionMeasurementArrayDisplay::processMessage(
00096     const people_msgs::PositionMeasurementArray::ConstPtr& msg)
00097   {
00098     boost::mutex::scoped_lock lock(mutex_);
00099     static int count = 0;
00100     static int square_count = 0;
00101     faces_ = msg->people;
00102     
00103     if (faces_.size() > visualizers_.size()) {
00104       for (size_t i = visualizers_.size(); i < faces_.size(); i++) {
00105         visualizers_.push_back(GISCircleVisualizer::Ptr(new GISCircleVisualizer(
00106                                                           scene_manager_,
00107                                                           scene_node_,
00108                                                           size_,
00109                                                           text_)));
00110         visualizers_[visualizers_.size() - 1]->setAnonymous(anonymous_);
00111         visualizers_[visualizers_.size() - 1]->update(0, 0);
00112         QColor color(25.0, 255.0, 240.0);
00113         visualizers_[visualizers_.size() - 1]->setColor(color);
00114       }
00115     }
00116     else {
00117       visualizers_.resize(faces_.size());
00118     }
00119     
00120     for (size_t i = 0; i < faces_.size(); i++) {
00121       Ogre::Quaternion orientation;
00122       Ogre::Vector3 position;
00123       geometry_msgs::Pose pose;
00124       pose.position = faces_[i].pos;
00125       pose.orientation.w = 1.0;
00126       if(!context_->getFrameManager()->transform(msg->header,
00127                                                  pose,
00128                                                  position, orientation))
00129       {
00130         std::ostringstream oss;
00131         oss << "Error transforming pose";
00132         oss << " from frame '" << msg->header.frame_id << "'";
00133         oss << " to frame '" << qPrintable(fixed_frame_) << "'";
00134         ROS_ERROR_STREAM(oss.str());
00135         setStatus(rviz::StatusProperty::Error, "Transform", QString::fromStdString(oss.str()));
00136       }
00137       else {
00138         visualizers_[i]->setPosition(position);
00139       }
00140     }
00141     latest_time_ = msg->header.stamp;
00142   }
00143 
00144   void PeoplePositionMeasurementArrayDisplay::update(
00145     float wall_dt, float ros_dt)
00146   {
00147     boost::mutex::scoped_lock lock(mutex_);
00148     if (faces_.size() == 0) {
00149       return;
00150     }
00151     if ((ros::Time::now() - latest_time_).toSec() > timeout_) {
00152       ROS_WARN("timeout face recognition result");
00153       clearObjects();
00154       return;
00155     }
00156     for (size_t i = 0; i < visualizers_.size(); i++) {
00157       visualizers_[i]->setOrientation(context_);
00158     }
00159     for (size_t i = 0; i < visualizers_.size(); i++) {
00160       visualizers_[i]->update(wall_dt, ros_dt);
00161     }
00162   }
00163 
00164   void PeoplePositionMeasurementArrayDisplay::updateTimeout()
00165   {
00166     boost::mutex::scoped_lock lock(mutex_);
00167     timeout_ = timeout_property_->getFloat();
00168   }
00169   
00170   void PeoplePositionMeasurementArrayDisplay::updateSize()
00171   {
00172     boost::mutex::scoped_lock lock(mutex_);
00173     size_ = size_property_->getFloat();
00174     visualizers_.clear();
00175   }
00176 
00177   void PeoplePositionMeasurementArrayDisplay::updateAnonymous()
00178   {
00179     boost::mutex::scoped_lock lock(mutex_);
00180     anonymous_ = anonymous_property_->getBool();
00181     for (size_t i = 0; i < visualizers_.size(); i++) {
00182       visualizers_[i]->setAnonymous(anonymous_);
00183     }
00184   }
00185 
00186   void PeoplePositionMeasurementArrayDisplay::updateText()
00187   {
00188     boost::mutex::scoped_lock lock(mutex_);
00189     text_ = text_property_->getStdString();
00190     for (size_t i = 0; i < visualizers_.size(); i++) {
00191       visualizers_[i]->setText(text_);
00192     }
00193   }
00194   
00195 }
00196 
00197 
00198 #include <pluginlib/class_list_macros.h>
00199 PLUGINLIB_EXPORT_CLASS( jsk_rviz_plugins::PeoplePositionMeasurementArrayDisplay, rviz::Display )
00200