ros2 / message_filters

BSD 3-Clause "New" or "Revised" License
76 stars 66 forks source link

`rclcpp::Time` source difference causing crash using `ApproximateEpsilonTime` #117

Closed russkel closed 5 months ago

russkel commented 7 months ago
terminate called after throwing an instance of 'std::runtime_error'
  what():  can't compare times with different time sources

Offending line is:

https://github.com/ros2/message_filters/blob/541d8a5009b14aaae4d9fe52e101273e428bb5d0/include/message_filters/sync_policies/approximate_epsilon_time.h#L142

142    if (current.first > candidate) {
gef➤  p current.first
$1 = {
  _vptr.Time = 0x7ffff7efa928 <vtable for rclcpp::Time+16>,
  rcl_time_ = {
    nanoseconds = 0x7fffffffffffffff,
    clock_type = RCL_ROS_TIME
  }
}
gef➤  p candidate
$2 = {
  _vptr.Time = 0x7ffff7efa928 <vtable for rclcpp::Time+16>,
  rcl_time_ = {
    nanoseconds = 0x0,
    clock_type = RCL_SYSTEM_TIME
  }
}
gef➤  
russkel commented 7 months ago

Looks like https://github.com/ros2/message_filters/blob/541d8a5009b14aaae4d9fe52e101273e428bb5d0/include/message_filters/message_traits.h#L88

needs to specify RCL_ROS_TIME.