Skip to content

Commit 768444e

Browse files
committed
feat: Changes from am_imu_utils
1. transform() 2. inverse() 3. rotate() for quaternion fixed
1 parent f780ee9 commit 768444e

File tree

2 files changed

+62
-3
lines changed

2 files changed

+62
-3
lines changed

include/vb_util_lib/rotate.h

Lines changed: 16 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -70,7 +70,17 @@ namespace am
7070

7171
static void rotate(double &x, double &y, double &z, geometry_msgs::Quaternion &q_rot);
7272

73-
static void rotate(geometry_msgs::Point32 &p, geometry_msgs::Quaternion &q_rot);
73+
static void rotate(geometry_msgs::Point32 &p, const geometry_msgs::Quaternion &q_rot);
74+
75+
/*
76+
* @brief transforms a point with the passed transformed stamped
77+
*/
78+
static void transform(geometry_msgs::Point32 &p_in, const geometry_msgs::TransformStamped &tranform);
79+
80+
/*
81+
* @brief inverse transform
82+
*/
83+
static void reverse(geometry_msgs::Quaternion &q);
7484

7585
//Static method to convert quaternion by component to rpy by component
7686
static void getRPY(double x, double y, double z, double w, double &roll, double &pitch, double &yaw);
@@ -101,6 +111,11 @@ namespace am
101111
static void toRadian(geometry_msgs::Point &rpy);
102112
static void toDegree(geometry_msgs::Point &rpy);
103113

114+
/*
115+
* @brief assure that the angle is between -M_PI and M_PI
116+
*/
117+
static double wrap_pi(double angle);
118+
104119
};
105120
}
106121

src/vb_util_lib/rotate.cpp

Lines changed: 46 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -351,9 +351,9 @@ namespace am
351351

352352
}
353353

354-
void Rotate::rotate(geometry_msgs::Point32 &p, geometry_msgs::Quaternion &q_rot)
354+
void Rotate::rotate(geometry_msgs::Point32 &p, const geometry_msgs::Quaternion &q_rot)
355355
{
356-
geometry_msgs::Point32 old_p;
356+
geometry_msgs::Point32 old_p = p;
357357
p.x = q_rot.w*q_rot.w*old_p.x + 2*q_rot.y*q_rot.w*old_p.z - 2*q_rot.z*q_rot.w*old_p.y + q_rot.x*q_rot.x*old_p.x + 2*q_rot.y*q_rot.x*old_p.y + 2*q_rot.z*q_rot.x*old_p.z - q_rot.z*q_rot.z*old_p.x - q_rot.y*q_rot.y*old_p.x;
358358
p.y = 2*q_rot.x*q_rot.y*old_p.x + q_rot.y*q_rot.y*old_p.y + 2*q_rot.z*q_rot.y*old_p.z + 2*q_rot.w*q_rot.z*old_p.x - q_rot.z*q_rot.z*old_p.y + q_rot.w*q_rot.w*old_p.y - 2*q_rot.x*q_rot.w*old_p.z - q_rot.x*q_rot.x*old_p.y;
359359
p.z = 2*q_rot.x*q_rot.z*old_p.x + 2*q_rot.y*q_rot.z*old_p.y + q_rot.z*q_rot.z*old_p.z - 2*q_rot.w*q_rot.y*old_p.x - q_rot.y*q_rot.y*old_p.z + 2*q_rot.w*q_rot.x*old_p.y - q_rot.x*q_rot.x*old_p.z + q_rot.w*q_rot.w*old_p.z;
@@ -418,6 +418,50 @@ namespace am
418418
rpy.z = Rotate::toDegree(rpy.z);
419419
}
420420

421+
/*
422+
* @brief transforms a point with the passed transformed stamped
423+
*/
424+
void Rotate::transform(geometry_msgs::Point32 &p, const geometry_msgs::TransformStamped &tranform)
425+
{
426+
rotate(p, tranform.transform.rotation);
427+
p.x += tranform.transform.translation.x;
428+
p.y += tranform.transform.translation.y;
429+
p.z += tranform.transform.translation.z;
430+
}
431+
432+
/*
433+
* @brief inverse transform
434+
*/
435+
void Rotate::reverse(geometry_msgs::Quaternion &q)
436+
{
437+
double roll, pitch, yaw;
438+
getRPY(q, roll, pitch, yaw);
439+
440+
yaw -= M_PI;
441+
pitch -= M_PI;
442+
roll -=M_PI;
443+
444+
q = toQuaternionMsg(wrap_pi(roll), wrap_pi(pitch), wrap_pi(yaw));
445+
}
446+
447+
/*
448+
* @brief wrap_pi
449+
*/
450+
double Rotate::wrap_pi(double angle)
451+
{
452+
while (angle >= M_PI)
453+
{
454+
angle -= 2 * M_PI;
455+
}
456+
457+
while (angle <= -M_PI)
458+
{
459+
angle += 2 * M_PI;
460+
}
461+
462+
return angle;
463+
}
464+
421465
}
422466

423467

0 commit comments

Comments
 (0)