InfoDisplay.cpp
Go to the documentation of this file.
00001 /*
00002 Copyright (c) 2010-2014, Mathieu Labbe - IntRoLab - Universite de Sherbrooke
00003 All rights reserved.
00004 
00005 Redistribution and use in source and binary forms, with or without
00006 modification, are permitted provided that the following conditions are met:
00007     * Redistributions of source code must retain the above copyright
00008       notice, this list of conditions and the following disclaimer.
00009     * Redistributions in binary form must reproduce the above copyright
00010       notice, this list of conditions and the following disclaimer in the
00011       documentation and/or other materials provided with the distribution.
00012     * Neither the name of the Universite de Sherbrooke nor the
00013       names of its contributors may be used to endorse or promote products
00014       derived from this software without specific prior written permission.
00015 
00016 THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
00017 ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
00018 WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
00019 DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY
00020 DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
00021 (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00022 LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
00023 ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
00024 (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
00025 SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
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 } // namespace rtabmap_ros
00118 
00119 #include <pluginlib/class_list_macros.h>
00120 PLUGINLIB_EXPORT_CLASS( rtabmap_ros::InfoDisplay, rviz::Display )


rtabmap_ros
Author(s): Mathieu Labbe
autogenerated on Thu Aug 27 2015 15:00:24