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 <boost/format.hpp>
00037 #include "tf_trajectory_display.h"
00038 
00039 namespace jsk_rviz_plugins
00040 {
00041   TFTrajectoryDisplay::TFTrajectoryDisplay()
00042     : Display()
00043   {
00044     frame_property_ = new rviz::TfFrameProperty("frame", "",
00045                                                 "frame to visualize trajectory",
00046                                                 this,
00047                                                 NULL,
00048                                                 false,
00049                                                 SLOT(updateFrame()));
00050     duration_property_ = new rviz::FloatProperty("duration", 10.0,
00051                                                  "duration to visualize trajectory",
00052                                                  this, SLOT(updateDuration()));
00053     line_width_property_ = new rviz::FloatProperty("line_width", 0.01,
00054                                                    "line width",
00055                                                    this, SLOT(updateLineWidth()));
00056     color_property_ = new rviz::ColorProperty("color", QColor(25, 255, 240),
00057                                               "color of trajectory",
00058                                               this, SLOT(updateColor()));
00059     duration_property_->setMin(0.0);
00060     line_width_property_->setMin(0.0);
00061   }
00062 
00063   TFTrajectoryDisplay::~TFTrajectoryDisplay()
00064   {
00065     delete line_width_property_;
00066     delete frame_property_;
00067     delete duration_property_;
00068     delete color_property_;
00069     delete line_;
00070   }
00071 
00072   void TFTrajectoryDisplay::onInitialize()
00073   {
00074     frame_property_->setFrameManager( context_->getFrameManager() );
00075     line_ = new rviz::BillboardLine(context_->getSceneManager(), scene_node_);
00076     updateFrame();
00077     updateDuration();
00078     updateColor();
00079     updateLineWidth();
00080   }
00081 
00082   void TFTrajectoryDisplay::updateFrame()
00083   {
00084     frame_ = frame_property_->getFrame().toStdString();
00085     trajectory_.clear();
00086   }
00087 
00088   void TFTrajectoryDisplay::updateDuration()
00089   {
00090     duration_ = duration_property_->getFloat();
00091   }
00092 
00093   void TFTrajectoryDisplay::updateColor()
00094   {
00095     color_ = color_property_->getColor();
00096   }
00097 
00098   void TFTrajectoryDisplay::onEnable()
00099   {
00100     line_->clear();
00101     trajectory_.clear();
00102   }
00103 
00104   void TFTrajectoryDisplay::updateLineWidth()
00105   {
00106     line_width_ = line_width_property_->getFloat();
00107   }
00108 
00109   void TFTrajectoryDisplay::onDisable()
00110   {
00111     line_->clear();
00112     trajectory_.clear();
00113   }
00114 
00115   void TFTrajectoryDisplay::update(float wall_dt, float ros_dt)
00116   {
00117     if (frame_.empty()) {
00118       return;
00119     }
00120     std::string fixed_frame_id = context_->getFrameManager()->getFixedFrame();
00121     if (fixed_frame_ != fixed_frame_id) {
00122       fixed_frame_ = fixed_frame_id;
00123       line_->clear();
00124       trajectory_.clear();
00125       return;
00126     }
00127     fixed_frame_ = fixed_frame_id;
00128     ros::Time now = context_->getFrameManager()->getTime();
00129     std_msgs::Header header;
00130     header.stamp = ros::Time(0.0);
00131     header.frame_id = frame_;
00132     Ogre::Vector3 position;
00133     Ogre::Quaternion orientation;
00134     if(!context_->getFrameManager()->getTransform(
00135          header, position, orientation)) {
00136       setStatus(rviz::StatusProperty::Error, "transformation",
00137                 (boost::format("Failed transforming from frame '%s' to frame '%s'")
00138                  % header.frame_id.c_str() % fixed_frame_id.c_str()).str().c_str());
00139       return;
00140     }
00141     setStatus(rviz::StatusProperty::Ok, "transformation", "Ok");
00142     geometry_msgs::PointStamped new_point;
00143     new_point.header.stamp = now;
00144     new_point.point.x = position[0];
00145     new_point.point.y = position[1];
00146     new_point.point.z = position[2];
00147     trajectory_.push_back(new_point);
00148     
00149     for (std::vector<geometry_msgs::PointStamped>::iterator it = trajectory_.begin();
00150          it != trajectory_.end();) {
00151       ros::Duration duration = now - it->header.stamp;
00152       if (duration.toSec() > duration_) {
00153         it = trajectory_.erase(it);
00154       }
00155       else {
00156         break;
00157       }
00158     }
00159     line_->clear();
00160     line_->setNumLines(1);
00161     line_->setMaxPointsPerLine(trajectory_.size());
00162     line_->setLineWidth(line_width_);
00163     line_->setColor(color_.red() * 255.0, color_.green() * 255.0, color_.blue() * 255.0, 255.0);
00164     for (size_t i = 0; i < trajectory_.size(); i++) {
00165       Ogre::Vector3 p;
00166       p[0] = trajectory_[i].point.x;
00167       p[1] = trajectory_[i].point.y;
00168       p[2] = trajectory_[i].point.z;
00169       line_->addPoint(p);
00170     }
00171   }
00172 }
00173 
00174 #include <pluginlib/class_list_macros.h>
00175 PLUGINLIB_EXPORT_CLASS( jsk_rviz_plugins::TFTrajectoryDisplay, rviz::Display )