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, "Loop closures", "0");
00055 this->setStatusStd(rviz::StatusProperty::Ok, "Proximity detections", "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").arg(msg->refId).arg(msg->loopClosureId);
00067 globalCount_ += 1;
00068 }
00069 else if(msg->proximityDetectionId)
00070 {
00071 info_ = QString("%1->%2 [Proximity]").arg(msg->refId).arg(msg->proximityDetectionId);
00072 localCount_ += 1;
00073 }
00074 else
00075 {
00076 info_ = "";
00077 }
00078 loopTransform_ = rtabmap_ros::transformFromGeometryMsg(msg->loopClosureTransform);
00079
00080 rtabmap::Statistics stat;
00081 rtabmap_ros::infoFromROS(*msg, stat);
00082 statistics_ = stat.data();
00083 }
00084
00085
00086 this->emitTimeSignal(msg->header.stamp);
00087 }
00088
00089 void InfoDisplay::update( float wall_dt, float ros_dt )
00090 {
00091 {
00092 boost::mutex::scoped_lock lock(info_mutex_);
00093 this->setStatusStd(rviz::StatusProperty::Ok, "Info", tr("%1").arg(info_).toStdString());
00094 if(loopTransform_.isNull())
00095 {
00096 this->setStatusStd(rviz::StatusProperty::Ok, "Position (XYZ)", "");
00097 this->setStatusStd(rviz::StatusProperty::Ok, "Orientation (RPY)", "");
00098 }
00099 else
00100 {
00101 float x,y,z, roll,pitch,yaw;
00102 loopTransform_.getTranslationAndEulerAngles(x,y,z, roll,pitch,yaw);
00103 this->setStatusStd(rviz::StatusProperty::Ok, "Position (XYZ)", tr("%1;%2;%3").arg(x).arg(y).arg(z).toStdString());
00104 this->setStatusStd(rviz::StatusProperty::Ok, "Orientation (RPY)", tr("%1;%2;%3").arg(roll).arg(pitch).arg(yaw).toStdString());
00105 }
00106 this->setStatusStd(rviz::StatusProperty::Ok, "Loop closures", tr("%1").arg(globalCount_).toStdString());
00107 this->setStatusStd(rviz::StatusProperty::Ok, "Proximity detections", tr("%1").arg(localCount_).toStdString());
00108
00109 for(std::map<std::string, float>::const_iterator iter=statistics_.begin(); iter!=statistics_.end(); ++iter)
00110 {
00111 this->setStatus(rviz::StatusProperty::Ok, iter->first.c_str(), tr("%1").arg(iter->second));
00112 }
00113 }
00114 }
00115
00116 void InfoDisplay::reset()
00117 {
00118 MFDClass::reset();
00119 {
00120 boost::mutex::scoped_lock lock(info_mutex_);
00121 info_.clear();
00122 globalCount_ = 0;
00123 localCount_ = 0;
00124 statistics_.clear();
00125 }
00126 }
00127
00128 }
00129
00130 #include <pluginlib/class_list_macros.h>
00131 PLUGINLIB_EXPORT_CLASS( rtabmap_ros::InfoDisplay, rviz::Display )