@@ -63,6 +63,12 @@ ImuFilterMadgwickRos::ImuFilterMadgwickRos(const rclcpp::NodeOptions &options)
6363 declare_parameter (" publish_debug_topics" , false , descriptor);
6464 get_parameter (" publish_debug_topics" , publish_debug_topics_);
6565
66+ double time_jump_threshold = 0.0 ;
67+ declare_parameter (" time_jump_threshold" , 0.0 , descriptor);
68+ get_parameter (" time_jump_threshold" , time_jump_threshold);
69+ time_jump_threshold_duration_ =
70+ rclcpp::Duration::from_seconds (time_jump_threshold);
71+
6672 double yaw_offset = 0.0 ;
6773 declare_parameter (" yaw_offset" , 0.0 , descriptor);
6874 get_parameter (" yaw_offset" , yaw_offset);
@@ -130,6 +136,8 @@ ImuFilterMadgwickRos::ImuFilterMadgwickRos(const rclcpp::NodeOptions &options)
130136 " The gravity vector is kept in the IMU message." );
131137 }
132138
139+ last_ros_time_ = this ->get_clock ()->now ();
140+
133141 // **** define reconfigurable parameters.
134142 double gain;
135143 floating_point_range float_range = {0.0 , 1.0 , 0 };
@@ -226,6 +234,8 @@ ImuFilterMadgwickRos::ImuFilterMadgwickRos(const rclcpp::NodeOptions &options)
226234
227235void ImuFilterMadgwickRos::imuCallback (ImuMsg::ConstSharedPtr imu_msg_raw)
228236{
237+ checkTimeJump ();
238+
229239 std::lock_guard<std::mutex> lock (mutex_);
230240
231241 const geometry_msgs::msg::Vector3 &ang_vel = imu_msg_raw->angular_velocity ;
@@ -291,6 +301,8 @@ void ImuFilterMadgwickRos::imuCallback(ImuMsg::ConstSharedPtr imu_msg_raw)
291301void ImuFilterMadgwickRos::imuMagCallback (ImuMsg::ConstSharedPtr imu_msg_raw,
292302 MagMsg::ConstSharedPtr mag_msg)
293303{
304+ checkTimeJump ();
305+
294306 std::lock_guard<std::mutex> lock (mutex_);
295307
296308 const geometry_msgs::msg::Vector3 &ang_vel = imu_msg_raw->angular_velocity ;
@@ -582,6 +594,40 @@ void ImuFilterMadgwickRos::checkTopicsTimerCallback()
582594 << " ..." );
583595}
584596
597+ void ImuFilterMadgwickRos::checkTimeJump ()
598+ {
599+ const auto now = this ->get_clock ()->now ();
600+ if (last_ros_time_ == rclcpp::Time (0 , 0 , last_ros_time_.get_clock_type ()) ||
601+ last_ros_time_ <= now + time_jump_threshold_duration_)
602+ {
603+ last_ros_time_ = now;
604+ return ;
605+ }
606+
607+ RCLCPP_WARN (this ->get_logger (),
608+ " Detected jump back in time of %.1f s. Resetting IMU filter." ,
609+ (last_ros_time_ - now).seconds ());
610+
611+ if (time_jump_threshold_duration_ == rclcpp::Duration (0 , 0 ) &&
612+ this ->get_clock ()->get_clock_type () == RCL_SYSTEM_TIME)
613+ {
614+ RCLCPP_INFO (this ->get_logger (),
615+ " To ignore short time jumps back, use ~time_jump_threshold "
616+ " parameter of the filter." );
617+ }
618+
619+ reset ();
620+ }
621+
622+ void ImuFilterMadgwickRos::reset ()
623+ {
624+ std::lock_guard<std::mutex> lock (mutex_);
625+ filter_.reset ();
626+ initialized_ = false ;
627+ last_time_ = rclcpp::Time (0 , 0 , this ->get_clock ()->get_clock_type ());
628+ last_ros_time_ = this ->get_clock ()->now ();
629+ }
630+
585631#include " rclcpp_components/register_node_macro.hpp"
586632
587633RCLCPP_COMPONENTS_REGISTER_NODE (ImuFilterMadgwickRos)
0 commit comments