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