Skip to content

Commit 3732365

Browse files
committed
Added ability to reset IMU filters when ROS time jumps back (CCNYRoboticsLab#165)
1 parent 1242a65 commit 3732365

File tree

8 files changed

+128
-0
lines changed

8 files changed

+128
-0
lines changed

imu_complementary_filter/include/imu_complementary_filter/complementary_filter.h

Lines changed: 3 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -87,6 +87,9 @@ class ComplementaryFilter
8787
void update(double ax, double ay, double az, double wx, double wy,
8888
double wz, double mx, double my, double mz, double dt);
8989

90+
// Reset the filter to the initial state.
91+
void reset();
92+
9093
private:
9194
static const double kGravity;
9295
static const double gamma_;

imu_complementary_filter/include/imu_complementary_filter/complementary_filter_ros.h

Lines changed: 8 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -57,6 +57,9 @@ class ComplementaryFilterROS : public rclcpp::Node
5757
ComplementaryFilterROS();
5858
~ComplementaryFilterROS() override;
5959

60+
// Reset the filter to the initial state.
61+
void reset();
62+
6063
private:
6164
// Convenience typedefs
6265
typedef sensor_msgs::msg::Imu ImuMsg;
@@ -86,10 +89,12 @@ class ComplementaryFilterROS : public rclcpp::Node
8689
bool publish_debug_topics_{};
8790
std::string fixed_frame_;
8891
double orientation_variance_{};
92+
rclcpp::Duration time_jump_threshold_duration_{0, 0};
8993

9094
// State variables:
9195
ComplementaryFilter filter_;
9296
rclcpp::Time time_prev_;
97+
rclcpp::Time last_ros_time_;
9398
bool initialized_filter_;
9499

95100
void initializeParams();
@@ -100,6 +105,9 @@ class ComplementaryFilterROS : public rclcpp::Node
100105

101106
tf2::Quaternion hamiltonToTFQuaternion(double q0, double q1, double q2,
102107
double q3) const;
108+
109+
// Check whether ROS time has jumped back. If so, reset the filter.
110+
void checkTimeJump();
103111
};
104112

105113
} // namespace imu_tools

imu_complementary_filter/src/complementary_filter.cpp

Lines changed: 10 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -454,6 +454,16 @@ double ComplementaryFilter::getAdaptiveGain(double alpha, double ax, double ay,
454454
return factor * alpha;
455455
}
456456

457+
void ComplementaryFilter::reset()
458+
{
459+
initialized_ = false;
460+
steady_state_ = false;
461+
q0_ = 1.0;
462+
q1_ = q2_ = q3_ = 0.0;
463+
wx_bias_ = wy_bias_ = wz_bias_ = 0.0;
464+
wx_prev_ = wy_prev_ = wz_prev_ = 0.0;
465+
}
466+
457467
void normalizeVector(double& x, double& y, double& z)
458468
{
459469
double norm = sqrt(x * x + y * y + z * z);

imu_complementary_filter/src/complementary_filter_ros.cpp

Lines changed: 45 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -49,6 +49,8 @@ ComplementaryFilterROS::ComplementaryFilterROS()
4949
RCLCPP_INFO(this->get_logger(), "Starting ComplementaryFilterROS");
5050
initializeParams();
5151

52+
last_ros_time_ = this->get_clock()->now();
53+
5254
int queue_size = 5;
5355

5456
// Register publishers:
@@ -99,6 +101,7 @@ void ComplementaryFilterROS::initializeParams()
99101
double bias_alpha;
100102
bool do_adaptive_gain;
101103
double orientation_stddev;
104+
double time_jump_threshold;
102105

103106
// set "Not Dynamically Reconfigurable Parameters"
104107
auto descriptor = rcl_interfaces::msg::ParameterDescriptor();
@@ -128,6 +131,11 @@ void ComplementaryFilterROS::initializeParams()
128131
this->declare_parameter<double>("orientation_stddev", 0.0);
129132
orientation_variance_ = orientation_stddev * orientation_stddev;
130133

134+
time_jump_threshold =
135+
this->declare_parameter<double>("time_jump_threshold", 0.0);
136+
time_jump_threshold_duration_ =
137+
rclcpp::Duration::from_seconds(time_jump_threshold);
138+
131139
filter_.setDoBiasEstimation(do_bias_estimation);
132140
filter_.setDoAdaptiveGain(do_adaptive_gain);
133141

@@ -162,6 +170,8 @@ void ComplementaryFilterROS::initializeParams()
162170

163171
void ComplementaryFilterROS::imuCallback(ImuMsg::ConstSharedPtr imu_msg_raw)
164172
{
173+
checkTimeJump();
174+
165175
const geometry_msgs::msg::Vector3 &a = imu_msg_raw->linear_acceleration;
166176
const geometry_msgs::msg::Vector3 &w = imu_msg_raw->angular_velocity;
167177
const rclcpp::Time &time = imu_msg_raw->header.stamp;
@@ -193,6 +203,8 @@ void ComplementaryFilterROS::imuCallback(ImuMsg::ConstSharedPtr imu_msg_raw)
193203
void ComplementaryFilterROS::imuMagCallback(ImuMsg::ConstSharedPtr imu_msg_raw,
194204
MagMsg::ConstSharedPtr mag_msg)
195205
{
206+
checkTimeJump();
207+
196208
const geometry_msgs::msg::Vector3 &a = imu_msg_raw->linear_acceleration;
197209
const geometry_msgs::msg::Vector3 &w = imu_msg_raw->angular_velocity;
198210
const geometry_msgs::msg::Vector3 &m = mag_msg->magnetic_field;
@@ -313,4 +325,37 @@ void ComplementaryFilterROS::publish(ImuMsg::ConstSharedPtr imu_msg_raw)
313325
}
314326
}
315327

328+
void ComplementaryFilterROS::checkTimeJump()
329+
{
330+
const auto now = this->get_clock()->now();
331+
if (last_ros_time_ == rclcpp::Time(0, 0, last_ros_time_.get_clock_type()) ||
332+
last_ros_time_ <= now + time_jump_threshold_duration_)
333+
{
334+
last_ros_time_ = now;
335+
return;
336+
}
337+
338+
RCLCPP_WARN(this->get_logger(),
339+
"Detected jump back in time of %.1f s. Resetting IMU filter.",
340+
(last_ros_time_ - now).seconds());
341+
342+
if (time_jump_threshold_duration_ == rclcpp::Duration(0, 0) &&
343+
this->get_clock()->get_clock_type() == RCL_SYSTEM_TIME)
344+
{
345+
RCLCPP_INFO(this->get_logger(),
346+
"To ignore short time jumps back, use ~time_jump_threshold "
347+
"parameter of the filter.");
348+
}
349+
350+
reset();
351+
}
352+
353+
void ComplementaryFilterROS::reset()
354+
{
355+
filter_.reset();
356+
time_prev_ = rclcpp::Time(0, 0, this->get_clock()->get_clock_type());
357+
last_ros_time_ = this->get_clock()->now();
358+
initialized_filter_ = false;
359+
}
360+
316361
} // namespace imu_tools

imu_filter_madgwick/include/imu_filter_madgwick/imu_filter.h

Lines changed: 3 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -97,6 +97,9 @@ class ImuFilter
9797
float az, float dt);
9898

9999
void getGravity(float& rx, float& ry, float& rz, float gravity = 9.80665);
100+
101+
// Reset the filter to the initial state.
102+
void reset();
100103
};
101104

102105
#endif // IMU_FILTER_MADWICK_IMU_FILTER_H

imu_filter_madgwick/include/imu_filter_madgwick/imu_filter_ros.h

Lines changed: 8 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -59,6 +59,9 @@ class ImuFilterMadgwickRos : public imu_filter::BaseNode
5959
IMU_FILTER_MADGWICK_CPP_PUBLIC
6060
explicit ImuFilterMadgwickRos(const rclcpp::NodeOptions& options);
6161

62+
// Reset the filter to the initial state.
63+
void reset();
64+
6265
// Callbacks are public so they can be called when used as a library
6366
void imuCallback(ImuMsg::ConstSharedPtr imu_msg_raw);
6467
void imuMagCallback(ImuMsg::ConstSharedPtr imu_msg_raw,
@@ -98,11 +101,13 @@ class ImuFilterMadgwickRos : public imu_filter::BaseNode
98101
geometry_msgs::msg::Vector3 mag_bias_;
99102
double orientation_variance_;
100103
double yaw_offset_total_;
104+
rclcpp::Duration time_jump_threshold_duration_{0, 0};
101105

102106
// **** state variables
103107
std::mutex mutex_;
104108
bool initialized_;
105109
rclcpp::Time last_time_;
110+
rclcpp::Time last_ros_time_;
106111
tf2::Quaternion yaw_offsets_;
107112

108113
// **** filter implementation
@@ -120,4 +125,7 @@ class ImuFilterMadgwickRos : public imu_filter::BaseNode
120125
void checkTopicsTimerCallback();
121126

122127
void applyYawOffset(double& q0, double& q1, double& q2, double& q3);
128+
129+
// Check whether ROS time has jumped back. If so, reset the filter.
130+
void checkTimeJump();
123131
};

imu_filter_madgwick/src/imu_filter.cpp

Lines changed: 5 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -342,3 +342,8 @@ void ImuFilter::getGravity(float& rx, float& ry, float& rz, float gravity)
342342
break;
343343
}
344344
}
345+
346+
void ImuFilter::reset()
347+
{
348+
setOrientation(1, 0, 0, 0);
349+
}

imu_filter_madgwick/src/imu_filter_ros.cpp

Lines changed: 46 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -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};
@@ -229,6 +237,8 @@ ImuFilterMadgwickRos::ImuFilterMadgwickRos(const rclcpp::NodeOptions &options)
229237

230238
void ImuFilterMadgwickRos::imuCallback(ImuMsg::ConstSharedPtr imu_msg_raw)
231239
{
240+
checkTimeJump();
241+
232242
std::lock_guard<std::mutex> lock(mutex_);
233243

234244
const geometry_msgs::msg::Vector3 &ang_vel = imu_msg_raw->angular_velocity;
@@ -294,6 +304,8 @@ void ImuFilterMadgwickRos::imuCallback(ImuMsg::ConstSharedPtr imu_msg_raw)
294304
void ImuFilterMadgwickRos::imuMagCallback(ImuMsg::ConstSharedPtr imu_msg_raw,
295305
MagMsg::ConstSharedPtr mag_msg)
296306
{
307+
checkTimeJump();
308+
297309
std::lock_guard<std::mutex> lock(mutex_);
298310

299311
const geometry_msgs::msg::Vector3 &ang_vel = imu_msg_raw->angular_velocity;
@@ -590,6 +602,40 @@ void ImuFilterMadgwickRos::checkTopicsTimerCallback()
590602
<< "...");
591603
}
592604

605+
void ImuFilterMadgwickRos::checkTimeJump()
606+
{
607+
const auto now = this->get_clock()->now();
608+
if (last_ros_time_ == rclcpp::Time(0, 0, last_ros_time_.get_clock_type()) ||
609+
last_ros_time_ <= now + time_jump_threshold_duration_)
610+
{
611+
last_ros_time_ = now;
612+
return;
613+
}
614+
615+
RCLCPP_WARN(this->get_logger(),
616+
"Detected jump back in time of %.1f s. Resetting IMU filter.",
617+
(last_ros_time_ - now).seconds());
618+
619+
if (time_jump_threshold_duration_ == rclcpp::Duration(0, 0) &&
620+
this->get_clock()->get_clock_type() == RCL_SYSTEM_TIME)
621+
{
622+
RCLCPP_INFO(this->get_logger(),
623+
"To ignore short time jumps back, use ~time_jump_threshold "
624+
"parameter of the filter.");
625+
}
626+
627+
reset();
628+
}
629+
630+
void ImuFilterMadgwickRos::reset()
631+
{
632+
std::lock_guard<std::mutex> lock(mutex_);
633+
filter_.reset();
634+
initialized_ = false;
635+
last_time_ = rclcpp::Time(0, 0, this->get_clock()->get_clock_type());
636+
last_ros_time_ = this->get_clock()->now();
637+
}
638+
593639
#include "rclcpp_components/register_node_macro.hpp"
594640

595641
RCLCPP_COMPONENTS_REGISTER_NODE(ImuFilterMadgwickRos)

0 commit comments

Comments
 (0)