Go to the documentation of this file.
36 : spinner_(1, &cbqueue_),
65 if(
msg->loopClosureId)
67 info_ = QString(
"%1->%2").arg(
msg->refId).arg(
msg->loopClosureId);
70 else if(
msg->proximityDetectionId)
72 info_ = QString(
"%1->%2 [Proximity]").arg(
msg->refId).arg(
msg->proximityDetectionId);
rtabmap::Transform transformFromGeometryMsg(const geometry_msgs::Transform &msg)
GLM_FUNC_DECL T yaw(detail::tquat< T, P > const &x)
void emitTimeSignal(ros::Time time)
ros::CallbackQueue cbqueue_
ros::AsyncSpinner spinner_
std::map< std::string, float > statistics_
virtual void setStatus(StatusProperty::Level level, const QString &name, const QString &text)
const std::map< std::string, float > & data() const
#define PLUGINLIB_EXPORT_CLASS(class_type, base_class_type)
void infoFromROS(const rtabmap_msgs::Info &info, rtabmap::Statistics &stat)
rtabmap::Transform loopTransform_
GLM_FUNC_DECL T pitch(detail::tquat< T, P > const &x)
void setCallbackQueue(CallbackQueueInterface *queue)
void onInitialize() override
void setStatusStd(StatusProperty::Level level, const std::string &name, const std::string &text)
iterator iter(handle obj)
virtual void update(float wall_dt, float ros_dt)
virtual void processMessage(const rtabmap_msgs::InfoConstPtr &cloud)
Process a single message. Overridden from MessageFilterDisplay.
virtual void onInitialize()
Do initialization. Overridden from MessageFilterDisplay.
ros::NodeHandle update_nh_
GLM_FUNC_DECL T roll(detail::tquat< T, P > const &x)