29 #ifndef utilfunctions_h__ 30 #define utilfunctions_h__ 39 return fmod(fmod(angle, 2.0
f*M_PI) + 2.0
f*M_PI, 2.0
f*M_PI);
51 static inline float sqr(
float val)
56 static inline int sign(
int x)
58 return x > 0 ? 1 : -1;
64 return radVal *
static_cast<T
>(180.0 / M_PI);
70 return degVal *
static_cast<T
>(M_PI / 180.0);
73 static bool poseDifferenceLargerThan(
const Eigen::Vector3f& pose1,
const Eigen::Vector3f& pose2,
float distanceDiffThresh,
float angleDiffThresh)
76 if ( ( (pose1.head<2>() - pose2.head<2>()).norm() ) > distanceDiffThresh){
80 float angleDiff = (pose1.z() - pose2.z());
82 if (angleDiff > M_PI) {
83 angleDiff -= M_PI * 2.0f;
84 }
else if (angleDiff < -M_PI) {
85 angleDiff += M_PI * 2.0f;
88 if (
abs(angleDiff) > angleDiffThresh){
static double getYaw(const Quaternion &bt_q)
static float sqr(float val)
static double getYawFromQuat(const geometry_msgs::Quaternion &quat)
static float normalize_angle_pos(float angle)
static float normalize_angle(float angle)
static T toRad(const T degVal)
static T toDeg(const T radVal)
INLINE Rall1d< T, V, S > abs(const Rall1d< T, V, S > &x)
static bool poseDifferenceLargerThan(const Eigen::Vector3f &pose1, const Eigen::Vector3f &pose2, float distanceDiffThresh, float angleDiffThresh)