Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Using angles library to normalize angles #739

Merged
Merged
Show file tree
Hide file tree
Changes from 1 commit
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
6 changes: 4 additions & 2 deletions src/ekf.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -36,6 +36,7 @@
#include <Eigen/Dense>
#include <rclcpp/duration.hpp>
#include <vector>
#include <cmath>

namespace robot_localization
{
Expand Down Expand Up @@ -173,9 +174,10 @@ void Ekf::correct(const Measurement & measurement)

// Wrap angles in the innovation
for (size_t i = 0; i < update_size; ++i) {
if (update_indices[i] == StateMemberRoll ||
if ((update_indices[i] == StateMemberRoll ||
update_indices[i] == StateMemberPitch ||
update_indices[i] == StateMemberYaw)
update_indices[i] == StateMemberYaw) &&
std::isfinite(innovation_subset(i)))
Copy link
Collaborator

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

So if the innovation has values that are not finite, we should look into why. Otherwise, this feels like we're trying to just cover up a bigger issue.

Also, oof. I need to update this code to use this.

Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Probably is not your fault - I modified little a bit this code and BANG I got infinity loop. I think, this function should be protected against wrong values.

I will try to add "angles" library

{
while (innovation_subset(i) < -PI) {
innovation_subset(i) += TAU;
Expand Down
6 changes: 4 additions & 2 deletions src/ukf.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -34,6 +34,7 @@
#include <robot_localization/ukf.hpp>
#include <Eigen/Cholesky>
#include <vector>
#include <cmath>


namespace robot_localization
Expand Down Expand Up @@ -240,9 +241,10 @@ void Ukf::correct(const Measurement & measurement)

// Wrap angles in the innovation
for (size_t i = 0; i < updateSize; ++i) {
if (update_indices[i] == StateMemberRoll ||
if ((update_indices[i] == StateMemberRoll ||
update_indices[i] == StateMemberPitch ||
update_indices[i] == StateMemberYaw)
update_indices[i] == StateMemberYaw) &&
std::isfinite(innovation_subset(i)))
{
while (innovation_subset(i) < -PI) {
innovation_subset(i) += TAU;
Expand Down