目录
rviz2 是 ros2 中的三维可视化工具,在里面可以根据坐标位置产生不同的点或物体
urdf是ros2 中的建模工具,可以用它来进行物体建模,然后再rviz2 中进行可视化显示。
urdf文件创建后是存在于磁盘中的,想要使用urdf文件就需要先将urdf文件加载到ros2系统中才可以。urdf的加载可以使用xacro工具进行加载
ros2 pkg list | grep -i xacro
可以看自己的ros2 中 是否安装了xacro,没有的话可以使用
sudo apt install ros-humble-xacro 安装
案例:要通过urdf创建一个模型并用rviz可视化
准备工作
安装所需要的功能包
sudo apt install ros-humble-joint-state-publisher
sudo apt install ros-humble-joint-state-publisher-gui
新建功能包
ros2 pkg create cpp06_urdf --build-type ament_cmake
在新建的功能包下创建文件夹,分别为urdf、rviz、launch、meshes,urdf下再新建子目录urdf和xacro,分别用于存储不同类型的文件
rviz: 用于存放rviz的配置
launch: 用于编写launch文件
meshes : 用于存储机器人的皮肤(存放别的软件生成的模型文件:solid works)
功能包配置
对package.xml进行配置(该功能包依赖于rviz2、xacro等其他功能包)
<exec_depend>ros2_launch</exec_depend>
<exec_depend>xacro</exec_depend>
<exec_depend>robot_state_publisher</exec_depend>
<exec_depend>joint_state_publisher</exec_depend>
<exec_depend>rviz2</exec_depend>
对cmakelist进行配置(对之前创建的文件夹添加路径)
install(DIRECTORY launch rviz urdf meshes
DESTINATION share/${PROJECT_NAME}
)
可以先colcon build 一下,看是否配置成功,成功的话可以在install目录下找到对应的文件夹
代码编写
创建一个长方体模型(在urdf/urdf下进行编写)
<!--
安装依赖 :sudo apt install ros-humble-joint-state-publisher
sudo apt install ros-humble-joint-state-publisher-gui
安装xacro :sudo apt install ros-humble-xacro
-->
<!--
需求 :创建一个盒装机器人
长 :1.0
宽 :0.5
高 :0.1
:
-->
<robot name="hello_world">
<link name="base_link">
<!-- 连杆 :机器人的刚体部分 -->
<visual>
<!-- 可视化 -->
<geometry>
<!-- 几何外观 -->
<box size="1.0 0.5 0.1"/>
</geometry>
</visual>
</link>
</robot>
编写launch文件
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
# 文件包含相关-------------------
# 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
from launch.substitutions import Command
def generate_launch_description():
param_value = ParameterValue(Command(["xacro ",get_package_share_directory("cpp06_urdf") + "/urdf/urdf/demo01_halloworld.urdf"]))
robot_state_pub = Node(
package="robot_state_publisher",
executable="robot_state_publisher",
parameters=[{"robot_description": param_value}]
)
rviz2 = Node(package="rviz2",executable="rviz2")
return LaunchDescription([robot_state_pub,rviz2])
在launch里要通过xacro导入urdf文件,xacro需要导入urdf的文件路径,这里使用command指令完成,再将urdf以参数的形式传给robot节点,通过ParamterValue进行封装。
写完后运行检查一次(如果vscode无法打开rviz2,那就直接终端打开)
运行成功后会打开rviz2,然后添加robot插件,话题选择robot_description,fixed frame 改为 base_link 即之前命名的link name
代码优化
1. 刚才导入的路径是直接固定写死的,可以优化的更灵活一些
2. 这里导入的模型是单个的固定的长方体,可以增加一些非固定的关节点,增加灵活性
3. 这里打开rviz2 后需要手动配置,可以优化为直接导入配置面板
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
# 文件包含相关-------------------
# 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
from launch.substitutions import Command
def generate_launch_description():
model = DeclareLaunchArgument(name="model",default_value=get_package_share_directory("cpp06_urdf") + "/urdf/urdf/demo01_halloworld.urdf")
param_value = ParameterValue(Command(["xacro ",LaunchConfiguration("model")]))
# 调用格式
# ros2 launch cpp06_urdf display.launch.py model:=`ros2 pkg prefix --share cpp06_urdf`/urdf/urdf/hah.urdf
# `ros2 pkg prefix --share cpp06_urdf`等价于get_package_share_directory("cpp06_urdf")
robot_state_pub = Node(
package="robot_state_publisher",
executable="robot_state_publisher",
parameters=[{"robot_description": param_value}]
)
# 优化2
joint_state_pub = Node(
package="joint_state_publisher",
executable="joint_state_publisher"
)
# 优化3
rviz2 = Node(
package="rviz2",
executable="rviz2",
arguments=["-d",get_package_share_directory("cpp06_urdf") + "/rviz/urdf.rviz"]
)
model = DeclareLaunchArgument(name="model",default_value=get_package_share_directory("cpp06_urdf") + "/urdf/urdf/demo01_halloworld.urdf")
return LaunchDescription([model,robot_state_pub,rviz2,joint_state_pub])
优化1:
为了路径的灵活性,将路径进行重新封装,参数化model,使用到了
# 参数声明与获取-----------------
from launch.actions import DeclareLaunchArgument
from launch.substitutions import LaunchConfiguration
如果要修改urdf的路径,直接通过终端修改参数model即可
ros2 launch cpp06_urdf display.launch.py model:=`ros2 pkg prefix --share cpp06_urdf`/urdf/urdf/xxxxxx.urdf
优化2:直接添加节点即可
优化3:可以先将rviz2 的配置文件保存到某个位置,然后在rviz的节点中带入参数,arguments表示在命令行后面加入你要加的内容
运行上面的
rviz2 = Node(
package="rviz2",
executable="rviz2",
arguments=["-d",get_package_share_directory("cpp06_urdf") + "/rviz/urdf.rviz"]
)就等价于
ros2 run rviz2 rviz2 -d /home/user/ws02_tools/src/cpp06_urdf/rviz/urdf.rviz