35 : spinner_(1, &cbqueue_),
64 if(msg->loopClosureId)
66 info_ = QString(
"%1->%2").arg(msg->refId).arg(msg->loopClosureId);
69 else if(msg->proximityDetectionId)
71 info_ = QString(
"%1->%2 [Proximity]").arg(msg->refId).arg(msg->proximityDetectionId);
109 for(std::map<std::string, float>::const_iterator iter=
statistics_.begin(); iter!=
statistics_.end(); ++iter)
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.
ros::CallbackQueue cbqueue_
void emitTimeSignal(ros::Time time)
ros::NodeHandle update_nh_
virtual void update(float wall_dt, float ros_dt)
GLM_FUNC_DECL T pitch(detail::tquat< T, P > const &x)
virtual void onInitialize()
Do initialization. Overridden from MessageFilterDisplay.
const std::map< std::string, float > & data() const
std::map< std::string, float > statistics_
void setCallbackQueue(CallbackQueueInterface *queue)
void infoFromROS(const rtabmap_ros::Info &info, rtabmap::Statistics &stat)
rtabmap::Transform loopTransform_
ros::AsyncSpinner spinner_
void onInitialize() override
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)