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 
29 
31 
32 namespace rtabmap_rviz_plugins
33 {
34 
36  : spinner_(1, &cbqueue_),
37  globalCount_(0),
38  localCount_(0)
39 {
41 }
42 
44 {
45  spinner_.stop();
46 }
47 
49 {
51 
52  this->setStatusStd(rviz::StatusProperty::Ok, "Info", "");
53  this->setStatusStd(rviz::StatusProperty::Ok, "Position (XYZ)", "");
54  this->setStatusStd(rviz::StatusProperty::Ok, "Orientation (RPY)", "");
55  this->setStatusStd(rviz::StatusProperty::Ok, "Loop closures", "0");
56  this->setStatusStd(rviz::StatusProperty::Ok, "Proximity detections", "0");
57 
58  spinner_.start();
59 }
60 
61 void InfoDisplay::processMessage( const rtabmap_msgs::InfoConstPtr& msg )
62 {
63  {
64  boost::mutex::scoped_lock lock(info_mutex_);
65  if(msg->loopClosureId)
66  {
67  info_ = QString("%1->%2").arg(msg->refId).arg(msg->loopClosureId);
68  globalCount_ += 1;
69  }
70  else if(msg->proximityDetectionId)
71  {
72  info_ = QString("%1->%2 [Proximity]").arg(msg->refId).arg(msg->proximityDetectionId);
73  localCount_ += 1;
74  }
75  else
76  {
77  info_ = "";
78  }
80 
83  statistics_ = stat.data();
84  }
85 
86 
87  this->emitTimeSignal(msg->header.stamp);
88 }
89 
90 void InfoDisplay::update( float wall_dt, float ros_dt )
91 {
92  {
93  boost::mutex::scoped_lock lock(info_mutex_);
94  this->setStatusStd(rviz::StatusProperty::Ok, "Info", tr("%1").arg(info_).toStdString());
96  {
97  this->setStatusStd(rviz::StatusProperty::Ok, "Position (XYZ)", "");
98  this->setStatusStd(rviz::StatusProperty::Ok, "Orientation (RPY)", "");
99  }
100  else
101  {
102  float x,y,z, roll,pitch,yaw;
104  this->setStatusStd(rviz::StatusProperty::Ok, "Position (XYZ)", tr("%1;%2;%3").arg(x).arg(y).arg(z).toStdString());
105  this->setStatusStd(rviz::StatusProperty::Ok, "Orientation (RPY)", tr("%1;%2;%3").arg(roll).arg(pitch).arg(yaw).toStdString());
106  }
107  this->setStatusStd(rviz::StatusProperty::Ok, "Loop closures", tr("%1").arg(globalCount_).toStdString());
108  this->setStatusStd(rviz::StatusProperty::Ok, "Proximity detections", tr("%1").arg(localCount_).toStdString());
109 
110  for(std::map<std::string, float>::const_iterator iter=statistics_.begin(); iter!=statistics_.end(); ++iter)
111  {
112  this->setStatus(rviz::StatusProperty::Ok, iter->first.c_str(), tr("%1").arg(iter->second));
113  }
114  }
115 }
116 
118 {
119  MFDClass::reset();
120  {
121  boost::mutex::scoped_lock lock(info_mutex_);
122  info_.clear();
123  globalCount_ = 0;
124  localCount_ = 0;
125  statistics_.clear();
126  }
127 }
128 
129 } // namespace rtabmap_rviz_plugins
130 
rtabmap_rviz_plugins::InfoDisplay::localCount_
int localCount_
Definition: InfoDisplay.h:63
rtabmap_conversions::transformFromGeometryMsg
rtabmap::Transform transformFromGeometryMsg(const geometry_msgs::Transform &msg)
rviz::MessageFilterDisplay::reset
void reset() override
rtabmap::Statistics
yaw
GLM_FUNC_DECL T yaw(detail::tquat< T, P > const &x)
rviz::Display::emitTimeSignal
void emitTimeSignal(ros::Time time)
rtabmap_rviz_plugins::InfoDisplay::cbqueue_
ros::CallbackQueue cbqueue_
Definition: InfoDisplay.h:59
ros::AsyncSpinner::start
void start()
rtabmap_rviz_plugins::InfoDisplay::spinner_
ros::AsyncSpinner spinner_
Definition: InfoDisplay.h:58
rtabmap_rviz_plugins::InfoDisplay::globalCount_
int globalCount_
Definition: InfoDisplay.h:62
rtabmap_rviz_plugins
Definition: InfoDisplay.h:37
y
Matrix3f y
rtabmap::Transform::isNull
bool isNull() const
rtabmap_rviz_plugins::InfoDisplay::statistics_
std::map< std::string, float > statistics_
Definition: InfoDisplay.h:64
rtabmap::Transform::getTranslationAndEulerAngles
void getTranslationAndEulerAngles(float &x, float &y, float &z, float &roll, float &pitch, float &yaw) const
rtabmap_rviz_plugins::InfoDisplay::info_
QString info_
Definition: InfoDisplay.h:61
rviz::Display
rtabmap_rviz_plugins::InfoDisplay::InfoDisplay
InfoDisplay()
Definition: InfoDisplay.cpp:35
rviz::Display::setStatus
virtual void setStatus(StatusProperty::Level level, const QString &name, const QString &text)
rtabmap::Statistics::data
const std::map< std::string, float > & data() const
PLUGINLIB_EXPORT_CLASS
#define PLUGINLIB_EXPORT_CLASS(class_type, base_class_type)
InfoDisplay.h
arg
rtabmap_rviz_plugins::InfoDisplay::info_mutex_
boost::mutex info_mutex_
Definition: InfoDisplay.h:66
rviz::StatusProperty::Ok
Ok
rtabmap_conversions::infoFromROS
void infoFromROS(const rtabmap_msgs::Info &info, rtabmap::Statistics &stat)
z
z
x
x
rtabmap_rviz_plugins::InfoDisplay::loopTransform_
rtabmap::Transform loopTransform_
Definition: InfoDisplay.h:65
pitch
GLM_FUNC_DECL T pitch(detail::tquat< T, P > const &x)
ros::NodeHandle::setCallbackQueue
void setCallbackQueue(CallbackQueueInterface *queue)
ros::AsyncSpinner::stop
void stop()
rviz::MessageFilterDisplay::onInitialize
void onInitialize() override
rviz::Display::setStatusStd
void setStatusStd(StatusProperty::Level level, const std::string &name, const std::string &text)
iter
iterator iter(handle obj)
rtabmap_rviz_plugins::InfoDisplay::update
virtual void update(float wall_dt, float ros_dt)
Definition: InfoDisplay.cpp:90
class_list_macros.hpp
rtabmap_rviz_plugins::InfoDisplay::processMessage
virtual void processMessage(const rtabmap_msgs::InfoConstPtr &cloud)
Process a single message. Overridden from MessageFilterDisplay.
Definition: InfoDisplay.cpp:61
rtabmap_rviz_plugins::InfoDisplay
Definition: InfoDisplay.h:40
rtabmap_rviz_plugins::InfoDisplay::~InfoDisplay
virtual ~InfoDisplay()
Definition: InfoDisplay.cpp:43
MsgConversion.h
rtabmap_rviz_plugins::InfoDisplay::onInitialize
virtual void onInitialize()
Do initialization. Overridden from MessageFilterDisplay.
Definition: InfoDisplay.cpp:48
rviz::Display::update_nh_
ros::NodeHandle update_nh_
roll
GLM_FUNC_DECL T roll(detail::tquat< T, P > const &x)
rtabmap_rviz_plugins::InfoDisplay::reset
virtual void reset()
Definition: InfoDisplay.cpp:117
msg
msg


rtabmap_rviz_plugins
Author(s): Mathieu Labbe
autogenerated on Mon Apr 28 2025 02:37:14