gazebo
forklift model 만들기 ( gz sim )
정지홍
2025. 3. 26. 10:20
1. 우선 작업할 폴더를 만들자.
mkdir -p ~/gazebo_ws/src
cd ~/gazebo_ws
colcon build
source install/setup.bash
2. 환경을 정의할 world파일을 만들자
- 2-1. 우선 src에서 패키지를 생성하자.
cd ~/gazebo_ws/src
ros2 pkg create --build-type ament_python fork --dependencies rclpy gazebo_ros
- 2-2. 그리고 worlds.sdf파일을 만들자. ( 위치는 fork패키지 안에 worlds디렉토리를 만들고 거기에 작성하자. )
<?xml version="1.0" ?>
<sdf version="1.7">
<world name="default">
<include>
<uri>model://sun</uri>
</include>
<include>
<uri>model://ground_plane</uri>
</include>
<include>
<uri>models://fork</uri>
<pose>0 0 0 0 0 0</pose>
</include>
</world>
</sdf>
3. model을 만들자.
- 3-1. 우선 /home/jeongjihong/gazebo/src/fork/models/fork 과 같은 경로에 model파일을 만들거니, 디렉토리 생성.
- 3-2. 차례대로 model.sdf와 model.config를 작성.
- 3-3. 모델을 찾을수있게, 모델 경로를 export해주자.
<?xml version='1.0' encoding='UTF-8'?>
<sdf version="1.7">
<model name="forklift">
<static>false</static>
<!-- Base -->
<link name="base_link">
<pose>0 0 0.55 0 0 0</pose>
<collision name="collision">
<geometry>
<box><size>1.4 0.8 0.5</size></box>
</geometry>
</collision>
<visual name="visual">
<geometry>
<box><size>1.4 0.8 0.5</size></box>
</geometry>
<material>
<diffuse>0.2 1.0 0.2 1</diffuse>
</material>
</visual>
<inertial>
<mass>500.0</mass>
<inertia>
<ixx>10</ixx>
<iyy>10</iyy>
<izz>10</izz>
<ixy>0</ixy>
<ixz>0</ixz>
<iyz>0</iyz>
</inertia>
</inertial>
</link>
<!-- Mast -->
<link name="mast_link">
<pose>0.7 0 1.3 0 0 0</pose>
<collision name="collision">
<geometry><box><size>0.2 0.2 2.0</size></box></geometry>
</collision>
<visual name="visual">
<geometry><box><size>0.2 0.2 2.0</size></box></geometry>
<material><diffuse>0.1 0.1 0.1 1</diffuse></material>
</visual>
</link>
<!-- base_link와 mast_link를 고정해서 연결-->
<joint name="mast_fixed_joint" type="fixed">
<parent>base_link</parent>
<child>mast_link</child>
</joint>
<!-- Carriage ( 포크 지지대 ) -->
<link name="carriage_link">
<pose>0.8 0 0.8 0 0 0</pose>
<collision name="collision">
<geometry><box><size>0.6 0.3 0.1</size></box></geometry>
</collision>
<visual name="visual">
<geometry><box><size>0.6 0.3 0.1</size></box></geometry>
<material><diffuse>0.1 0.1 0.1 1</diffuse></material>
</visual>
</link>
<!-- mast_link와 carriage_link를 고정해서 연결-->
<joint name="carriage_joint" type="fixed">
<parent>mast_link</parent>
<child>carriage_link</child>
</joint>
<!-- Forks -->
<link name="fork_left_link">
<pose>0.95 0.15 0.3 0 0 0</pose>
<collision name="collision">
<geometry><box><size>0.8 0.05 0.05</size></box></geometry>
</collision>
<visual name="visual">
<geometry><box><size>0.8 0.05 0.05</size></box></geometry>
<material><diffuse>0.2 1.0 0.2 1</diffuse></material>
</visual>
</link>
<link name="fork_right_link">
<pose>0.95 -0.15 0.3 0 0 0</pose>
<collision name="collision">
<geometry><box><size>0.8 0.05 0.05</size></box></geometry>
</collision>
<visual name="visual">
<geometry><box><size>0.8 0.05 0.05</size></box></geometry>
<material><diffuse>0.2 1.0 0.2 1</diffuse></material>
</visual>
</link>
<joint name="fork_left_fixed" type="fixed">
<parent>carriage_link</parent>
<child>fork_left_link</child>
</joint>
<joint name="fork_right_fixed" type="fixed">
<parent>carriage_link</parent>
<child>fork_right_link</child>
</joint>
<!-- Wheels (with 90-degree rotation) -->
<link name="wheel_front_left">
<pose>0.4 0.39 0.15 1.5708 0 0</pose>
<collision name="collision">
<geometry><cylinder><radius>0.15</radius><length>0.05</length></cylinder></geometry>
</collision>
<visual name="visual">
<geometry><cylinder><radius>0.15</radius><length>0.05</length></cylinder></geometry>
<material><diffuse>0.1 0.1 0.1 1</diffuse></material>
</visual>
</link>
<link name="wheel_front_right">
<pose>0.4 -0.39 0.15 1.5708 0 0</pose>
<collision name="collision">
<geometry><cylinder><radius>0.15</radius><length>0.05</length></cylinder></geometry>
</collision>
<visual name="visual">
<geometry><cylinder><radius>0.15</radius><length>0.05</length></cylinder></geometry>
<material><diffuse>0.1 0.1 0.1 1</diffuse></material>
</visual>
</link>
<link name="wheel_rear_left">
<pose>-0.4 0.39 0.15 1.5708 0 0</pose>
<collision name="collision">
<geometry><cylinder><radius>0.15</radius><length>0.05</length></cylinder></geometry>
</collision>
<visual name="visual">
<geometry><cylinder><radius>0.15</radius><length>0.05</length></cylinder></geometry>
<material><diffuse>0.1 0.1 0.1 1</diffuse></material>
</visual>
</link>
<link name="wheel_rear_right">
<pose>-0.4 -0.39 0.15 1.5708 0 0</pose>
<collision name="collision">
<geometry><cylinder><radius>0.15</radius><length>0.05</length></cylinder></geometry>
</collision>
<visual name="visual">
<geometry><cylinder><radius>0.15</radius><length>0.05</length></cylinder></geometry>
<material><diffuse>0.1 0.1 0.1 1</diffuse></material>
</visual>
</link>
<!-- Wheel Joints -->
<joint name="front_left_wheel_joint" type="revolute">
<parent>base_link</parent>
<child>wheel_front_left</child>
<axis>
<xyz>0 0 1</xyz>
<limit>
<lower>-1e16</lower>
<upper>1e16</upper>
<effort>1e6</effort></limit>
</axis>
</joint>
<joint name="front_right_wheel_joint" type="revolute">
<parent>base_link</parent>
<child>wheel_front_right</child>
<axis>
<xyz>0 0 1</xyz>
<limit>
<lower>-1e16</lower>
<upper>1e16</upper>
<effort>1e6</effort></limit>
</axis>
</joint>
<joint name="rear_left_wheel_joint" type="fixed">
<parent>base_link</parent>
<child>wheel_rear_left</child>
</joint>
<joint name="rear_right_wheel_joint" type="fixed">
<parent>base_link</parent>
<child>wheel_rear_right</child>
</joint>
<plugin name="gz::sim::systems::DiffDrive" filename="libgz-sim-diff-drive-system.so">
<left_joint>front_left_wheel_joint</left_joint>
<right_joint>front_right_wheel_joint</right_joint>
<wheel_separation>0.5</wheel_separation>
<wheel_radius>0.1</wheel_radius>
<topic>cmd_vel</topic>
<odom_publish_frequency>10</odom_publish_frequency>
<odom_frame>odom</odom_frame>
<odom_topic>odom</odom_topic>
<publish_odom>true</publish_odom>
<publish_tf>false</publish_tf>
</plugin>
</model>
</sdf>
<?xml version="1.0" ?>
<model>
<name>forklift</name>
<version>1.0</version>
<sdf version="1.7">model.sdf</sdf>
<author>
<name>Jeongjihong</name>
<email>example@email.com</email>
</author>
<description>Basic mobile robot with differential drive</description>
</model>
export GZ_SIM_RESOURCE_PATH=~/gazebo_ws/src/fork/models:$GZ_SIM_RESOURCE_PATH
4. 실행 gz sim worlds.sdf

gz topic -t /cmd_vel -m gz.msgs.Twist -p 'linear: {x: 1.0}'
run_fork.sh
0.00MB
model.config
0.00MB
worlds.sdf
0.00MB
model.sdf
0.01MB