소스 검색

更新imu模块线性加速度数据方向,ROS中规定沿着各轴方向为正方向

corvin 4 년 전
부모
커밋
1ec8758784

+ 3 - 2
src/rasp_imu_hat_6dof/rasp_imu_hat_6dof/nodes/imu_node.py

@@ -13,6 +13,7 @@
 #    20191209:新增发布IMU芯片温度的话题,发布频率与发布imu数据频率相同.
 #    20200406:增加可以直接发布yaw数据的话题.
 #    20200410:增加通过service方式发布yaw数据,方便其他节点调用.
+#    20200703:修改三轴线性加速度的方向,沿着各轴正方向数据为正,否则加速度就为负值,单位m/s2.
 import rospy
 import math
 
@@ -80,8 +81,8 @@ imuMsg.linear_acceleration_covariance = [
 ]
 
 seq=0
-# sensor reports accel as 256.0 = 1G (9.8m/s^2). Convert to m/s^2.
-accel_factor = 9.806/256.0
+# sensor accel g convert to m/s^2.
+accel_factor = 9.806
 
 myIMU = MyIMU(0x50)
 rate = rospy.Rate(pub_hz)

+ 4 - 2
src/rasp_imu_hat_6dof/serial_imu_hat_6dof/cfg/param.yaml

@@ -4,7 +4,8 @@
 #   imu_dev:指示串口设备挂在点,如果使用usb转串口
 #     模块,都是写ttyUSB0,1,2等.如果使用树莓派的
 #     GPIO排针处串口,则使用ttyS0.
-#   baud_rate:串口通信波特率
+#   baud_rate:串口通信波特率,旧模块的波特率为9600,
+#     新版本的波特率为57600,如果串口没数据可以修改.
 #   data_bits:数据位
 #   parity:数据校验位
 #   stop_bits:停止位
@@ -18,7 +19,7 @@
 #   20200406: 增加直接发布yaw数据的话题.
 ################################################
 imu_dev: /dev/ttyS0
-baud_rate: 9600
+baud_rate: 57600
 data_bits: 8
 parity: N
 stop_bits: 1
@@ -28,3 +29,4 @@ pub_temp_topic: imu_temp
 yaw_topic: yaw_data
 link_name: base_imu_link
 pub_hz: 10
+

+ 10 - 7
src/rasp_imu_hat_6dof/serial_imu_hat_6dof/src/serial_imu_node.cpp

@@ -1,12 +1,15 @@
-/**************************************************
+/****************************************************
  * Copyright:2016-2020 www.corvin.cn ROS小课堂
  * Description:使用串口来读取IMU模块的数据,并通过
- *   topic将数据发布出来.
+ *   topic将数据发布出来.芯片中默认读取出来的加速度数据
+ *   单位是g,需要将其转换为ROS中加速度规定的m/s2才能发布.
  * Author: corvin
  * History:
  *   20200403: init this file.
  *   20200406:增加发布yaw数据的话题.
-**************************************************/
+ *   20200703:修改三轴加速度数据正负,按照ROS规定沿着各轴
+ *     正方向时数据为正,否则为负.单位m/s2。
+*****************************************************/
 #include <ros/ros.h>
 #include <tf/tf.h>
 #include "imu_data.h"
@@ -29,7 +32,7 @@ int main(int argc, char **argv)
     std::string yaw_topic;
     int pub_hz = 0;
     float degree2Rad = 3.1415926/180.0;
-    float acc_factor = 9.806/256.0;
+    float acc_factor = 9.806;
 
     ros::init(argc, argv, "imu_data_pub_node");
     ros::NodeHandle handle;
@@ -92,9 +95,9 @@ int main(int argc, char **argv)
                                                0, 0, 0.02};
 
         //ROS_INFO("acc_x:%f acc_y:%f acc_z:%f",getAccX(), getAccY(), getAccZ());
-        imu_msg.linear_acceleration.x = getAccX()*acc_factor;
-        imu_msg.linear_acceleration.y = getAccY()*acc_factor;
-        imu_msg.linear_acceleration.z = getAccZ()*acc_factor;
+        imu_msg.linear_acceleration.x = -getAccX()*acc_factor;
+        imu_msg.linear_acceleration.y = -getAccY()*acc_factor;
+        imu_msg.linear_acceleration.z = -getAccZ()*acc_factor;
         imu_msg.linear_acceleration_covariance = {0.04, 0, 0,
                                                    0, 0.04, 0,
                                                    0, 0, 0.04};