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 #include "InfoDisplay.h"
00029 #include "rtabmap_ros/MsgConversion.h"
00030
00031 namespace rtabmap_ros
00032 {
00033
00034 InfoDisplay::InfoDisplay()
00035 : spinner_(1, &cbqueue_),
00036 globalCount_(0),
00037 localCount_(0)
00038 {
00039 update_nh_.setCallbackQueue( &cbqueue_ );
00040 }
00041
00042 InfoDisplay::~InfoDisplay()
00043 {
00044 spinner_.stop();
00045 }
00046
00047 void InfoDisplay::onInitialize()
00048 {
00049 MFDClass::onInitialize();
00050
00051 this->setStatusStd(rviz::StatusProperty::Ok, "Info", "");
00052 this->setStatusStd(rviz::StatusProperty::Ok, "Position (XYZ)", "");
00053 this->setStatusStd(rviz::StatusProperty::Ok, "Orientation (RPY)", "");
00054 this->setStatusStd(rviz::StatusProperty::Ok, "Global", "0");
00055 this->setStatusStd(rviz::StatusProperty::Ok, "Local", "0");
00056
00057 spinner_.start();
00058 }
00059
00060 void InfoDisplay::processMessage( const rtabmap_ros::InfoConstPtr& msg )
00061 {
00062 {
00063 boost::mutex::scoped_lock lock(info_mutex_);
00064 if(msg->loopClosureId)
00065 {
00066 info_ = QString("%1->%2 [Global]").arg(msg->refId).arg(msg->loopClosureId);
00067 globalCount_ += 1;
00068 }
00069 else if(msg->localLoopClosureId)
00070 {
00071 info_ = QString("%1->%2 [Local]").arg(msg->refId).arg(msg->localLoopClosureId);
00072 localCount_ += 1;
00073 }
00074 else
00075 {
00076 info_ = "";
00077 }
00078 loopTransform_ = rtabmap_ros::transformFromGeometryMsg(msg->loopClosureTransform);
00079 }
00080
00081 this->emitTimeSignal(msg->header.stamp);
00082 }
00083
00084 void InfoDisplay::update( float wall_dt, float ros_dt )
00085 {
00086 {
00087 boost::mutex::scoped_lock lock(info_mutex_);
00088 this->setStatusStd(rviz::StatusProperty::Ok, "Info", tr("%1").arg(info_).toStdString());
00089 if(loopTransform_.isNull())
00090 {
00091 this->setStatusStd(rviz::StatusProperty::Ok, "Position (XYZ)", "");
00092 this->setStatusStd(rviz::StatusProperty::Ok, "Orientation (RPY)", "");
00093 }
00094 else
00095 {
00096 float x,y,z, roll,pitch,yaw;
00097 loopTransform_.getTranslationAndEulerAngles(x,y,z, roll,pitch,yaw);
00098 this->setStatusStd(rviz::StatusProperty::Ok, "Position (XYZ)", tr("%1;%2;%3").arg(x).arg(y).arg(z).toStdString());
00099 this->setStatusStd(rviz::StatusProperty::Ok, "Orientation (RPY)", tr("%1;%2;%3").arg(roll).arg(pitch).arg(yaw).toStdString());
00100 }
00101 this->setStatusStd(rviz::StatusProperty::Ok, "Global", tr("%1").arg(globalCount_).toStdString());
00102 this->setStatusStd(rviz::StatusProperty::Ok, "Local", tr("%1").arg(localCount_).toStdString());
00103 }
00104 }
00105
00106 void InfoDisplay::reset()
00107 {
00108 MFDClass::reset();
00109 {
00110 boost::mutex::scoped_lock lock(info_mutex_);
00111 info_.clear();
00112 globalCount_ = 0;
00113 localCount_ = 0;
00114 }
00115 }
00116
00117 }
00118
00119 #include <pluginlib/class_list_macros.h>
00120 PLUGINLIB_EXPORT_CLASS( rtabmap_ros::InfoDisplay, rviz::Display )