-
-
Notifications
You must be signed in to change notification settings - Fork 469
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
Normalize quaternions from msgs before Ogre use #1179
Changes from 10 commits
42a4416
3dc2e74
76e3a52
99d4096
5ef2fa4
332d24d
52ddd20
f16fefb
4eb197e
f5c7bab
df6dfd4
498c185
File filter
Filter by extension
Conversations
Jump to
Diff view
Diff view
There are no files selected for viewing
Original file line number | Diff line number | Diff line change |
---|---|---|
|
@@ -40,40 +40,89 @@ | |
namespace rviz | ||
{ | ||
|
||
// Tolerance for acceptable quaternion normalization (same as in tf) | ||
static double QUATERNION_NORMALIZATION_TOLERANCE = 10e-3; | ||
|
||
inline float quaternionNorm2( float w, float x, float y, float z ) | ||
{ | ||
return w * w + x * x + y * y + z * z; | ||
} | ||
|
||
inline bool validateQuaternions( float w, float x, float y, float z ) | ||
{ | ||
if ( 0.0f == x && 0.0f == y && 0.0f == z && 0.0f == w ) | ||
{ | ||
// Allow null quaternions to pass because they are common in uninitialized ROS messages. | ||
return true; | ||
} | ||
float norm2 = w * w + x * x + y * y + z * z; | ||
bool is_normalized = std::abs( norm2 - 1.0f ) < 10e-3f; | ||
float norm2 = quaternionNorm2( w, x, y, z ); | ||
bool is_normalized = std::abs( norm2 - 1.0f ) < QUATERNION_NORMALIZATION_TOLERANCE; | ||
ROS_DEBUG_COND_NAMED( !is_normalized, "quaternions", "Quaternion [x: %.3f, y: %.3f, z: %.3f, w: %.3f] not normalized. " | ||
"Magnitude: %.3f", x, y, z, w, std::sqrt(norm2) ); | ||
return is_normalized; | ||
} | ||
|
||
inline float normalizeQuaternion( float& w, float& x, float& y, float& z ) | ||
{ | ||
if ( 0.0f == x && 0.0f == y && 0.0f == z && 0.0f == w ) | ||
{ | ||
w = 1.0f; | ||
x = y = z = 0.0f; | ||
return 0.0f; | ||
} | ||
float norm2 = quaternionNorm2( w, x, y, z ); | ||
norm2 = std::sqrt( norm2 ); | ||
w /= norm2; | ||
x /= norm2; | ||
y /= norm2; | ||
z /= norm2; | ||
return norm2; | ||
} | ||
|
||
|
||
inline double quaternionNorm2( double w, double x, double y, double z ) | ||
{ | ||
return w * w + x * x + y * y + z * z; | ||
} | ||
|
||
inline bool validateQuaternions( double w, double x, double y, double z ) | ||
{ | ||
if ( 0.0 == x && 0.0 == y && 0.0 == z && 0.0 == w ) | ||
{ | ||
// Allow null quaternions to pass because they are common in uninitialized ROS messages. | ||
return true; | ||
} | ||
double norm2 = w * w + x * x + y * y + z * z; | ||
bool is_normalized = std::abs( norm2 - 1.0 ) < 10e-3; | ||
double norm2 = quaternionNorm2( w, x, y, z ); | ||
bool is_normalized = std::abs( norm2 - 1.0 ) < QUATERNION_NORMALIZATION_TOLERANCE; | ||
ROS_DEBUG_COND_NAMED( !is_normalized, "quaternions", "Quaternion [x: %.3f, y: %.3f, z: %.3f, w: %.3f] not normalized. " | ||
"Magnitude: %.3f", x, y, z, w, std::sqrt(norm2) ); | ||
return is_normalized; | ||
} | ||
|
||
inline bool validateQuaternions( Ogre::Quaternion quaternion ) | ||
inline double normalizeQuaternion( double& w, double& x, double& y, double& z ) | ||
{ | ||
if ( 0.0 == x && 0.0 == y && 0.0 == z && 0.0 == w ) | ||
{ | ||
w = 1.0; | ||
x = y = z = 0.0; | ||
There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. Superfluous again. |
||
return 0.0; | ||
} | ||
double norm2 = quaternionNorm2( w, x, y, z ); | ||
norm2 = std::sqrt( norm2 ); | ||
w /= norm2; | ||
x /= norm2; | ||
y /= norm2; | ||
z /= norm2; | ||
return norm2; | ||
} | ||
|
||
|
||
inline bool validateQuaternions( const Ogre::Quaternion& quaternion ) | ||
{ | ||
return validateQuaternions( quaternion.w, quaternion.x, quaternion.y, quaternion.z ); | ||
} | ||
|
||
inline bool validateQuaternions( tf::Quaternion quaternion ) | ||
inline bool validateQuaternions( const tf::Quaternion& quaternion ) | ||
{ | ||
return validateQuaternions( quaternion.w(), quaternion.x(), quaternion.y(), quaternion.z()); | ||
} | ||
|
@@ -93,6 +142,20 @@ inline bool validateQuaternions( const geometry_msgs::PoseStamped &msg ) | |
return validateQuaternions( msg.pose ); | ||
} | ||
|
||
inline double normalizeQuaternion( Ogre::Quaternion& quaternion ) | ||
{ | ||
return normalizeQuaternion( quaternion.w, quaternion.x, quaternion.y, quaternion.z ); | ||
} | ||
|
||
inline double normalizeQuaternion( const geometry_msgs::Quaternion &msg, Ogre::Quaternion &q ) | ||
{ | ||
q.w = msg.w; | ||
q.x = msg.x; | ||
q.y = msg.y; | ||
q.z = msg.z; | ||
return normalizeQuaternion( q ); | ||
} | ||
|
||
template<typename T> | ||
inline bool validateQuaternions( const std::vector<T> &vec ) | ||
There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. I more like the old version as it is more compact and easier to grasp ;-) There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. yeah, I know, but I'm trying to keep unnecessary changes out for this PR 😃 |
||
{ | ||
|
@@ -126,6 +189,7 @@ inline bool validateQuaternions( const boost::array<T, N> &arr ) | |
|
||
return true; | ||
} | ||
|
||
} // namespace rviz | ||
|
||
#endif // RVIZ_VALIDATE_QUATERNIONS_H |
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
This line is superfluous. x,y,z are zero already.
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
gah, thanks for pointing that out: df6dfd4