ソースを参照

通过欧拉角获取四元数时直接调用tf::createQuaternionMsgFromRollPitchYaw为imu_msg.orientation赋值

corvin_zhang 4 年 前
コミット
1c6c6e6165

+ 1 - 1
src/rasp_imu_hat_6dof/serial_imu_hat_6dof/cfg/param.yaml

@@ -16,7 +16,7 @@
 # History:
 #   20200402: init this file.
 ################################################
-imu_dev: /dev/ttyUSB0
+imu_dev: /dev/ttyS0
 baud_rate: 9600
 data_bits: 8
 parity: N

+ 2 - 6
src/rasp_imu_hat_6dof/serial_imu_hat_6dof/src/serial_imu_node.cpp

@@ -5,7 +5,7 @@
  * Author: corvin
  * History:
  *   20200403: init this file.
- **************************************************/
+**************************************************/
 #include <ros/ros.h>
 #include <tf/tf.h>
 #include "imu_data.h"
@@ -70,11 +70,7 @@ int main(int argc, char **argv)
             yaw -= 360.0;
 
         //ROS_INFO("yaw:%f pitch:%f roll:%f",yaw, pitch, roll);
-        q = tf::createQuaternionMsgFromRollPitchYaw(roll, pitch, yaw);
-        imu_msg.orientation.x = q.x;
-        imu_msg.orientation.y = q.y;
-        imu_msg.orientation.z = q.z;
-        imu_msg.orientation.w = q.w;
+        imu_msg.orientation = tf::createQuaternionMsgFromRollPitchYaw(roll, pitch, yaw);
         imu_msg.orientation_covariance = {0.0025, 0, 0,
                                           0, 0.0025, 0,
                                           0, 0, 0.0025};