2.3.1. 模型与 urdf 文件
目录结构:
model/
├── meshes/
| ├── collision/
| | ├── base_link.stl
| | └── xxx.stl
| └── visual/
| ├── base_link.dae
| └── xxx.dae
└── urdf/
└── <robot-name>_description.urdf.xacro (如原来就有 urdf 则继续使用 .urdf)注意 urdf 里所有参数都要用浮点数,原 MoveIt1 可用而 MoveIt2 不可用
- KDL 相关警告:
base_link has an inertia specified ... KDL does not support a root link with an inertia表示根链接带惯量,建议加个无惯量dummy root link作为根链接(不改也能用)
xml<link name="base_link" /> <link name="base_body"> <!-- 原 base_link 内容,含惯量 --> </link> <joint name="base_joint" type="fixed"> <parent link="base_link" /> <child link="base_body" /> <origin xyz="0 0 0" rpy="0 0 0" /> </joint> <link name="link_1"> <!-- link_1 内容 --> </link> <joint name="joint1" type="revolute"> <origin xyz="0 0 0.0533" rpy="0 0 0" /> <parent link="base_body" /> <child link="link_1" /> <axis xyz="0 0 -1" /> <limit lower="-2.0944" upper="2.0944" effort="100" velocity="3" /> </joint>
2.3.2. 机器人描述包 + Rviz 验证
创建描述包:
# 如果未安装相关依赖,则先安装
sudo apt install ros-humble-joint-state-publisher-gui
# 进入 src
cd src
# 创建
ros2 pkg create --build-type ament_cmake <robot-name>_description --dependencies urdf xacro robot_state_publisher joint_state_publisher_gui目录结构:
<robot-name>_description/
├── CMakeLists.txt
├── package.xml
├── meshes/
├── urdf/
│ ├── <robot-name>_description.urdf.xacro ← 主文件(xacro 或 urdf)
│ ├── materials.xacro ← 可选
│ ├── macros/ ← 可选
│ └── ...
├── launch/
│ └── display.launch.py ← 用于 rviz 可视化检查
└── config/
└── joint_names.yaml ← 可选修改 CmakeLists.txt:
cmake_minimum_required(VERSION 3.8)
project(dm_arm_description)
if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang")
add_compile_options(-Wall -Wextra -Wpedantic)
endif()
# find dependencies
find_package(ament_cmake REQUIRED)
find_package(urdf REQUIRED)
find_package(xacro REQUIRED)
find_package(robot_state_publisher REQUIRED)
##########################################################
## 注释掉 joint_state_publisher_gui,因为是运行时节点而非依赖
### find_package(joint_state_publisher_gui REQUIRED)
##########################################################
if(BUILD_TESTING)
find_package(ament_lint_auto REQUIRED)
# the following line skips the linter which checks for copyrights
# comment the line when a copyright and license is added to all source files
set(ament_cmake_copyright_FOUND TRUE)
# the following line skips cpplint (only works in a git repo)
# comment the line when this package is in a git repo and when
# a copyright and license is added to all source files
set(ament_cmake_cpplint_FOUND TRUE)
ament_lint_auto_find_test_dependencies()
endif()
############################
## 安装 URDF、meshes 等资源
############################
install(
DIRECTORY urdf meshes launch config
DESTINATION share/${PROJECT_NAME}
)
ament_package()添加 display.launch.py:
from launch import LaunchDescription
from launch.substitutions import Command, PathJoinSubstitution
from launch_ros.actions import Node
from launch_ros.substitutions import FindPackageShare
URDF_PATH = "dm_arm_description.urdf"
def generate_launch_description():
# 查找包路径
pkg_share = FindPackageShare("dm_arm_description").find("dm_arm_description")
# URDF 文件路径
urdf_path = PathJoinSubstitution([pkg_share, "urdf", URDF_PATH])
# 判断是否使用 xacro
use_xacro = True if URDF_PATH.endswith(".xacro") else False
return LaunchDescription(
[
# 从 URDF 加载并发布 robot_description
Node(
package="robot_state_publisher",
executable="robot_state_publisher",
name="robot_state_publisher",
output="screen",
parameters=[
{
"robot_description": (
Command(["xacro ", urdf_path])
if use_xacro
else Command(["cat ", urdf_path])
)
}
],
),
# 启动 joint_state_publisher_gui
Node(
package="joint_state_publisher_gui",
executable="joint_state_publisher_gui",
name="joint_state_publisher_gui",
output="screen",
),
# 启动 RViz 并加载配置
Node(
package="rviz2",
executable="rviz2",
name="rviz2",
output="screen",
arguments=[
"-d",
PathJoinSubstitution([pkg_share, "config", "view_robot.rviz"]),
],
),
]
)构建并 source:
colcon build --symlink-install --packages-select <robot-name>_description运行 display.launch.py:
ros2 launch dm_arm_description display.launch.py- 选择
Global Options/Fixed Frame为基座:
- 添加
RobotModel并选择RobotModel/Description Topic为/robot_description如果没显示则是未及时更新,可点一下其他选项刷新
- 选择
2.3.3. MoveIt Config 包
2.3.3.1. MoveIt Setup Assistant
启动:
ros2 launch moveit_setup_assistant setup_assistant.launch.py新建:
Create New->Browse-><robot-name>_description.urdf->Load FileSelf-Collisions:
Generate Collision MatirxPlanning Groups:
Add Group- arm:
KDL->RRTConnect->Add Kin. Chain(base_link->link_tcp即底座 - 末端工作点) - gripper:
Add Joints->gripper_left(gripper_right是 mimic joint 不需要加进来)
- arm:
Robot Poses:
Add->homeEnd Effectors:
Add->Name=gripper->Group=gripper->Link=link_tcp->Parent=armROS2 Controllers:
Auto- arm:
joint_trajectory_controller/JointTrajectoryController - gripper:
position_controllers/GripperActionController
- arm:
MoveIt Controllers:
Auto- arm:
FollowJointTrajectory - gripper:
GripperCommand
- arm:
剩下个必填项为作者信息,按实际情况填即可
在
src/下新建<robot-name>_moveit_config/包用于存放生成的 SRDF,保存后构建并Sourceros2 launch dm_arm_moveit_config demo.launch.py验证
- 如果 setup_assistant 加载 urdf file 时报错 QT 相关的错误,需要降级 ros-humble-rviz-common
- 如果仍然有 parameter 'robot_description_planning.joint_limits.joint1.max_velocity' has invalid type: expected [double] got [integer] 报错,则在 config/joint_limits.yaml 里将整数补齐为浮点数后再构建并 Source
- 如果有 No action namespace specified for controller … through parameter … 报错,需要
- 在
<robot-name>_moveit_config/config/moveit_controller.yaml里的每个 controller 里添加:- action_ns: …(对应你的配置,如 follow_joint_trajectory)
2.3.3.2. MoveIt Setup Assistant 其他可选选项
2.3.3.3. 生成文件结构说明
Setup Assistant 完成后会在 <robot-name>_moveit_config/config/ 下生成以下关键文件,了解它们的作用有助于后续手动调整:
| 文件 | 作用 |
|---|---|
<robot>.srdf | 规划组定义、碰撞豁免、预设姿态、末端执行器 |
joint_limits.yaml | 关节速度/加速度上限,覆盖 URDF 中的值 |
kinematics.yaml | IK 求解器配置(插件名、超时、搜索步长) |
ompl_planning.yaml | OMPL 规划器参数,默认使用 RRTConnect |
ros2_controllers.yaml | ros2_control 的 controller 定义 |
moveit_controllers.yaml | MoveIt 侧的 controller 接口配置 |
moveit.rviz | RViz 预配置,含 MotionPlanning 插件 |
2.3.3.4. kinematics.yaml 关键参数
生成后可手动微调 config/kinematics.yaml,KDL 的两个参数影响 IK 成功率:
arm:
kinematics_solver: kdl_kinematics_plugin/KDLKinematicsPlugin
kinematics_solver_search_resolution: 0.005 # 搜索步长,越小越精确但越慢
kinematics_solver_timeout: 0.005 # 单次 IK 超时(秒),复杂位姿可调到 0.05
kinematics_solver_attempts: 3 # 超时后重试次数如果 KDL 在某些奇异构型下 IK 频繁失败,可以将求解器换为 trac_ik_kinematics_plugin/TRAC_IKKinematicsPlugin(需额外安装 ros-humble-trac-ik-kinematics-plugin),参数格式相同,收敛性更好,对近奇异点的处理比 KDL 稳定
2.3.3.5. 仿真与真实臂的切换
Setup Assistant 生成的 ros2_controllers.yaml 默认使用 mock_components/GenericSystem(即 FakeSystem)用于仿真;切换到真实臂时不需要重新跑 Setup Assistant,只需替换 hardware interface:
# 仿真(config/ros2_controllers.yaml 或 description 包内的 .ros2_control.xacro)
ros2_control:
hardware:
plugin: mock_components/GenericSystem # FakeSystem,纯仿真
# 真实臂(后续重构硬件接口后替换为)
ros2_control:
hardware:
plugin: dm_arm_hardware/DmHardwareInterface
# 其余 joint 定义、SRDF、Planning Group 完全不变MoveIt 规划层(SRDF、kinematics.yaml、ompl_planning.yaml)与硬件接口完全解耦,切换硬件不影响规划配置
2.3.3.6. mimic joint 处理
gripper_right 在 URDF 中声明了 <mimic joint="gripper_left">,但 mock_components/GenericSystem 默认不处理 mimic 关系,仿真时两指可能不同步。在 ros2_controllers.yaml 的 gripper controller 下添加:
gripper_controller:
ros__parameters:
joints:
- gripper_left
command_interfaces:
- position
state_interfaces:
- position
- velocity
allow_partial_joints_goal: true2.3.4. 纯 urdf 迁移为 xacro
- **目的:**把
.urdf改为.urdf.xacro,分离出dm_arm.ros2_control.xacro,通过 launch 参数控制仿真/真实切换,方便后续维护和调试 - **改造步骤:**把 URDF 主文件改成 xacro 格式 -> 新建一个专门放 ros2_control 描述的 xacro 文件 -> 重新对 xacro 文件再配置一次 MoveIt Config
2.3.4.1.把 URDF 主文件改成 xacro 格式
- 重命名:
<robot-name>_description.urdf.xacro - 然后在文件第二行(
<robot>标签里)加上 xacro 命名空间声明:
<!-- 原来 -->
<robot name="<robot-name>_description">
<!-- 改为 -->
<robot name="<robot-name>_description" xmlns:xacro="http://www.ros.org/wiki/xacro">- 然后在文件末尾
</robot>前加两行,引入 ros2_control 描述:
<!-- 引入 ros2_control 描述 -->
<xacro:arg name="use_fake_hardware" default="true"/>
<xacro:include filename="$(find <robot-name>_description)/urdf/<robot-name>.ros2_control.xacro"/>
<xacro:<robot-name>_ros2_control name="<robot-name>_hardware" use_fake_hardware="$(arg use_fake_hardware)"/>
</robot>2.3.4.2. 新建 <robot-name>.ros2_control.xacro
在 urdf/ 下新建文件并添加:
<?xml version="1.0"?>
<robot xmlns:xacro="http://www.ros.org/wiki/xacro">
<xacro:macro name="dm_arm_ros2_control" params="name use_fake_hardware:=true">
<ros2_control name="${name}" type="system">
<!-- 硬件插件选择 -->
<hardware>
<!-- 仿真模式 -->
<xacro:if value="${use_fake_hardware}">
<plugin>mock_components/GenericSystem</plugin>
</xacro:if>
<!-- 真实硬件模式 -->
<xacro:unless value="${use_fake_hardware}">
<plugin>dm_arm_hardware/DmHardwareInterface</plugin>
<param name="serial_port">/dev/ttyACM0</param>
<param name="baudrate">921600</param>
<param name="control_frequency">500.0</param>
</xacro:unless>
</hardware>
<!-- 关节名称(必须与 URDF 里的 joint name 一致) -->
<joint name="joint1">
<command_interface name="position"/>
<state_interface name="position">
<param name="initial_value">0.0</param>
</state_interface>
<state_interface name="velocity"/>
<state_interface name="effort"/>
</joint>
<!-- joint2 ~ joint6 -->
<joint name="gripper_left">
<command_interface name="position"/>
<state_interface name="position">
<param name="initial_value">0.0</param>
</state_interface>
<state_interface name="velocity"/>
<state_interface name="effort"/>
</joint>
</ros2_control>
</xacro:macro>
</robot>2.3.4.3. 重复之前的操作配置 MoveIt Config
- 本文链接:https://kaede-rei.github.io/learning-path/arm-motion-control/phase-2/2-3
- 版权声明:本博客所有文章除特别声明外,均默认采用 CC BY-NC-SA 许可协议。