分享

如何在Gazebo中实现多机器人仿真

 netouch 2023-06-28 发布于北京

gazebo是一款功能强大的三维物理仿真平台,具备强大的物理引擎、高质量的图形渲染、方便的编程与图形接口,最重要的是其开源免费的特性。gazebo中的机器人模型与rviz使用的模型相同,但是需要在模型中加入机器人和周围环境的物理属性,例如质量、摩擦系数、弹性系数等。机器人的传感器信息也可以通过插件的形式加入仿真环境,以可视化的方式进行显示。

 

在ros学习及研发过程中,经常需要使用gazebo来进行3D仿真,对模型的各种物理参数、控制代码等进行实物前的操练。在多智能体协同控制的研究中,需要在gazebo中添加多个机器人用于仿真,那么,应该如何将一个乃至多个机器人,放入gazebo仿真环境中呢?

 

1.单机器人仿真

在gazebo中放入机器人的操作通常用launch文件实现,步骤可归纳为:

 

设置launch文件参数-运行gazebo仿真环境-加载机器人模型描述参数-加载机器人模型

 

其中有关于urdf模型的构建可以参考古月学院的课程《一起从零手写URDF模型》和前面小伙伴的帖子《URDF物理参数解释及生成》

 

在我的仿真任务中代码如下:

<launch> <!-- 设置launch文件的参数 --> <arg name='world_name' value='$(find ares_gazebo)/worlds/playground.world'/> <arg name='paused' default='false'/> <arg name='use_sim_time' default='true'/> <arg name='gui' default='true'/> <arg name='headless' default='false'/> <arg name='debug' default='false'/> <!-- 运行gazebo仿真环境 --> <include file='$(find gazebo_ros)/launch/empty_world.launch'> <arg name='world_name' value='$(arg world_name)' /> <arg name='debug' value='$(arg debug)' /> <arg name='gui' value='$(arg gui)' /> <arg name='paused' value='$(arg paused)'/> <arg name='use_sim_time' value='$(arg use_sim_time)'/> <arg name='headless' value='$(arg headless)'/> </include> <!-- 加载机器人模型描述参数 --> <param name='robot_description' command='$(find xacro)/xacro --inorder '$(find ares_description)/urdf/ares_laser.xacro'' /> <!-- 运行joint_state_publisher节点,发布机器人的关节状态 --> <node name='joint_state_publisher' pkg='joint_state_publisher' type='joint_state_publisher' ></node> <!-- 运行robot_state_publisher节点,发布tf --> <node name='robot_state_publisher' pkg='robot_state_publisher' type='robot_state_publisher' output='screen' > <param name='publish_frequency' type='double' value='50.0' /> </node> <!-- 在gazebo中加载机器人模型--> <node name='urdf_spawner' pkg='gazebo_ros' type='spawn_model' respawn='false' output='screen' args='-urdf -model ares -param robot_description'/> </launch>
<launch> <!-- 设置launch文件的参数 --> <arg name='world_name' value='$(find ares_gazebo)/worlds/playground.world'/> <arg name='paused' default='false'/> <arg name='use_sim_time' default='true'/> <arg name='gui' default='true'/> <arg name='headless' default='false'/> <arg name='debug' default='false'/> <!-- 运行gazebo仿真环境 --> <include file='$(find gazebo_ros)/launch/empty_world.launch'> <arg name='world_name' value='$(arg world_name)' /> <arg name='debug' value='$(arg debug)' /> <arg name='gui' value='$(arg gui)' /> <arg name='paused' value='$(arg paused)'/> <arg name='use_sim_time' value='$(arg use_sim_time)'/> <arg name='headless' value='$(arg headless)'/> </include> <!-- 加载机器人模型描述参数 --> <param name='robot_description' command='$(find xacro)/xacro --inorder '$(find ares_description)/urdf/ares_laser.xacro'' /> <!-- 运行joint_state_publisher节点,发布机器人的关节状态 --> <node name='joint_state_publisher' pkg='joint_state_publisher' type='joint_state_publisher' ></node> <!-- 运行robot_state_publisher节点,发布tf --> <node name='robot_state_publisher' pkg='robot_state_publisher' type='robot_state_publisher' output='screen' > <param name='publish_frequency' type='double' value='50.0' /> </node> <!-- 在gazebo中加载机器人模型--> <node name='urdf_spawner' pkg='gazebo_ros' type='spawn_model' respawn='false' output='screen' args='-urdf -model ares -param robot_description'/> </launch>
   

2.多机器人仿真

相比于单机器人,多机器人仿真需要在原基础上加入<group>标签,做到用同样的descripion配置文件加载多个独立的机器人。

 

<group>具有ns属性,可以将节点组推送到单独的命名空间中。

 

在前面的基础上,在launch文件中改写成以下内容:

<group ns='命名空间'>
    <param name='robot_description' command='$(find xacro)/xacro --inorder '$(find ares_description)/urdf/ares_laser.xacro' ns:= 命名空间' /> 
    	<node name='joint_state_publisher' pkg='joint_state_publisher' type='joint_state_publisher' ></node> 
   	<node name='robot_state_publisher' pkg='robot_state_publisher' type='robot_state_publisher'  output='screen' >
     <param name='publish_frequency' type='double' value='50.0' />
</node>
    	<node name='urdf_spawner' pkg='gazebo_ros' type='spawn_model' respawn='false' output='screen'
    args='-urdf -model 命名空间 -param robot_description -x 0'/>   
</group>
<group ns='命名空间'> <param name='robot_description' command='$(find xacro)/xacro --inorder '$(find ares_description)/urdf/ares_laser.xacro' ns:= 命名空间' /> <node name='joint_state_publisher' pkg='joint_state_publisher' type='joint_state_publisher' ></node> <node name='robot_state_publisher' pkg='robot_state_publisher' type='robot_state_publisher' output='screen' > <param name='publish_frequency' type='double' value='50.0' /> </node> <node name='urdf_spawner' pkg='gazebo_ros' type='spawn_model' respawn='false' output='screen' args='-urdf -model 命名空间 -param robot_description -x 0'/> </group>
 

命名空间根据工程定义,在我的仿真中为ares1、ares2、ares3;“-x 0

-x 0
”为机器人在gazebo中的初始位置。  

将原本有关机器人状态的节点以及机器人模型放在<group>标签内,这样被<group>标签包围的节点、话题、参数、服务,都会在前面加入<命名空间>的前缀,如 /ares2/joint_state_publisher

image001

图1 在命名空间为ares2下的节点、话题等

 

这样便可以加入独立的多个机器人模型,效果如下:

image003

图2 多机器人仿真效果

 

当<group>及命名空间使用正确时,机器人的输入输出都应独立,如下图中三车搭载的摄像头所看的图像正确,无相互影响:

图3 ares1、ares2、ares3视角图像

3.多机器人运动控制

在加入多个机器人后,再做一下键盘对其的简单控制。

 

1)同时控制多个机器人

这里我使用的方法,是在机器人配置文件控制驱动插件代码中设置全局名称/cmd_vel

<gazebo> <plugin name='mecanum_controller' filename='libgazebo_ros_planar_move.so'> <commandTopic>/cmd_vel</commandTopic> <odometryTopic>/odom</odometryTopic> <odometryFrame>odom</odometryFrame> <leftFrontJoint>wheel_lf_joint</leftFrontJoint> <rightFrontJoint>wheel_rf_joint</rightFrontJoint> <leftRearJoint>wheel_lb_joint</leftRearJoint> <rightRearJoint>wheel_rb_joint</rightRearJoint> <odometryRate>20.0</odometryRate> <robotBaseFrame>base_link</robotBaseFrame> </plugin> </gazebo>
<gazebo> <plugin name='mecanum_controller' filename='libgazebo_ros_planar_move.so'> <commandTopic>/cmd_vel</commandTopic> <odometryTopic>/odom</odometryTopic> <odometryFrame>odom</odometryFrame> <leftFrontJoint>wheel_lf_joint</leftFrontJoint> <rightFrontJoint>wheel_rf_joint</rightFrontJoint> <leftRearJoint>wheel_lb_joint</leftRearJoint> <rightRearJoint>wheel_rb_joint</rightRearJoint> <odometryRate>20.0</odometryRate> <robotBaseFrame>base_link</robotBaseFrame> </plugin> </gazebo>
 

然后在键盘控制节点中发布全局名称/cmd_vel,这样就可以简单地做到多机器人同时接收一致的控制指令:

vel_pub = rospy.Publisher('/cmd_vel', Twist, queue_size=1)
vel_pub = rospy.Publisher('/cmd_vel', Twist, queue_size=1)
  image011

图6 整体控制时的rqt_graph

 

图7 整体控制时的效果

 

2)单独控制一个机器人

与前面相对,在这里我们将发布和接收的cmd_vel全部设置为相对名称(相对名称的典型特征是它缺少全局名称带有的前斜杠“/”),在我们设置的命名空间内发布后,ROS将当前命名空间的名称加在相对名称的前面,从而将相对名解析为全局名称。

 

即做以下修改:

<commandTopic>cmd_vel</commandTopic> vel_pub = rospy.Publisher('cmd_vel', Twist, queue_size=1)
<commandTopic>cmd_vel</commandTopic> vel_pub = rospy.Publisher('cmd_vel', Twist, queue_size=1)

在终端启动键盘控制节点时加上命名空间,即可实现对单个机器人的控制:

$ ROS_NAMESPACE=ares1 rosrun ares_teleop ares_teleop.py
$ ROS_NAMESPACE=ares1 rosrun ares_teleop ares_teleop.py
 

image014图8 单独控制时的rqt_graph

 

图9、10 单独控制时的效果

 

在命名空间下,还有经常使用的重映射<remap>操作,这里就不在赘述,感兴趣的小伙伴可以参考古月君的文章《ROS探索总结(五十六)—— launch文件》

 

在gazebo中加载多机器人仅仅是多智能体协同控制研究的第一步,之后还有大量的研究要做,我写的也只是个人总结 ,一定有很多不足之处,欢迎大家一起留言讨论。引用古月君的话作为总结,“怕什么真理无穷,进一寸有一寸的欢喜”,共勉!

 

完整代码:

<launch> <!-- 设置launch文件的参数 --> <arg name='world_name' value='$(find ares_gazebo)/worlds/playground.world'/> <arg name='paused' default='false'/> <arg name='use_sim_time' default='true'/> <arg name='gui' default='true'/> <arg name='headless' default='false'/> <arg name='debug' default='false'/> <!-- 运行gazebo仿真环境 --> <include file='$(find gazebo_ros)/launch/empty_world.launch'> <arg name='world_name' value='$(arg world_name)' /> <arg name='debug' value='$(arg debug)' /> <arg name='gui' value='$(arg gui)' /> <arg name='paused' value='$(arg paused)'/> <arg name='use_sim_time' value='$(arg use_sim_time)'/> <arg name='headless' value='$(arg headless)'/> </include> <!-- 加载机器人模型描述参数 --> <!-- begin robot1 --> <group ns='ares1'> <param name='robot_description' command='$(find xacro)/xacro --inorder '$(find ares_description)/urdf/ares_laser.xacro' ns:=ares1' /> <!-- 运行joint_state_publisher节点,发布机器人的关节状态 --> <node name='joint_state_publisher' pkg='joint_state_publisher' type='joint_state_publisher' ></node> <!-- 运行robot_state_publisher节点,发布tf --> <node name='robot_state_publisher' pkg='robot_state_publisher' type='robot_state_publisher' output='screen' > <param name='publish_frequency' type='double' value='50.0' /> </node> <!-- node name='ares_teleop' pkg='ares_teleop' type='ares_teleop.py' output='screen' /--> <!-- 在gazebo中加载机器人模型--> <node name='urdf_spawner' pkg='gazebo_ros' type='spawn_model' respawn='false' output='screen' args='-urdf -model ares1 -param robot_description -x 0'/> </group> <!-- begin robot2 --> <group ns='ares2'> <param name='robot_description' command='$(find xacro)/xacro --inorder '$(find ares_description)/urdf/ares_laser.xacro' ns:=ares2' /> <!-- 运行joint_state_publisher节点,发布机器人的关节状态 --> <node name='joint_state_publisher' pkg='joint_state_publisher' type='joint_state_publisher' ></node> <!-- 运行robot_state_publisher节点,发布tf --> <node name='robot_state_publisher' pkg='robot_state_publisher' type='robot_state_publisher' output='screen' > <param name='publish_frequency' type='double' value='50.0' /> </node> <!-- 在gazebo中加载机器人模型--> <node name='urdf_spawner' pkg='gazebo_ros' type='spawn_model' respawn='false' output='screen' args='-urdf -model ares2 -param robot_description -x 0.8'/> </group> <!-- begin robot3 --> <group ns='ares3'> <param name='robot_description' command='$(find xacro)/xacro --inorder '$(find ares_description)/urdf/ares_laser.xacro' ns:=ares3' /> <!-- 运行joint_state_publisher节点,发布机器人的关节状态 --> <node name='joint_state_publisher' pkg='joint_state_publisher' type='joint_state_publisher' ></node> <!-- 运行robot_state_publisher节点,发布tf --> <node name='robot_state_publisher' pkg='robot_state_publisher' type='robot_state_publisher' output='screen' > <param name='publish_frequency' type='double' value='50.0' /> </node> <!-- 在gazebo中加载机器人模型--> <node name='urdf_spawner' pkg='gazebo_ros' type='spawn_model' respawn='false' output='screen' args='-urdf -model ares3 -param robot_description -y 0.8'/> </group> </launch>
<launch> <!-- 设置launch文件的参数 --> <arg name='world_name' value='$(find ares_gazebo)/worlds/playground.world'/> <arg name='paused' default='false'/> <arg name='use_sim_time' default='true'/> <arg name='gui' default='true'/> <arg name='headless' default='false'/> <arg name='debug' default='false'/> <!-- 运行gazebo仿真环境 --> <include file='$(find gazebo_ros)/launch/empty_world.launch'> <arg name='world_name' value='$(arg world_name)' /> <arg name='debug' value='$(arg debug)' /> <arg name='gui' value='$(arg gui)' /> <arg name='paused' value='$(arg paused)'/> <arg name='use_sim_time' value='$(arg use_sim_time)'/> <arg name='headless' value='$(arg headless)'/> </include> <!-- 加载机器人模型描述参数 --> <!-- begin robot1 --> <group ns='ares1'> <param name='robot_description' command='$(find xacro)/xacro --inorder '$(find ares_description)/urdf/ares_laser.xacro' ns:=ares1' /> <!-- 运行joint_state_publisher节点,发布机器人的关节状态 --> <node name='joint_state_publisher' pkg='joint_state_publisher' type='joint_state_publisher' ></node> <!-- 运行robot_state_publisher节点,发布tf --> <node name='robot_state_publisher' pkg='robot_state_publisher' type='robot_state_publisher' output='screen' > <param name='publish_frequency' type='double' value='50.0' /> </node> <!-- node name='ares_teleop' pkg='ares_teleop' type='ares_teleop.py' output='screen' /--> <!-- 在gazebo中加载机器人模型--> <node name='urdf_spawner' pkg='gazebo_ros' type='spawn_model' respawn='false' output='screen' args='-urdf -model ares1 -param robot_description -x 0'/> </group> <!-- begin robot2 --> <group ns='ares2'> <param name='robot_description' command='$(find xacro)/xacro --inorder '$(find ares_description)/urdf/ares_laser.xacro' ns:=ares2' /> <!-- 运行joint_state_publisher节点,发布机器人的关节状态 --> <node name='joint_state_publisher' pkg='joint_state_publisher' type='joint_state_publisher' ></node> <!-- 运行robot_state_publisher节点,发布tf --> <node name='robot_state_publisher' pkg='robot_state_publisher' type='robot_state_publisher' output='screen' > <param name='publish_frequency' type='double' value='50.0' /> </node> <!-- 在gazebo中加载机器人模型--> <node name='urdf_spawner' pkg='gazebo_ros' type='spawn_model' respawn='false' output='screen' args='-urdf -model ares2 -param robot_description -x 0.8'/> </group> <!-- begin robot3 --> <group ns='ares3'> <param name='robot_description' command='$(find xacro)/xacro --inorder '$(find ares_description)/urdf/ares_laser.xacro' ns:=ares3' /> <!-- 运行joint_state_publisher节点,发布机器人的关节状态 --> <node name='joint_state_publisher' pkg='joint_state_publisher' type='joint_state_publisher' ></node> <!-- 运行robot_state_publisher节点,发布tf --> <node name='robot_state_publisher' pkg='robot_state_publisher' type='robot_state_publisher' output='screen' > <param name='publish_frequency' type='double' value='50.0' /> </node> <!-- 在gazebo中加载机器人模型--> <node name='urdf_spawner' pkg='gazebo_ros' type='spawn_model' respawn='false' output='screen' args='-urdf -model ares3 -param robot_description -y 0.8'/> </group> </launch>
 

    本站是提供个人知识管理的网络存储空间,所有内容均由用户发布,不代表本站观点。请注意甄别内容中的联系方式、诱导购买等信息,谨防诈骗。如发现有害或侵权内容,请点击一键举报。
    转藏 分享 献花(0

    0条评论

    发表

    请遵守用户 评论公约

    类似文章 更多