实现步骤
1、构建新的package,包名叫 imu_package;
2、在package中新建节点,节点叫imu_node;
3、在节点中,向nodehandle申请订阅话题/imu/data,并设置回调函数IMUCallback;
4、构建回调函数IMUCallback;
5、使用四元数转换成欧拉角。
查找IMU话题
rostopic list
节点代码
#include "ros/ros.h"
#include "sensor_msgs/Imu.h"
#include "tf/tf.h"
// IMU 回调函数
void IMUCallback(const sensor_msgs::Imu msg)
{
// 检测消息包中四元数数据是否存在
if(msg.orientation_covariance[0] < 0)
return;
// 四元数转成欧拉角
tf::Quaternion quaternion(
msg.orientation.x,
msg.orientation.y,
msg.orientation.z,
msg.orientation.w
);
double roll, pitch, yaw;
tf::Matrix3x3(quaternion).getRPY(roll, pitch, yaw);
// 弧度换算成角度
roll = roll*180/M_PI;
pitch = pitch*180/M_PI;
yaw = yaw*180/M_PI;
ROS_INFO("滚转= %.0f 俯仰= %.0f 朝向= %.0f", roll, pitch, yaw);
}
int main(int argc, char **argv)
{
setlocale(LC_ALL, "");
ros::init(argc,argv, "demo_imu_data");
ros::NodeHandle n;
// 订阅 IMU 的数据话题
ros::Subscriber sub = n.subscribe("imu/data", 100, IMUCallback);
ros::spin();
return 0;
}
参考
https://www.bilibili.com/video/BV1Ge4y1o7XS/?p=29&spm_id_from=pageDriver