diff --git a/LaserPublisher.cpp b/LaserPublisher.cpp index 6a9606a63ced8e20a04f0e8ad9f141f82494787d..ab6f277ebeba25cd6466234e1efc917595f4316a 100644 --- a/LaserPublisher.cpp +++ b/LaserPublisher.cpp @@ -52,6 +52,8 @@ LaserPublisher::LaserPublisher(ArLaser *_l, ros::NodeHandle& _n, bool _broadcast laserscan.range_min = 0; //laser->getMinRange() / 1000.0; laserscan.range_max = laser->getMaxRange() / 1000.0; pointcloud.header.frame_id = globaltfname; + + readingsCallbackTime = new ArTime; } LaserPublisher::~LaserPublisher() @@ -59,10 +61,12 @@ LaserPublisher::~LaserPublisher() laser->lockDevice(); laser->remReadingCB(&laserReadingsCB); laser->unlockDevice(); + delete readingsCallbackTime; } void LaserPublisher::readingsCB() { + printf("readingsCB(): %lu ms since last readingsCB() call.\n", readingsCallbackTime->mSecSince()); assert(laser); laser->lockDevice(); publishLaserScan(); @@ -70,6 +74,7 @@ void LaserPublisher::readingsCB() laser->unlockDevice(); if(broadcast_tf) transform_broadcaster.sendTransform(tf::StampedTransform(lasertf, convertArTimeToROS(laser->getLastReadingTime()), parenttfname, tfname)); + readingsCallbackTime->setToNow(); } void LaserPublisher::publishLaserScan() diff --git a/LaserPublisher.h b/LaserPublisher.h index fdec9d701e0bac04ffb0bbcbffe37259b1d0e016..bd9f0fdee48afb0c2af10a9ffd988bdd9ef9f1d0 100644 --- a/LaserPublisher.h +++ b/LaserPublisher.h @@ -6,6 +6,9 @@ #include <sensor_msgs/PointCloud.h> #include <tf/transform_broadcaster.h> +class ArLaser; +class ArTime; + class LaserPublisher { public: @@ -28,6 +31,8 @@ protected: tf::Transform lasertf; tf::TransformBroadcaster transform_broadcaster; bool broadcast_tf; + + ArTime *readingsCallbackTime; }; #endif