GAZEBO에 로봇 통합
저작권: 쿼드(QUAD) 드론연구소 https://www.youtube.com/@quad-robotics
이제 Gazebo와 함께 작동하도록 로봇(예: 이전 자습서의 로봇)을 변환할 때 수행할 수 있는 몇 가지 단계를 살펴보겠습니다.
참고로 여기에 전체 코드가 표시되어 있으며 아래 단락에서 추가 설명을 제공합니다.
<?xml version="1.0"?>
<robot xmlns:xacro="http://www.ros.org/wiki/xacro">
<!-- This file demonstrates the use of some <gazebo> tags -->
<!-- To include it add the following line -->
<!-- <xacro:include filename="example_gazebo.xacro" /> -->
<!-- Gazebo is unable to use the same <material> tags that are already in the URDF (that RViz uses). -->
<!-- Instead, we need to add gazebo tags for our links that refer to Gazebo materials -->
<gazebo reference="base_link">
<material>Gazebo/Green</material>
</gazebo>
<gazebo reference="slider_link">
<material>Gazebo/Blue</material>
</gazebo>
<gazebo reference="arm_link">
<material>Gazebo/Orange</material>
</gazebo>
<!-- Gazebo requires the use of plugins to interact with other systems such as ROS. -->
<!-- This plugin will publish the joint_states for the selected joints
(which robot_state_publisher can then use to broadcast the approprate tf). -->
<gazebo>
<plugin name="gazebo_ros_joint_state_publisher"
filename="libgazebo_ros_joint_state_publisher.so">
<update_rate>20</update_rate>
<joint_name>slider_joint</joint_name>
<joint_name>arm_joint</joint_name>
</plugin>
</gazebo>
<!-- This plugin will read a JointTrajectory message from the /set_joint_trajectory topic
and move the machine accordingly. It's a bit clunky but it works. -->
<!-- You'll probably want to add damping to the joints to stop them it flopping around.
e.g. <dynamics damping="10.0" friction="10.0"/> -->
<!-- Here's an example message to publish to test it:
ros2 topic pub -1 /set_joint_trajectory trajectory_msgs/msg/JointTrajectory '{header: {frame_id: world}, joint_names: [slider_joint, arm_joint], points: [ {positions: {0.8,0.6}} ]}' -->
<gazebo>
<plugin name="gazebo_ros_joint_pose_trajectory"
filename="libgazebo_ros_joint_pose_trajectory.so">
<update_rate>2</update_rate>
</plugin>
</gazebo>
<!-- The next section shows an example of adding a sensor, in this case a depth camera. -->
<!-- Due to a quirk of how cameras work, an extra joint/link is required to create an
"optical frame" for the sensor. That isn't the focus for this tutorial, but you can
look at https://www.ros.org/reps/rep-0103.html#suffix-frames for slightly more information. -->
<!-- First, create the link and joint for the optical frame -->
<joint name="camera_optical_joint" type="fixed">
<origin xyz="0 0 0" rpy="-1.571 0 -1.571" />
<parent link="camera_link" />
<child link="camera_link_optical" />
</joint>
<link name="camera_link_optical"></link>
<!-- Add a gazebo tag for the ORIGINAL camera_link (but in the plugin we reference the optical frame so that ROS can orient things correctly) -->
<!-- Within the gazebo tag we have the sensor tag, and inside that there is (among other things) the camera tag with the camera parameters,
and the plugin tag with some extra parameters the plugin needs. -->
<!-- Note that although visualise is set to true, it won't actually visualise the depth camera in gazebo. To see the preview,
try swapping "depth" to "camera"-->
<gazebo reference="camera_link">
<sensor type="depth" name="my_camera">
<update_rate>20</update_rate>
<visualize>true</visualize>
<camera name="cam">
<horizontal_fov>1.3962634</horizontal_fov>
<image>
<width>640</width>
<height>480</height>
<format>R8B8G8</format>
</image>
<clip>
<near>0.02</near>
<far>300</far>
</clip>
<noise>
<type>gaussian</type>
<mean>0.0</mean>
<stddev>0.007</stddev>
</noise>
</camera>
<plugin name="camera_controller" filename="libgazebo_ros_camera.so">
<frame_name>camera_link_optical</frame_name>
<min_depth>0.1</min_depth>
<max_depth>500</max_depth>
</plugin>
</sensor>
</gazebo>
</robot>
소재/색상
material
태그를 사용하여 URDF에서 RViz의 색상을 지정하더라도 Gazebo에서 올바르게 표시되지 않습니다. 대신 적절한 자료를 지정하는 고유한 gazebo
태그가 있는 각 링크에 대한 material
태그를 사용해야 합니다(Gazebo에는 묶음이 함께 제공되며 여기를 클릭 하고 검색하여 Gazebo/
내용을 확인할 수 있음).
<gazebo reference="my_link">
<material>Gazebo/Black</material>
</gazebo>
Joint 상태 게시 및 컨트롤러 실행
로봇이 Gazebo 내부에 생성되면 시뮬레이터가 더 광범위한 ROS 시스템과 통합하기 위해 수행해야 하는 두 가지 주요 작업이 있습니다.
일종의 명령 입력을 기반으로 가상 액추에이터 시뮬레이션
결과 관절 위치/각도를
joint_states 토픽
에 게시합니다.
그런 다음 모든 변환을 브로드캐스트하는 데 필요한 robot_state_publisher
정보를 갖게 됩니다.
앞에서 보았듯이 이를 달성하는 방법은 플러그인을 통하는 것입니다. 이러한 작업을 위한 가장 일반적이고 강력한 플러그인은 gazebo_ros2_control 입니다
. ros2_control은
로봇의 시뮬레이션 버전과 실제 버전 간에 또는 심지어 서로 다른 로봇 간에도 컨트롤러를 쉽게 재사용할 수 있는 모듈식 시스템인 이라는 광범위한 시스템의 일부로 설계되었습니다 .
이 gazebo_ros2_control은
두 가지 작업을 모두 수행할 수 있는 훌륭한 플러그인 이지만 초보자에게는 혼란스러울 수 있으며 자체 전체 자습서가 필요합니다. 다양한 방식으로 이러한 작업을 수행하는 다른 플러그인이 있으며 데모에 사용된 플러그인은 gazebo-ros 라이브러리와 함께 번들로 제공되는 더 간단한 플러그인입니다.
ROS 1에서 우리가 Gazebo와 상호 작용하는 방식의 큰 부분
ros_control
은transmissions 방식입니다
. ROS 2에서 일부 지원이 있기는 하지만 현재 표준 접근 방식은 아닌 것 같습니다.
Gazebo에서 조인트 상태를 게시하기 위해 사용된 플러그인의 예:
<plugin name="gazebo_ros_joint_state_publisher"
filename="libgazebo_ros_joint_state_publisher.so">
<update_rate>20</update_rate>
<joint_name>slider_joint</joint_name>
<joint_name>arm_joint</joint_name>
</plugin>
Joint 제어의 경우:
<gazebo>
<plugin name="gazebo_ros_joint_pose_trajectory"
filename="libgazebo_ros_joint_pose_trajectory.so">
<update_rate>20</update_rate>
</plugin>
</gazebo>
Gazebo를 다시 시작한 후 이제 변환이 작동하므로 RViz와 같은 도구에서 로봇이 올바르게 표시되는 것을 볼 수 있습니다. 아래 명령을 실행하면 관절이 끝에 있는 값으로 설정됩니다( 0.8m for
slider_joint, 0.6rad
for arm_joint
) .
ros2 topic pub -1 /set_joint_trajectory trajectory_msgs/msg/JointTrajectory '{header: {frame_id: world}, joint_names: [slider_joint, arm_joint], points: [ {positions: {0.8,0.6}} ]}'
로봇이 너무 많이 "퍼핑"하는 경우 다음 태그를 사용하여 원래 URDF( slider_joint
및 arm_joint
) 의 조인트에 약간의 댐핑을 추가해 보십시오 .
<dynamics damping="10.0" friction="10.0"/>
센서
Gazebo에는 센서를 시뮬레이션하고 출력을 ROS 주제에 게시하는 기능이 있습니다. 각 센서는 링크에 연결되어야 하므로 추가하려는 Gazebo 참조 태그 내에 <sensor>
태그를 추가해야 합니다 . 정확한 구현은 모든 센서마다 다르기 때문에 지금 모두 다루지는 않겠지만 각각에 대해 센서 유형, ROS에 연결하는 데 필요한 플러그인, 센서 또는 플러그인에 필요한 모든 매개 변수를 지정해야 합니다. .
다음은 LiDAR(Gazebo에서 "레이저 센서"라고 함)를 시뮬레이트하는 데 사용할 수 있는 센서 태그의 예입니다. 앞의 샘플 코드는 깊이 카메라에 대한 전체 구성을 보여줍니다.
<gazebo reference="lidar_link">
<sensor name="lidar" type="ray">
...any parameters common to all sensor types...
<ray>
...any parameters specific to the ray sensor...
</ray>
<plugin name="laser_controller" filename="libgazebo_ros_ray_sensor.so">
...any parameters specific to the ROS ray sensor plugin...
</plugin>
</sensor>
</gazebo>
향후 프로젝트에서 다양한 센서 유형을 다루겠지만 더 많은 정보가 필요하면 다음을 확인하세요.
Last updated