|
@@ -122,10 +122,20 @@ void callback_twist(const geometry_msgs::TwistConstPtr &msg)
|
|
|
void callback_imu(const sensor_msgs::ImuConstPtr &msg)
|
|
|
{
|
|
|
ROS_INFO("Received nav992_device/Imu Array");
|
|
|
- adc_x = msg->orientation.x;
|
|
|
- adc_y = msg->orientation.y;
|
|
|
- adc_z = msg->orientation.z;
|
|
|
- adc_w = msg->orientation.w;
|
|
|
+ Quaternion q;
|
|
|
+ q.x = msg->orientation.x;
|
|
|
+ q.y = msg->orientation.y;
|
|
|
+ q.z = msg->orientation.z;
|
|
|
+ q.w = msg->orientation.w;
|
|
|
+ EulerAngles ang = ToEulerAngles(q);
|
|
|
+ double yaw = ang.yaw;
|
|
|
+ yaw = M_PI/2.0 - yaw;
|
|
|
+ ang.yaw = yaw;
|
|
|
+ q = ToQuaternion(ang.yaw,ang.pitch,ang.roll);
|
|
|
+ adc_x = q.x;
|
|
|
+ adc_y = q.y;
|
|
|
+ adc_z = q.z;
|
|
|
+ adc_w = q.w;
|
|
|
b_imu = true;
|
|
|
}
|
|
|
|