Namespaces | Functions | Variables
validate_quaternions.h File Reference
#include <geometry_msgs/PoseStamped.h>
#include <OgreQuaternion.h>
#include <ros/ros.h>
#include <tf/LinearMath/Quaternion.h>
#include <boost/array.hpp>
Include dependency graph for validate_quaternions.h:
This graph shows which files directly or indirectly include this file:

Go to the source code of this file.

Namespaces

 rviz
 

Functions

float rviz::normalizeQuaternion (float &w, float &x, float &y, float &z)
 
double rviz::normalizeQuaternion (double &w, double &x, double &y, double &z)
 
double rviz::normalizeQuaternion (Ogre::Quaternion &quaternion)
 
double rviz::normalizeQuaternion (const geometry_msgs::Quaternion &msg, Ogre::Quaternion &q)
 
float rviz::quaternionNorm2 (float w, float x, float y, float z)
 
double rviz::quaternionNorm2 (double w, double x, double y, double z)
 
bool rviz::validateQuaternions (float w, float x, float y, float z)
 
bool rviz::validateQuaternions (double w, double x, double y, double z)
 
bool rviz::validateQuaternions (const Ogre::Quaternion &quaternion)
 
bool rviz::validateQuaternions (const tf::Quaternion &quaternion)
 
bool rviz::validateQuaternions (const geometry_msgs::Quaternion &msg)
 
bool rviz::validateQuaternions (const geometry_msgs::Pose &msg)
 
bool rviz::validateQuaternions (const geometry_msgs::PoseStamped &msg)
 
template<typename T >
bool rviz::validateQuaternions (const std::vector< T > &vec)
 
template<typename T , size_t N>
bool rviz::validateQuaternions (const boost::array< T, N > &arr)
 

Variables

static double rviz::QUATERNION_NORMALIZATION_TOLERANCE = 10e-3
 


rviz
Author(s): Dave Hershberger, David Gossow, Josh Faust
autogenerated on Wed Aug 28 2019 04:01:52