注册 登录
电子工程世界-论坛 返回首页 EEWORLD首页 频道 EE大学堂 下载中心 Datasheet 专题
LitchiCheng的个人空间 https://home.eeworld.com.cn/space-uid-1003127.html [收藏] [复制] [分享] [RSS]
日志

想知道两轮差速方形底盘 URDF 咋做,ROS2 配 Rviz 咋显示吗?看这里!

已有 62 次阅读2025-2-27 23:23 |个人分类:ROS2

视频讲解

 
 

模型概述

一个方形底盘和两个差速驱动轮

URDF 代码

<?xml version="1.0" encoding="utf-8"?>
<robot name="diff"> 
  <!-- 定义方形底盘 -->  
  <link name="base_link"> 
    <visual> 
      <geometry> 
        <box size="0.5 0.3 0.1"/> 
      </geometry>  
      <material name="base_link_material"> 
        <color rgba="0.0 0.0 1.0 1.0"/> <!-- 蓝色车体 -->
      </material> 
    </visual>  
    <collision> 
      <geometry> 
        <box size="0.5 0.3 0.1"/> 
      </geometry> 
    </collision>  
    <inertial> 
      <mass value="1.0"/>  
      <inertia ixx="0.01" ixy="0.0" ixz="0.0" iyy="0.01" iyz="0.0" izz="0.01"/> 
    </inertial> 
  </link>  
  <!-- 定义左驱动轮 -->  
  <link name="left_wheel_link"> 
    <visual> 
      <geometry> 
        <!-- 减小轮子宽度 -->
        <cylinder radius="0.05" length="0.05"/> 
      </geometry>  
      <material name="left_wheel_material"> 
        <color rgba="1.0 0.0 0.0 1.0"/> <!-- 红色轮子 -->
      </material> 
    </visual>  
    <collision> 
      <geometry> 
        <cylinder radius="0.05" length="0.05"/> 
      </geometry> 
    </collision>  
    <inertial> 
      <mass value="0.1"/>  
      <inertia ixx="0.001" ixy="0.0" ixz="0.0" iyy="0.001" iyz="0.0" izz="0.001"/> 
    </inertial> 
  </link>  
  <!-- 定义右驱动轮 -->  
  <link name="right_wheel_link"> 
    <visual> 
      <geometry> 
        <!-- 减小轮子宽度 -->
        <cylinder radius="0.05" length="0.05"/> 
      </geometry>  
      <material name="right_wheel_material"> 
        <color rgba="1.0 0.0 0.0 1.0"/> <!-- 红色轮子 -->
      </material> 
    </visual>  
    <collision> 
      <geometry> 
        <cylinder radius="0.05" length="0.05"/> 
      </geometry> 
    </collision>  
    <inertial> 
      <mass value="0.1"/>  
      <inertia ixx="0.001" ixy="0.0" ixz="0.0" iyy="0.001" iyz="0.0" izz="0.001"/> 
    </inertial> 
  </link>  
  <!-- 定义左驱动轮关节 -->  
  <joint name="left_wheel_joint" type="continuous"> 
    <parent link="base_link"/>  
    <child link="left_wheel_link"/>  
    <!-- 调整轮子位置到车体中心线 -->
    <origin xyz="0.0 0.15 0" rpy="1.5708 0 0"/>  
    <axis xyz="0 0 1"/> 
  </joint>  
  <!-- 定义右驱动轮关节 -->  
  <joint name="right_wheel_joint" type="continuous"> 
    <parent link="base_link"/>  
    <child link="right_wheel_link"/>  
    <!-- 调整轮子位置到车体中心线 -->
    <origin xyz="0.0 -0.15 0" rpy="1.5708 0 0"/>  
    <axis xyz="0 0 1"/> 
  </joint> 
</robot>

使用方法

安装相关的包

sudo apt update
sudo apt install ros-${ROS_DISTRO}-rviz2 ros-${ROS_DISTRO}-joint-state-publisher-gui ros-${ROS_DISTRO}-robot-state-publisher

将上述代码保存为 diff.urdf ,然后可以使用 Rviz 进行显示

进入工作空间,创建launch运行包

ros2 pkg create display_urdf_launch --build-type ament_cmake --destination-directory src

在 src/display_urdf_launch 中创建 launch 文件夹,添加文件 display_urdf.py 及内容如下:

urdf_file_path = '/home/dar/ros2/diff.urdf' 为上面 urdf 保存的位置

import os
from ament_index_python.packages import get_package_share_directory
from launch import LaunchDescription
from launch_ros.actions import Node

def generate_launch_description():
    # 读取 URDF 文件内容
    urdf_file_path = '/home/dar/ros2/diff.urdf'
    with open(urdf_file_path, 'r') as file:
        robot_description = file.read()

    return LaunchDescription([
        Node(
            package='joint_state_publisher_gui',
            executable='joint_state_publisher_gui',
            name='joint_state_publisher_gui',
            parameters=[{'robot_description': robot_description}]
        ),
        Node(
            package='robot_state_publisher',
            executable='robot_state_publisher',
            name='robot_state_publisher',
            parameters=[{'robot_description': robot_description}]
        ),
        Node(
            package='rviz2',
            executable='rviz2',
            name='rviz2'
        )
    ])

在 CMakeLists.txt 中增加如下:

install(DIRECTORY launch
  DESTINATION share/${PROJECT_NAME})

编译及运行

colcon build --packages-select display_urdf_launch
source install/setup.bash 
ros2 launch display_urdf_launch display_urdf.py

Rviz 中添加RobotModel

 

 

在 RobotModel 中的 Description Topic 中选择 /robot/description

 

 

在 Global Options 中选择 Fixed Frame 为 base_link

 

 

小车可以显示在中间位置

 

 

拖动控制台中的 joint 可以控制 link 转动

 

 

 

本文来自论坛,点击查看完整帖子内容。

评论 (0 个评论)

facelist doodle 涂鸦板

您需要登录后才可以评论 登录 | 注册

热门文章