全国大学生智能汽车竞赛--讯飞组解读(六)

2026.01.20

IMU

官方的imu功能包为fdilink_ahrs,但是imu数据的发布又被封装在了底盘base_driver.cpp中(详见base_driver.cpp第798行),所以fdilink_ahrs这个功能包似乎没什么用,至少我没用上,里面好像可以设置一些imu的参数。本文将直接启动小车底盘获取imu数据,顺便讲解一下底盘功能包ucar_controller

启动底盘

底盘功能包为ucar_controller,该功能包下节点的作用为启动小车底盘订阅运动控制话题分解控制命令写入电机计算发布里程计…使用以下命令启动底盘。

roslaunch ucar_controller base_driver.launch

该launch文件中导入了driver_params_ucarV2.yaml参数文件,你可以修改其中的参数。比如,后期如果想使用robot_pose_ekf包优化定位,可能就需要修改这个参数文件中的话题名称和provide_odom_tf

启动成功后,终端输入rostopic list查看话题:

/battery_state
/cmd_vel
/imu
/joy
/mag_pose_2d
/odom
/rosout
/rosout_agg
/tf

获取imu数据

启动底盘后,在终端输入rostopic echo /imu,其中一条数据格式为:

orientation: 
  x: -0.004318391312092315
  y: 0.0017283791477151074
  z: -0.9999822844779546
  w: -0.003709964195724212
orientation_covariance: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]
angular_velocity: 
  x: 0.00180831050965935
  y: 0.004994199611246586
  z: 0.0006617492763325572
angular_velocity_covariance: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]
linear_acceleration: 
  x: -0.050474103540182114
  y: -0.056839585304260254
  z: 9.810661315917969
linear_acceleration_covariance: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]

其中:

  • orientation为四元数,可以解算出当前小车的姿态。
  • angular_velocity为各个方向上的角速度。
  • linear_acceleration为各个方向上的线性加速度。

最常使用的是orientation数据,因为它可以解算姿态,并且十分精准,这对于后续优化导航定位是非常有用的。

注意!!

imu是在每次小车开机时进行初始化,也就是说开机时小车的姿态为标准姿态(pitch、row为0)。imu的数据是多少与底盘节点无关,底盘节点只负责发布imu数据。

可以测试一下,先记录orientation数据,然后关掉底盘节点后旋转小车,重新启动底盘节点,会发现orientation发生变化。

此外,据官方所说,不同小车imu的安装方向也不一样。我将在导航定位优化章节中提到这两个问题的解决方法。

imu可视化插件

我们将在rviz上观察imu的变化,首先请修改ucar_controller中的tf_server.launch文件,将imu坐标系名称改为:

<param name="~imu_frame"     value="imu"/>

修改的原因是,该可视化插件要求imu坐标系的名称为imu

然后启动tf_server.launch,这个节点是用于发布所有传感器的tf关系。

roslaunch ucar_controller tf_server.launch 

接着启动rviz,Fixed Frame选择imu,在可视化窗口添加rviz_imu_plugin插件。

图片走丢了...
可视化插件

如果没有找到这个插件请自行安装。

订阅/imu话题后可以看到imu坐标系,旋转小车可以观察坐标系的变化。你可能会发现坐标系的变化方向跟小车旋转方向不一致,这是由于上文提到的imu安装方向有误。正常来说,红色代表x轴正方向,绿色代表y轴正方向,蓝色代表z轴正方向,且符合右手定则。

图片走丢了...
可视化插件

关于imu先介绍到这里,个人认为,imu最大的用处就是用于代替里程计的角度积分。此外,imu还可以用于记录小车姿态、计算相对姿态等,这或许能提供新的比赛思路。

运动控制

运动控制初体验

在上文我们已经成功启动了小车底盘,接下来顺便讲解一下小车的运动控制。首先确保底盘是启动状态:

roslaunch ucar_controller base_driver.launch

然后使用rostopic list命令查看当前活跃的话题,显示大致如下:

/battery_state
/cmd_vel
/imu
/joy
/mag_pose_2d
/odom
/rosout
/rosout_agg
/tf

其中/cmd_vel为运动控制话题,底盘节点订阅这个话题,接收到数据后解算为电机输入。

底盘节点也就是ucar_controller功能包下的base_driver.cpp,第977行velCallback函数中接收了/cmd_vel话题的数据,并保存在全局变量中。然后在第179行writeLoop函数中进行麦伦解算,将数据解析为四个轮子各自的转速指令,并循环写入电机。

接下来在新终端中输入以下指令:

rosrun teleop_twist_keyboard teleop_twist_keyboard.py 

这是ROS自带的键盘控制节点,它可以监听键盘输入,并发送控制数据到话题/cmd_vel。你可以按照终端输出进行操控,这也是后续导航建图必不可少的一步。

编写运动控制节点

接下来我们编写一个运动控制发布节点,在自己的功能包下创建move_test.py,导入以下代码,记得添加可执行权限。运行时请将小车放在空旷处。小车将会直行然后向左平移接着原地旋转。

#!/usr/bin/python3
# -*- coding: UTF-8 -*-
import rospy
from geometry_msgs.msg import Twist

if __name__ == "__main__":
    rospy.init_node("move_and_turn_node")
    pub = rospy.Publisher("/cmd_vel", Twist, queue_size=10)
    rospy.sleep(1)   # 等待publisher连接

    #======= 直行 =======
    # 设置速度
    move_cmd = Twist()
    move_cmd.linear.x = 0.5
    move_cmd.linear.y = 0.0
    move_cmd.angular.z = 0.0
    # 发布频率
    rate = rospy.Rate(10)  
    # 持续发布2秒
    start_time = rospy.Time.now()
    while rospy.Time.now() - start_time < rospy.Duration(2.0):
        pub.publish(move_cmd)
        rate.sleep()

    #======= 平移 =======
    move_cmd.linear.x = 0.0
    move_cmd.linear.y = 0.5
    move_cmd.angular.z = 0.0
    # 持续发布2秒
    start_time = rospy.Time.now()
    while rospy.Time.now() - start_time < rospy.Duration(2.0):
        pub.publish(move_cmd)
        rate.sleep()

    #======= 旋转 =======
    move_cmd.linear.x = 0.0
    move_cmd.linear.y = 0.0
    move_cmd.angular.z = 2.0
    # 持续发布2秒
    start_time = rospy.Time.now()
    while rospy.Time.now() - start_time < rospy.Duration(2.0):
        pub.publish(move_cmd)
        rate.sleep()

    #======= 停止 =======
    move_cmd.linear.x = 0.0
    move_cmd.linear.y = 0.0
    move_cmd.angular.z = 0.0
    pub.publish(move_cmd)

搭配麦克纳姆轮的小车可以实现全向移动、原地旋转,可以在任务算法实现时充分利用这一特性。


更多关于全国大学生智能汽车的分享,请访问个人主页。 期待你的评论与交流!