InfoDisplay.cpp
Go to the documentation of this file.
1 /*
2 Copyright (c) 2010-2016, Mathieu Labbe - IntRoLab - Universite de Sherbrooke
3 All rights reserved.
4 
5 Redistribution and use in source and binary forms, with or without
6 modification, are permitted provided that the following conditions are met:
7  * Redistributions of source code must retain the above copyright
8  notice, this list of conditions and the following disclaimer.
9  * Redistributions in binary form must reproduce the above copyright
10  notice, this list of conditions and the following disclaimer in the
11  documentation and/or other materials provided with the distribution.
12  * Neither the name of the Universite de Sherbrooke nor the
13  names of its contributors may be used to endorse or promote products
14  derived from this software without specific prior written permission.
15 
16 THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
17 ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
18 WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
19 DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY
20 DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
21 (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
22 LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
23 ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
24 (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
25 SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
26 */
27 
28 #include "InfoDisplay.h"
30 
31 namespace rtabmap_ros
32 {
33 
35  : spinner_(1, &cbqueue_),
36  globalCount_(0),
37  localCount_(0)
38 {
40 }
41 
43 {
44  spinner_.stop();
45 }
46 
48 {
50 
51  this->setStatusStd(rviz::StatusProperty::Ok, "Info", "");
52  this->setStatusStd(rviz::StatusProperty::Ok, "Position (XYZ)", "");
53  this->setStatusStd(rviz::StatusProperty::Ok, "Orientation (RPY)", "");
54  this->setStatusStd(rviz::StatusProperty::Ok, "Loop closures", "0");
55  this->setStatusStd(rviz::StatusProperty::Ok, "Proximity detections", "0");
56 
57  spinner_.start();
58 }
59 
60 void InfoDisplay::processMessage( const rtabmap_ros::InfoConstPtr& msg )
61 {
62  {
63  boost::mutex::scoped_lock lock(info_mutex_);
64  if(msg->loopClosureId)
65  {
66  info_ = QString("%1->%2").arg(msg->refId).arg(msg->loopClosureId);
67  globalCount_ += 1;
68  }
69  else if(msg->proximityDetectionId)
70  {
71  info_ = QString("%1->%2 [Proximity]").arg(msg->refId).arg(msg->proximityDetectionId);
72  localCount_ += 1;
73  }
74  else
75  {
76  info_ = "";
77  }
78  loopTransform_ = rtabmap_ros::transformFromGeometryMsg(msg->loopClosureTransform);
79 
81  rtabmap_ros::infoFromROS(*msg, stat);
82  statistics_ = stat.data();
83  }
84 
85 
86  this->emitTimeSignal(msg->header.stamp);
87 }
88 
89 void InfoDisplay::update( float wall_dt, float ros_dt )
90 {
91  {
92  boost::mutex::scoped_lock lock(info_mutex_);
93  this->setStatusStd(rviz::StatusProperty::Ok, "Info", tr("%1").arg(info_).toStdString());
95  {
96  this->setStatusStd(rviz::StatusProperty::Ok, "Position (XYZ)", "");
97  this->setStatusStd(rviz::StatusProperty::Ok, "Orientation (RPY)", "");
98  }
99  else
100  {
101  float x,y,z, roll,pitch,yaw;
102  loopTransform_.getTranslationAndEulerAngles(x,y,z, roll,pitch,yaw);
103  this->setStatusStd(rviz::StatusProperty::Ok, "Position (XYZ)", tr("%1;%2;%3").arg(x).arg(y).arg(z).toStdString());
104  this->setStatusStd(rviz::StatusProperty::Ok, "Orientation (RPY)", tr("%1;%2;%3").arg(roll).arg(pitch).arg(yaw).toStdString());
105  }
106  this->setStatusStd(rviz::StatusProperty::Ok, "Loop closures", tr("%1").arg(globalCount_).toStdString());
107  this->setStatusStd(rviz::StatusProperty::Ok, "Proximity detections", tr("%1").arg(localCount_).toStdString());
108 
109  for(std::map<std::string, float>::const_iterator iter=statistics_.begin(); iter!=statistics_.end(); ++iter)
110  {
111  this->setStatus(rviz::StatusProperty::Ok, iter->first.c_str(), tr("%1").arg(iter->second));
112  }
113  }
114 }
115 
117 {
118  MFDClass::reset();
119  {
120  boost::mutex::scoped_lock lock(info_mutex_);
121  info_.clear();
122  globalCount_ = 0;
123  localCount_ = 0;
124  statistics_.clear();
125  }
126 }
127 
128 } // namespace rtabmap_ros
129 
GLM_FUNC_DECL T roll(detail::tquat< T, P > const &x)
void setStatusStd(StatusProperty::Level level, const std::string &name, const std::string &text)
virtual void processMessage(const rtabmap_ros::InfoConstPtr &cloud)
Process a single message. Overridden from MessageFilterDisplay.
Definition: InfoDisplay.cpp:60
x
ros::CallbackQueue cbqueue_
Definition: InfoDisplay.h:59
void emitTimeSignal(ros::Time time)
ros::NodeHandle update_nh_
virtual void update(float wall_dt, float ros_dt)
Definition: InfoDisplay.cpp:89
GLM_FUNC_DECL T pitch(detail::tquat< T, P > const &x)
void getTranslationAndEulerAngles(float &x, float &y, float &z, float &roll, float &pitch, float &yaw) const
virtual void onInitialize()
Do initialization. Overridden from MessageFilterDisplay.
Definition: InfoDisplay.cpp:47
const std::map< std::string, float > & data() const
std::map< std::string, float > statistics_
Definition: InfoDisplay.h:64
void setCallbackQueue(CallbackQueueInterface *queue)
void infoFromROS(const rtabmap_ros::Info &info, rtabmap::Statistics &stat)
bool isNull() const
rtabmap::Transform loopTransform_
Definition: InfoDisplay.h:65
ros::AsyncSpinner spinner_
Definition: InfoDisplay.h:58
GLM_FUNC_DECL T yaw(detail::tquat< T, P > const &x)
PLUGINLIB_EXPORT_CLASS(rtabmap_ros::CoreWrapper, nodelet::Nodelet)
rtabmap::Transform transformFromGeometryMsg(const geometry_msgs::Transform &msg)
virtual void setStatus(StatusProperty::Level level, const QString &name, const QString &text)
boost::mutex info_mutex_
Definition: InfoDisplay.h:66


rtabmap_ros
Author(s): Mathieu Labbe
autogenerated on Tue Jan 24 2023 04:04:40