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

Check for odometry quaternion normalization before display #1139

Merged
merged 1 commit into from
Aug 17, 2017
Merged
Changes from all commits
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
15 changes: 15 additions & 0 deletions src/rviz/default_plugin/odometry_display.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -253,6 +253,15 @@ bool validateFloats(const nav_msgs::Odometry& msg)
return valid;
}

bool validateQuaternion(const nav_msgs::Odometry& msg)
{
bool valid = std::abs((msg.pose.pose.orientation.x * msg.pose.pose.orientation.x
+ msg.pose.pose.orientation.y * msg.pose.pose.orientation.y
+ msg.pose.pose.orientation.z * msg.pose.pose.orientation.z
+ msg.pose.pose.orientation.w * msg.pose.pose.orientation.w) - 1.0f) < 10e-3;
return valid;
}

void OdometryDisplay::processMessage( const nav_msgs::Odometry::ConstPtr& message )
{
typedef CovarianceProperty::CovarianceVisualPtr CovarianceVisualPtr;
Expand All @@ -263,6 +272,12 @@ void OdometryDisplay::processMessage( const nav_msgs::Odometry::ConstPtr& messag
return;
}

if( !validateQuaternion( *message ))
{
setStatus( StatusProperty::Error, "Topic", "Message contained unnormalized quaternion (squares of values don't add to 1)");
return;
}

if( last_used_message_ )
{
Ogre::Vector3 last_position(last_used_message_->pose.pose.position.x, last_used_message_->pose.pose.position.y, last_used_message_->pose.pose.position.z);
Expand Down