四轮阿克曼(前轮转向、后轮驱动)车子仿真控制

写在前面的话

这里增加一个四轮阿克曼(前轮转向、后轮驱动)车子仿真控制的版本,使用的事gazebo的插件

参考资料:gazebo plugins文档

调用 libgazebo_ros_ackermann_drive.so 插件

这段代码要添加到车子描述的xacro文件

属性介绍

  • plugin 声明调用的插件,name可以随便
  • ros 声明环境和话题映射
  • update_rate 更新频率
  • 底盘车轮控制
    • front_left_joint 这些跟自身的车子进行匹配就行,控制车轮转动的
    • left_steering_joint 这是控制车轮转向的
    • steering_wheel_joint 这个不是一个真正的轮子,类似是车子的方向盘,需要另外添加,后面有代码补充
  • max_steer 车轮最大转向角度,大约是37度(弧度制=0.6458)
  • max_steering_angle 方向盘(steering_wheel_joint)的最大转向角度,大概一圈半(弧度制=7.85)
  • publish_wheel_tf 官方代码是true,但github上很多代码是false
  • robot_base_frame 机器人的基准轴
  • odometry_frame 里程计odom的链接
  <gazebo>
    <plugin name="gazebo_ros_ackermann_drive" filename="libgazebo_ros_ackermann_drive.so">

      <ros>
        <namespace>/car_nav2</namespace>
        <remapping>cmd_vel:=cmd_demo</remapping>
        <remapping>odom:=odom_demo</remapping>
        <remapping>distance:=distance_demo</remapping>
      </ros>

      <update_rate>100.0</update_rate>

      <!-- wheels -->
      <front_left_joint>left_front_wheel_joint</front_left_joint>
      <front_right_joint>right_front_wheel_joint</front_right_joint>
      <rear_left_joint>left_back_wheel_joint</rear_left_joint>
      <rear_right_joint>right_back_wheel_joint</rear_right_joint>
      <left_steering_joint>left_front_orient_joint</left_steering_joint>
      <right_steering_joint>right_front_orient_joint</right_steering_joint>
      <steering_wheel_joint>virtual_steering_wheel_joint</steering_wheel_joint>

      <!-- Max absolute steer angle for tyre in radians-->
      <!-- Any cmd_vel angular z greater than this would be capped -->
      <max_steer>0.6458</max_steer>

      <!-- Max absolute steering angle of steering wheel -->
      <max_steering_angle>7.85</max_steering_angle>

      <!-- Max absolute linear speed in m/s -->
      <max_speed>5</max_speed>

      <!-- PID tuning -->
      <left_steering_pid_gain>1500 0 1</left_steering_pid_gain>
      <left_steering_i_range>0 0</left_steering_i_range>
      <right_steering_pid_gain>1500 0 1</right_steering_pid_gain>
      <right_steering_i_range>0 0</right_steering_i_range>
      <linear_velocity_pid_gain>1000 0 1</linear_velocity_pid_gain>
      <linear_velocity_i_range>0 0</linear_velocity_i_range>

      <!-- output -->
      <publish_odom>true</publish_odom>
      <publish_odom_tf>true</publish_odom_tf>
      <publish_wheel_tf>false</publish_wheel_tf>
      <publish_distance>true</publish_distance>

      <odometry_frame>odom_demo</odometry_frame>
      <robot_base_frame>base_link</robot_base_frame>

    </plugin>
  </gazebo>

补充 steering_wheel_joint 配置

需要把这段代码添加到车子描述的xacro文件中

  • virtual_steer_link 可以看到都是虚的,惯性啥的都是0,也就是不存在的
  • virtual_steering_wheel_joint 这个设置是前轮的转向的中间位置,z轴高度随意,我这里两个左右两个车轮分别是0.22654 0.5868 -0.0680.22654 -0.5868 -0.068,跟 base_link 绑定上即可
  <!-- Virtual Steering wheel -->
  <link name="virtual_steer_link">
      <visual>
          <origin xyz="0.0 0.0 0.0" rpy="0.0 0.0 0.0" />
          <geometry>
              <box size="0.01 0.15 0.075" />
          </geometry>
          <material name="">
              <color rgba="1.0 1.0 0.0 1" />
          </material>
      </visual>
      <inertial>  <!-- Gazebo won't show this link without this inertial mass -->
          <origin xyz="0.0 0.0 0.0" rpy="0.0 0.0 0.0" />
          <mass value="0.001" />
          <inertia ixx="0.0" ixy="0.0" ixz="0.0" iyy="0.0" iyz="0.0" izz="0.0" />
      </inertial>
  </link>
  <joint name="virtual_steering_wheel_joint" type="revolute">
    <origin xyz="0.22654 0 0" rpy="0.0 0.0 0.0" />
    <parent link="base_link" />
    <child link="virtual_steer_link" />
    <axis xyz="0 0 -1" />
    <limit lower="-3" upper="3" effort="200" velocity="10" />
  </joint>
  

键盘控制命令

注意,这里需要进行cmd_vel的进行映射,因为我们在调用 gazebo 插件的时候进行了 remapping 映射,可以查看上面的描述,同时要加上命名空间(namespace)

ros2 run teleop_twist_keyboard teleop_twist_keyboard cmd_vel:=/car_nav2/cmd_demo

结果演示

前轮转向,后轮驱动

在这里插入图片描述
在这里插入图片描述

评论 4
添加红包

请填写红包祝福语或标题

红包个数最小为10个

红包金额最低5元

当前余额3.43前往充值 >
需支付:10.00
成就一亿技术人!
领取后你会自动成为博主和红包主的粉丝 规则
hope_wisdom
发出的红包

打赏作者

G果

你的鼓励将是我创作的最大动力

¥1 ¥2 ¥4 ¥6 ¥10 ¥20
扫码支付:¥1
获取中
扫码支付

您的余额不足,请更换扫码支付或充值

打赏作者

实付
使用余额支付
点击重新获取
扫码支付
钱包余额 0

抵扣说明:

1.余额是钱包充值的虚拟货币,按照1:1的比例进行支付金额的抵扣。
2.余额无法直接购买下载,可以购买VIP、付费专栏及课程。

余额充值