diff --git a/package.xml b/package.xml index 7b3b6b81d..d7806c311 100644 --- a/package.xml +++ b/package.xml @@ -28,6 +28,7 @@ geographiclib message_filters nav_msgs + angles rclcpp rmw_implementation sensor_msgs diff --git a/src/ekf.cpp b/src/ekf.cpp index 4f4fa259e..b3dcc21f2 100644 --- a/src/ekf.cpp +++ b/src/ekf.cpp @@ -33,6 +33,7 @@ #include #include +#include #include #include #include @@ -177,13 +178,7 @@ void Ekf::correct(const Measurement & measurement) update_indices[i] == StateMemberPitch || update_indices[i] == StateMemberYaw) { - while (innovation_subset(i) < -PI) { - innovation_subset(i) += TAU; - } - - while (innovation_subset(i) > PI) { - innovation_subset(i) -= TAU; - } + innovation_subset(i) = ::angles::normalize_angle(innovation_subset(i)); } } diff --git a/src/ukf.cpp b/src/ukf.cpp index 4305c763e..ee77100bb 100644 --- a/src/ukf.cpp +++ b/src/ukf.cpp @@ -32,6 +32,7 @@ #include #include +#include #include #include @@ -244,13 +245,7 @@ void Ukf::correct(const Measurement & measurement) update_indices[i] == StateMemberPitch || update_indices[i] == StateMemberYaw) { - while (innovation_subset(i) < -PI) { - innovation_subset(i) += TAU; - } - - while (innovation_subset(i) > PI) { - innovation_subset(i) -= TAU; - } + innovation_subset(i) = ::angles::normalize_angle(innovation_subset(i)); } }