Gazebo model spawn 기능 구현

Min woo Kim·2023년 9월 19일

구글링을 통해 좋은 체커보드 sdf 파일을 찾았다.

하지만 캘리브레이션할때마다 수동으로 체스보드를 배치해주기는 너무나도 귀찮지 않을까?
그런 당신을 위해 준비했다..!

Gazebo model spawn node

rosrun gazebo_ros spawn_model -file /root/catkin_ws/src/auturbo_ma-ah_gazebo/models/calibration_board/model.sdf -sdf -model chessboard -y 0.2 -x -0.3 -z 0.5

gazebo_ros 패키지에는 spawn_model이라는 노드가 존재하는데 말 그대로 urdf, sdf등으로 만들어진 모델을 gazebo map상에 배치 할 수 있는 노드이다.

소스를 보면 다양한 옵션을 확인 할 수 있다. 우리가 사용할 주요 옵션은 다음과 같다.

  • -file : sdf 파일의 경로
  • -sdf : sdf 파일임을 명시
  • -model : gazebo상에서 모델의 이름을 지정

이제 위 spawn_model 노드를 roslaunch에서 적절한 인자를 넣어서 실행하면 된다.

turtlebot3_calibration.launch

<launch>
  <env name="GAZEBO_RESOURCE_PATH" value="$(find auturbo_ma-ah_gazebo)/models/autorace/ground_picture" />

  <arg name="x_pos" default="0.8"/>
  <arg name="y_pos" default="-1.747"/>
  <arg name="z_pos" default="0"/>  

  <!-- chessboard translation -->
  <arg name="chessboard_x_pos" default="0.3"/>
  <arg name="chessboard_y_pos" default="0.2"/>
  <arg name="chessboard_z_pos" default="0.5"/>  

  <include file="$(find gazebo_ros)/launch/empty_world.launch">
    <arg name="world_name" value="$(find auturbo_ma-ah_gazebo)/worlds/turtlebot3_autorace_2020.world" />
    <arg name="paused" value="false"/>
    <arg name="use_sim_time" value="true"/>
    <arg name="gui" value="true"/>
    <arg name="headless" value="false"/>
    <arg name="debug" value="false"/>
  </include>  

  <param name="robot_description" command="$(find xacro)/xacro --inorder $(find auturbo_ma-ah_gazebo)/urdf/turtlebot3_burger.urdf.xacro" />
  <node pkg="gazebo_ros" type="spawn_model" name="spawn_urdf" args="-urdf -model autorace -x $(arg x_pos) -y $(arg y_pos) -z $(arg z_pos) -param robot_description" />

  <!-- chessboard add -->
  <arg name="chessboard_sdf_path" default="/root/catkin_ws/src/auturbo_ma-ah_gazebo/models/calibration_board/model.sdf" />
  <node pkg="gazebo_ros" type="spawn_model" name="spawn_sdf" output="screen" args="-file $(arg chessboard_sdf_path) -sdf -model chessboard -x $(arg chessboard_x_pos) -y $(arg chessboard_y_pos) -z $(arg chessboard_z_pos)" />
</launch>

이걸 3번더 반복하면 아래 사진처럼 동서남북으로 배치 완료!

profile
머신러닝과 로보틱스를 좋아합니다.

0개의 댓글