--- tools/rosbag/src/recorder.cpp 2011-09-02 13:55:20.000000000 -0400 +++ tools/rosbag/src/recorder.cpp 2013-10-21 14:22:48.000000000 -0400 @@ -437,5 +437,11 @@ } boost::xtime xt; - boost::xtime_get(&xt, boost::TIME_UTC); + boost::xtime_get(&xt, boost:: +#if BOOST_VERSION <= 105200 + TIME_UTC_ +#else + TIME_UTC +#endif + ); xt.nsec += 250000000; queue_condition_.timed_wait(lock, xt);