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