目录

1.准备

1. 创建go2_description功能包

2.模型下载

3. xml和CmakeList配置

3. launch文件编写

1.导入模型文件

2.发布关节消息

3. 雷达点云可视化

众所周之,可视化对机器人开发具有很重要的意义,实体开发具有一定的局限性,在某些场合可视化仿真是不二选择。本文将介绍如何在rviz2显示宇树go2机器狗的模型以及展示雷达点云。

1.准备

1. 创建go2_description功能包

打开vscode终端,输入以下指令创造功能包:

cd unitree_go2_ws/src/base

ros2 pkg create go2_description 

:创建的功能包必须为go2_description,这是适配之后要下载的宇树go2机器🐶的模型文件,不然会报一大堆错。同理,之后任何型号的机器人都是命名为:型号_description。

创建完成后你会看到上图框起来的四个文件,这时候就可以进行下一步的工作了。

2.模型下载

访问宇树官网:https://support.unitree.com/home/zh/developer/Obtain%20SDK下载go2_urdf。

下载后解压缩会得到GO2_URDF文件夹,然后要将GO2_URDF下的dae、meshes、urdf三个子文件夹,也就是框住的三个文件夹复制到~/unitree_go2_ws/src/base/go2_description目录下。

复制完后就可以开始下一步配置了。

3. xml和CmakeList配置

先要在~/unitree_go2_ws/src/base/go2_description目录下创建一个launch子文件夹,用来存放launch文件。

配置CmakeList文件,在CmakeList文件中添上以下内容:

install(

DIRECTORY launch dae urdf meshes

DESTINATION share/${PROJECT_NAME}

)

配置xml文件,在xml文件中添上以下内容:

<exec_depend>rviz2</exec_depend>

<exec_depend>ros2launch</exec_depend>

<exec_depend>xacro</exec_depend>

<exec_depend>robot_state_publisher</exec_depend>

<exec_depend>joint_state_publisher</exec_depend>

所有准备工作就做好了,接下来可以进行下一步操作了。

3. launch文件编写

在~/unitree_go2_ws/src/base/go2_description/launch目录下创建display.launch.py文件,然后编写代码。

1.导入模型文件

先要导入模型文件并发布,模型导入有两种方式,一种为静态导入,一种为动态导入,代码中有展示:

from launch import LaunchDescription
from launch_ros.actions import Node
# 封装终端指令相关类--------------
# from launch.actions import ExecuteProcess
# from launch.substitutions import FindExecutable
# 参数声明与获取-----------------
from launch.actions import DeclareLaunchArgument
from launch.substitutions import LaunchConfiguration,Command
# 文件包含相关-------------------
# from launch.actions import IncludeLaunchDescription
# from launch.launch_description_sources import PythonLaunchDescriptionSource
# 分组相关----------------------
# from launch_ros.actions import PushRosNamespace
# from launch.actions import GroupAction
# 事件相关----------------------
# from launch.event_handlers import OnProcessStart, OnProcessExit
# from launch.actions import ExecuteProcess, RegisterEventHandler,LogInfo
# 获取功能包下share目录路径-------
from ament_index_python.packages import get_package_share_directory
from launch_ros.parameter_descriptions import ParameterValue
import os
from launch.conditions import IfCondition


def generate_launch_description():
    #获取功能包路径
    go2_description_pkg = get_package_share_directory("go2_description")

    model = DeclareLaunchArgument(
        name="urdf_path",
        default_value=os.path.join(go2_description_pkg,"urdf","go2_description.urdf")
    )
    #使用xacro读取urdf文件内容
    # robot_desc = ParameterValue(Command(["xacro ",os.path.join(go2_description_pkg,"urdf","go2_description.urdf")]))
    robot_desc = ParameterValue(Command(["xacro ",LaunchConfiguration("urdf_path")]))
    #robot_state_publisher === 加载机器人urdf文件
    robot_state_publisher = Node(
        package="robot_state_publisher",
        executable="robot_state_publisher",
        parameters=[{"robot_description":robot_desc}]
    )



    return LaunchDescription([
                              model,
                              robot_state_publisher,
                              ])

写到这就可以进行初步编译调试了,在~/unitree_go2_ws目录下,输入如下指令:

colcon build --packaegs-select go2_description

. install/setup.bash

ros2 launch go2_description display.launch.py

然后要新开一个终端,还是在~/unitree_go2_ws目录下,输入以下指令:

. install/setup.bash

rviz2

然后将map替换成base,再在add中添加RobotModel组件,在RobotModel中将话题选为/robot_description。此时就会发现,一只机器🐶的身子显示出来,腿还没出来。因为还没发布joint_state_publisher的原因。

特别提醒:一定要在~/unitree_go2_ws目录下先使用. install/setup.bash指令,再使用rviz2指令,不然就会出现下面两张图片的情况。朱波已经有了惨痛的教训,找了一个多h的bug才发现!!!

2.发布关节消息

要加上这段发布关节消息的代码:


    use_joint_state_publisher = DeclareLaunchArgument(
        name="use_joint_state_publisher",
        default_value="true"
    )

    #joint_state_publisher === 发布关节状态,使关节贴合、
    #以后更合理的方式,由程序动态获取关节信息并发布
    #这个节点的启动应灵活设置
    joint_state_publisher = Node(
        package="joint_state_publisher",
        executable="joint_state_publisher",
        condition = IfCondition(LaunchConfiguration("use_joint_state_publisher"))
    )

最终的代码如以下所示:

from launch import LaunchDescription
from launch_ros.actions import Node
# 封装终端指令相关类--------------
# from launch.actions import ExecuteProcess
# from launch.substitutions import FindExecutable
# 参数声明与获取-----------------
from launch.actions import DeclareLaunchArgument
from launch.substitutions import LaunchConfiguration,Command
# 文件包含相关-------------------
# from launch.actions import IncludeLaunchDescription
# from launch.launch_description_sources import PythonLaunchDescriptionSource
# 分组相关----------------------
# from launch_ros.actions import PushRosNamespace
# from launch.actions import GroupAction
# 事件相关----------------------
# from launch.event_handlers import OnProcessStart, OnProcessExit
# from launch.actions import ExecuteProcess, RegisterEventHandler,LogInfo
# 获取功能包下share目录路径-------
from ament_index_python.packages import get_package_share_directory
from launch_ros.parameter_descriptions import ParameterValue
import os
from launch.conditions import IfCondition


def generate_launch_description():
    #获取功能包路径
    go2_description_pkg = get_package_share_directory("go2_description")

    
    use_joint_state_publisher = DeclareLaunchArgument(
        name="use_joint_state_publisher",
        default_value="true"
    )
    model = DeclareLaunchArgument(
        name="urdf_path",
        default_value=os.path.join(go2_description_pkg,"urdf","go2_description.urdf")
    )
    #使用xacro读取urdf文件内容
    # robot_desc = ParameterValue(Command(["xacro ",os.path.join(go2_description_pkg,"urdf","go2_description.urdf")]))
    robot_desc = ParameterValue(Command(["xacro ",LaunchConfiguration("urdf_path")]))
    #robot_state_publisher === 加载机器人urdf文件
    robot_state_publisher = Node(
        package="robot_state_publisher",
        executable="robot_state_publisher",
        parameters=[{"robot_description":robot_desc}]
    )

    #joint_state_publisher === 发布关节状态,使关节贴合、
    #以后更合理的方式,由程序动态获取关节信息并发布
    #这个节点的启动应灵活设置
    joint_state_publisher = Node(
        package="joint_state_publisher",
        executable="joint_state_publisher",
        condition = IfCondition(LaunchConfiguration("use_joint_state_publisher"))
    )

    return LaunchDescription([
                              model,
                              use_joint_state_publisher,
                              robot_state_publisher,
                              joint_state_publisher])

然后再按照上面进行编译运行,就会得到:

一只躺在地上的机器🐶,这是因为没有动态发布关节关系的原因,所以代码中有个处理,使用use_joint_state_publisher来决定是动态发布还是静态发布。动态发布先留个彩蛋,之后更新。

3. 雷达点云可视化

由于宇树官方给的仿真模型中雷达对应的坐标系为:radar,我们可以运用一点ROS2的小知识,输入以下指令查找机器🐶实体坐标系名称:

ros2 topic echo /utlidar/cloud --no-arr

得到机器🐶实体的坐标系名称为:utlidar_lidar。

想要使雷达点云可视化,就必须使用坐标系转换指令:

ros2 run tf2_ros static_transform_publisher --frame-id radar --child-frame-id utlidar_lidar

然后在rviz2中选取PointCloud2模块,然后选取话题为/utlidar/cloud,就可以看到点云数据已经在rviz2上显示喽。

本次blog就到这里,下期再见!

Logo

DAMO开发者矩阵,由阿里巴巴达摩院和中国互联网协会联合发起,致力于探讨最前沿的技术趋势与应用成果,搭建高质量的交流与分享平台,推动技术创新与产业应用链接,围绕“人工智能与新型计算”构建开放共享的开发者生态。

更多推荐