环境:
ubuntu22.04
ros2-humble
ignition gazebo-fortress
如果文章中的内容有误,欢迎在评论内指出讨论
前言(碎碎念
ignition gazebo安装版本
ignition gazebo这个官网教程在安装这里就给我搞得有点糊涂,在Getting Started这个页面,ubuntu22.04版本它在garden后面写了个recommended
但是在Ros/gazebo Installation下面,推荐配置的是fortress
查了一下,ubuntu22.04还可以装ros2-iron,如果ros版本是humble就最好装fortress,是iron就推荐装garden。
ros2_controls
在用gazebo11进行仿真时会用到gazebo_ros2_control,ignition gazebo也有它对应的包,现在在官方github里,这个包叫gz_ros2_control,但注意,这个名字是从ros2-iron这个版本开始的,在humble里用二进制安装得用sudo apt install ros-humble-ign-ros2-control
。
xacro/urdf文件
这个是在你的机器人模型的基础上要加的,最好是单独写在一个文件里,然后用xacro把它和你的模型加载到一起。
<robot name="rob_gazebo" xmlns:xacro="http://wiki.ros.org/xacro">
<ros2_control name="IgnitionSystem" type="system">
<hardware>
<plugin>ign_ros2_control/IgnitionSystem</plugin>
</hardware>
<joint name="joint1">
<command_interface name="position" />
<state_interface name="position"/>
<state_interface name="velocity"/>
</joint>
<joint name="wheel1">
<command_interface name="velocity">
<param name="min">-10</param>
<param name="max">10</param>
</command_interface>
<state_interface name="position"/>
<state_interface name="velocity"/>
</joint>
</ros2_control>
<gazebo>
<plugin filename="ign_ros2_control-system" name="ign_ros2_control::IgnitionROS2ControlPlugin">
<parameters>$(find robot_gazebo)/config/ros2_controllers.yaml</parameters>
</plugin>
</gazebo>
</robot>
注意,我这里用的是对应fortess的ign_ros2_control,如果你用的是garden,参考gz_ros2_control-github里面的demo,plugin是不一样的。
ros2_controllers.yaml
这个文件如果你用了moveit2,是会自动生成的,直接用就行。如果没有用moveit,可以参考我另一篇文章里的,这个文件是一样的,没有修改。
ign.launch.py
import os
from ament_index_python.packages import get_package_share_directory
from launch import LaunchDescription
from launch.substitutions import LaunchConfiguration
from launch.actions import IncludeLaunchDescription, ExecuteProcess, DeclareLaunchArgument
from launch.launch_description_sources import PythonLaunchDescriptionSource
from launch_ros.actions import Node
import xacro
def generate_launch_description():
use_sim_time = LaunchConfiguration('use_sim_time', default=True)
robot_gazebo_path = os.path.join(get_package_share_directory('robot_gazebo'))
xacro_file = os.path.join(robot_gazebo_path,
'urdf_xacro',
'robot_simple_ign.urdf.xacro')
doc = xacro.parse(open(xacro_file))
xacro.process_doc(doc)
params = {'robot_description': doc.toxml(), 'use_sim_time': use_sim_time}
robot_state_publisher = Node(
package='robot_state_publisher',
executable='robot_state_publisher',
output='screen',
parameters=[params]
)
spawn_entity = Node(
package='ros_gz_sim',
executable='create',
output='screen',
arguments=['-topic', 'robot_description',
'-name', 'robot_gazebo',
'-allow_renaming', 'true',
'-z', '1.0'],
)
load_controllers = []
for controller in ["joint_state_broadcaster", "arm_controller","wheel_controller"]:
load_controllers += [
ExecuteProcess(
cmd=["ros2 run controller_manager spawner {}".format(controller)],
shell=True,
output="screen",
)
]
return LaunchDescription([
IncludeLaunchDescription(
PythonLaunchDescriptionSource(
[os.path.join(get_package_share_directory('ros_gz_sim'),
'launch', 'gz_sim.launch.py')]),
launch_arguments=[('gz_args', ['-r empty.sdf'])]
),
robot_state_publisher,
spawn_entity,
DeclareLaunchArgument(
'use_sim_time',
default_value=use_sim_time,
description='If true, use simulated clock'),
]
+ load_controllers)
这里在运行时如果提示找不到ros_gz_sim,就sudo apt install ros-humble-ros-gz-sim
,启动ignition gazebo和载入模型时最好就不用ros_ign_gazebo了,尤其是载入模型,会提示已经过时。
tips:启动ignition gazebo的launch_arguments里面,-r表示打开gazebo就启动仿真,没写-r进去是暂停的,需手动开始;-v表示终端显示的详细程度,范围是0~4;-s表示启动gazebo但不显示界面。
例:launch_arguments=[(‘gz_args’, [‘-r -v 4 empty.sdf’])]
遇到的问题
启动ignition gazebo后,界面是灰色的,什么都加载不出来,controllers都无法被成功加载,除非把gazebo关掉,但是分别加载empty.sdf和机器人模型都是没有问题的。
问题原因:
我的机器人加载进去最开始是在默认的原点,而empty.sdf里的地面加载的位置也是原点,由于我的机器人模型较为复杂,两个模型发生的碰撞导致计算量极大,RTF降至0.01%,谁也加载不出来。
解决办法:
在launch启动的spawn_entity参数里加上’-z’, ‘1.0’,把机器人初始位置抬高,避免和地面碰撞,稍微高点也没事,仿真开始时会由于重力掉落到地面上的。
moveit2 servo键盘控制
一文学会使用键盘控制moveit2机械臂模型-机器人梦想家
参考上面这篇文章可以快速实现在rviz2下的机械臂键盘控制,我尝试在该环境下加入gazebo11,实现在仿真软件对机械臂键盘实时控制,但是哪里动的都有问题,遂转用了ignition gazebo,效果好多了。不过由于RTF还是不太上的去,导致会存在一些延迟,可能和我模型优化得不太好有关。
注意,如果用ignition gazebo实现servo实时控制机械臂,一定记得把每一个节点的use_sim_time设置为true,每!一!个!
更新:最近又回gazebo尝试了一下,发现效果和ign里差不多了,但是中间弄了很多东西,我也不知道是哪里的问题,可能是和优化了模型的inertia有关?不过没有动moveit servo相关的内容,所以如果在gazebo11里servo效果不好,或许可以再检查一下自己的模型。