Skip to content

Commit

Permalink
Added timing messages to map maker
Browse files Browse the repository at this point in the history
  • Loading branch information
aharmat committed Dec 16, 2014
1 parent 32aea9a commit 28a48de
Show file tree
Hide file tree
Showing 8 changed files with 59 additions and 4 deletions.
2 changes: 1 addition & 1 deletion CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -28,7 +28,7 @@ link_directories(${catkin_LIBRARY_DIRS} ${Boost_LIBRARY_DIRS} ${SUITESPARSE_LIBR

add_message_files(
DIRECTORY msg
FILES MapInfo.msg NetworkMapPoint.msg NetworkMeasurement.msg NetworkKeyFrame.msg NetworkMultiKeyFrame.msg NetworkOutlier.msg
FILES MapInfo.msg MapMakerTiming.msg NetworkMapPoint.msg NetworkMeasurement.msg NetworkKeyFrame.msg NetworkMultiKeyFrame.msg NetworkOutlier.msg
SystemInfo.msg TrackerTiming.msg TrackerState.msg
)

Expand Down
4 changes: 4 additions & 0 deletions include/mcptam/MapMaker.h
Original file line number Diff line number Diff line change
Expand Up @@ -137,6 +137,10 @@ class MapMaker : public MapMakerClientBase, public MapMakerServerBase, protected
//testing
bool mbStopInit; ///< End of initialization phase requested

ros::Publisher mCreationTimingPub;
ros::Publisher mLocalTimingPub;
ros::Publisher mGlobalTimingPub;

};

#endif
Expand Down
4 changes: 4 additions & 0 deletions msg/MapMakerTiming.msg
Original file line number Diff line number Diff line change
@@ -0,0 +1,4 @@
Header header
float32 elapsed
int32 map_num_mkfs
int32 map_num_points
2 changes: 2 additions & 0 deletions msg/TrackerTiming.msg
Original file line number Diff line number Diff line change
Expand Up @@ -12,3 +12,5 @@ float32 pose
float32 depth
float32 add
float32 total
int32 map_num_mkfs
int32 map_num_points
43 changes: 43 additions & 0 deletions src/MapMaker.cc
Original file line number Diff line number Diff line change
Expand Up @@ -43,12 +43,17 @@
#include <mcptam/SmallBlurryImage.h>
#include <mcptam/Map.h>
#include <mcptam/BundleAdjusterBase.h>
#include <mcptam/MapMakerTiming.h>

MapMaker::MapMaker(Map &map, TaylorCameraMap &cameras, BundleAdjusterBase &bundleAdjuster)
: MapMakerBase(map, true)
, MapMakerClientBase(map)
, MapMakerServerBase(map, cameras, bundleAdjuster)
{
mCreationTimingPub = mNodeHandlePriv.advertise<mcptam::MapMakerTiming>("timing_mkf_creation", 1, true);
mLocalTimingPub = mNodeHandlePriv.advertise<mcptam::MapMakerTiming>("timing_local_ba", 1,true);
mGlobalTimingPub = mNodeHandlePriv.advertise<mcptam::MapMakerTiming>("timing_global_ba", 1,true);

Reset();
start();
}
Expand Down Expand Up @@ -189,9 +194,19 @@ void MapMaker::run()
mBundleAdjuster.UseTukey((mState == MM_RUNNING && mMap.mlpMultiKeyFrames.size() > 2));
mBundleAdjuster.UseTwoStep((mState == MM_RUNNING && mMap.mlpMultiKeyFrames.size() > 2));

mcptam::MapMakerTiming timingMsg;
timingMsg.map_num_mkfs = mMap.mlpMultiKeyFrames.size();
timingMsg.map_num_points = mMap.mlpPoints.size();

ros::Time start = ros::Time::now();

int nAccepted = mBundleAdjuster.BundleAdjustRecent(vOutliers);
//mdMaxCov = mBundleAdjuster.GetMaxCov();

ros::Time nowTime = ros::Time::now();
timingMsg.elapsed = (nowTime - start).toSec();
timingMsg.header.stamp = nowTime;

ROS_DEBUG_STREAM("Accepted iterations: "<<nAccepted);
ROS_DEBUG_STREAM("Number of outliers: "<<vOutliers.size());
//ROS_DEBUG_STREAM("Max cov: "<<mdMaxCov);
Expand All @@ -210,6 +225,9 @@ void MapMaker::run()
mnNumConsecutiveFailedBA = 0;
HandleOutliers(vOutliers);
PublishMapVisualization();

timingMsg.elapsed /= nAccepted;
mLocalTimingPub.publish(timingMsg);
}
}

Expand All @@ -233,7 +251,18 @@ void MapMaker::run()
mBundleAdjuster.UseTukey(mState == MM_RUNNING && mMap.mlpMultiKeyFrames.size() > 2);
mBundleAdjuster.UseTwoStep((mState == MM_RUNNING && mMap.mlpMultiKeyFrames.size() > 2));

mcptam::MapMakerTiming timingMsg;
timingMsg.map_num_mkfs = mMap.mlpMultiKeyFrames.size();
timingMsg.map_num_points = mMap.mlpPoints.size();

ros::Time start = ros::Time::now();

int nAccepted = mBundleAdjuster.BundleAdjustAll(vOutliers);

ros::Time nowTime = ros::Time::now();
timingMsg.elapsed = (nowTime - start).toSec();
timingMsg.header.stamp = nowTime;

mdMaxCov = mBundleAdjuster.GetMaxCov();

ROS_DEBUG_STREAM("Accepted iterations: "<<nAccepted);
Expand All @@ -255,6 +284,9 @@ void MapMaker::run()
HandleOutliers(vOutliers);
PublishMapVisualization();

timingMsg.elapsed /= nAccepted;
mGlobalTimingPub.publish(timingMsg);

if(mState == MM_INITIALIZING && (mdMaxCov < MapMakerServerBase::sdInitCovThresh || mbStopInit))
{
ROS_INFO_STREAM("INITIALIZING, Max cov "<<mdMaxCov<<" below threshold "<<MapMakerServerBase::sdInitCovThresh<<", switching to MM_RUNNING");
Expand Down Expand Up @@ -401,6 +433,12 @@ void MapMaker::AddMultiKeyFrameFromTopOfQueue()
}
*/

mcptam::MapMakerTiming timingMsg;
timingMsg.map_num_mkfs = mMap.mlpMultiKeyFrames.size();
timingMsg.map_num_points = mMap.mlpPoints.size();

ros::Time start = ros::Time::now();

if(mState == MM_RUNNING)
{
if(pMKF->NoImages()) // leftovers from Tracker, don't bother adding these
Expand All @@ -427,6 +465,11 @@ void MapMaker::AddMultiKeyFrameFromTopOfQueue()
mMap.MoveDeletedMultiKeyFramesToTrash();
}

ros::Time nowTime = ros::Time::now();
timingMsg.elapsed = (nowTime - start).toSec();
timingMsg.header.stamp = nowTime;
mCreationTimingPub.publish(timingMsg);

lock.lock();
mqpMultiKeyFramesFromTracker.pop_front();
lock.unlock();
Expand Down
2 changes: 1 addition & 1 deletion src/MapMakerBase.cc
Original file line number Diff line number Diff line change
Expand Up @@ -369,7 +369,7 @@ void MapMakerBase::PublishMapPoints()
pointMsg->height = 1;
pointMsg->is_dense = false;

#if ROS_VERSION_MINIMUM(1, 9, 54) // Hydro or above, uses new PCL library
#if ROS_VERSION_MINIMUM(1, 9, 56) // Hydro or above, uses new PCL library
pointMsg->header.stamp = ros::Time::now().toNSec();
#else
pointMsg->header.stamp = ros::Time::now();
Expand Down
2 changes: 1 addition & 1 deletion src/SystemFrontendBase.cc
Original file line number Diff line number Diff line change
Expand Up @@ -331,7 +331,7 @@ void SystemFrontendBase::PublishSmallImage()
pointMsg->height = 1;
pointMsg->is_dense = false;

#if ROS_VERSION_MINIMUM(1, 9, 54) // Hydro or above, uses new PCL library
#if ROS_VERSION_MINIMUM(1, 9, 56) // Hydro or above, uses new PCL library
pointMsg->header.stamp = timestamp.toNSec();
#else
pointMsg->header.stamp = timestamp;
Expand Down
4 changes: 3 additions & 1 deletion src/Tracker.cc
Original file line number Diff line number Diff line change
Expand Up @@ -114,7 +114,7 @@ Tracker::Tracker(Map &map, MapMakerClientBase &mapmaker, TaylorCameraMap &camera
ROS_DEBUG("Tracker: In constructor, done");

maskPub = mNodeHandlePrivate.advertise<sensor_msgs::Image>("mask", 1);
timingPub = mNodeHandlePrivate.advertise<mcptam::TrackerTiming>("timing", 1);
timingPub = mNodeHandlePrivate.advertise<mcptam::TrackerTiming>("timing_tracker", 1);
}

Tracker::~Tracker()
Expand Down Expand Up @@ -511,6 +511,8 @@ void Tracker::TrackFrame(ImageBWMap& imFrames, ros::Time timestamp, bool bDraw)
}

timingMsg.total = (ros::WallTime::now() - startTimeTotal).toSec();
timingMsg.map_num_points = mMap.mlpPoints.size();
timingMsg.map_num_mkfs = mMap.mlpMultiKeyFrames.size();
timingMsg.header.stamp = ros::Time::now();
timingPub.publish(timingMsg);
}
Expand Down

0 comments on commit 28a48de

Please sign in to comment.