콘텐츠로 바로가기

now0930 일지

이런저런 생각

  • 홈
  • 비공개
  • 강좌
  • 잔여 작업 조회
  • 위치

sdf? urdf?

urdf로 모델을 그리려면 각 좌표값를 모두 알아야 한다. 수치를 넣어야 되는데 시간 많이 걸린다. 다행히도 gazebo가 제공하는 model 에디터로 사각형, 바퀴 등 을 쉽게 그릴 수 있다. 원하는 그림이 없다면 무료 프로그램인 blender로 스케치한 다음 stl, dae 파일로 export 후 gazebo에서 import하면 만족도가 높아진다.

그런데 ros가 urdf를 정식으로 지원하고, sdf는 지원하지 않는 듯 하다. sdf만으로는 joint_state_publisher, robot_state_publisher를 제대로 이용할 수 없다. sdf와 urdf는 사용 분야가 다르고, 한 형식이 확장하는 개념은 아니다. ros에서 모델을 불러 제어하기 위해서는 어떻게든 sdf를 urdf로 바꿔야 한다고 결론을 냈다. 다행히 관련 스크립트를 찾을 수 있었다.

https://ik-test.readthedocs.io/en/latest/pysdf/

실행하면 sdf 1.7은 지원하지 않지만, parse.py의 supported_sdf_versions에 1.7을 추가하면 큰 무리없이 사용할 수 있다.(오픈소스의 위대함!!)

 22 mesh_path_env_name='MESH_WORKSPACE_PATH'
 23 if mesh_path_env_name in os.environ:
 24   catkin_ws_path = os.environ[mesh_path_env_name]
 25 else:
 26   catkin_ws_path = os.path.expanduser('~') + '/catkin_ws/src/'
 27 supported_sdf_versions = [1.4, 1.5, 1.6, 1.7]

mesh 파일 부분을 넣는 부분이 잘 안되는데, stl 위치를 export로 넣어주면 된다. 찾은 stl, dae 모두 OR로 넣어주는데, 해당 부분을 찾아 정확하게 수정해야 한다.

now0930@amd2004:~/ros_test/workspace/src/battery_agv$ tree
.
├── CMakeLists.txt
├── include
│   └── battery_agv
├── launch
│   ├── robot_description.launch
│   └── staion.launch
├── meshes
│   ├── axis_gear.stl
│   ├── stepperMotor.stl
│   └── stepperMotor3.stl
├── models
│   └── AGV
│       ├── axis_gear.stl
│       ├── model.config
│       ├── model.sdf
│       ├── stepperMotor.stl
│       └── stepperMotor3.stl
├── package.xml
├── src
│   └── red_green_light.py
├── urdf
│   ├── agv.urdf
│   └── agv.xacro
└── worlds
    └── testbed2

9 directories, 16 files
<?xml version="1.0"?>
<robot xmlns:xacro="http://www.ros.org/wiki/xacro" name="AGV">
  <joint name="AGV__link_bottomplate_JOINT_0" type="fixed">
    <parent link="AGV__link_bottomplate"/>
    <child link="AGV__link_topplate"/>
    <origin xyz="0      -0.00667  1.86611" rpy="1.5708 0     0.01"/>
    <axis xyz="0 0 0"/>
    <limit lower="0" upper="0" effort="0" velocity="0"/>
  </joint>
  <joint name="AGV__link_bottomplate_JOINT_2" type="fixed">
    <parent link="AGV__link_bottomplate"/>
    <child link="AGV__link_leftplate"/>
    <origin xyz="-8.80000e-04 -4.18110e-01  1.42999e+00" rpy="0.e+00  0.e+00 -2.e-05"/>
    <axis xyz="0 0 0"/>
    <limit lower="0" upper="0" effort="0" velocity="0"/>
  </joint>
  <joint name="AGV__link_bottomplate_JOINT_3" type="fixed">
    <parent link="AGV__link_bottomplate"/>
    <child link="AGV__link_rightplate"/>
    <origin xyz="8.80000e-04 4.12490e-01 1.42998e+00" rpy="-3.14159  0       0"/>
    <axis xyz="0 0 0"/>
    <limit lower="0" upper="0" effort="0" velocity="0"/>
  </joint>
  <joint name="AGV__link_bottomplate_JOINT_4" type="revolute">
    <parent link="AGV__link_bottomplate"/>
    <child link="AGV__link_leftwheel"/>
    <origin xyz="0.73669 -0.27702  1.05254" rpy="1.5708 0     0"/>
    <axis xyz="0 0 1"/>
    <limit lower="-1.79769e+308" upper="1.79769e+308" effort="-1.0" velocity="-1.0"/>
  </joint>
  <joint name="AGV__link_bottomplate_JOINT_5" type="revolute">
    <parent link="AGV__link_bottomplate"/>
    <child link="AGV__link_rightwheel"/>
    <origin xyz="0.73669 0.27702 1.05434" rpy="1.5708 0     0"/>
    <axis xyz="0 0 1"/>
    <limit lower="-1.79769e+308" upper="1.79769e+308" effort="-1.0" velocity="-1.0"/>
  </joint>
  <joint name="AGV__link_bottomplate_JOINT_6" type="fixed">
    <parent link="AGV__link_bottomplate"/>
    <child link="AGV__link_rightwheel0"/>
    <origin xyz="-0.73669  0.27702  1.05254" rpy="1.5708 0     0"/>
    <axis xyz="0 0 0"/>
    <limit lower="0" upper="0" effort="0" velocity="0"/>
  </joint>
  <joint name="AGV__link_bottomplate_JOINT_7" type="fixed">
    <parent link="AGV__link_bottomplate"/>
    <child link="AGV__link_leftwheel0"/>
    <origin xyz="-0.73669 -0.27702  1.05254" rpy="1.5708 0     0"/>
    <axis xyz="0 0 0"/>
    <limit lower="0" upper="0" effort="0" velocity="0"/>
  </joint>
  <joint name="AGV__link_loadingplate_JOINT_2" type="fixed">
    <parent link="AGV__link_loadingplate"/>
    <child link="AGV__link_rightgear"/>
    <origin xyz="0.87839 -0.40904 -0.19812" rpy="-1.57395e+00 -3.18700e-02  1.20000e-04"/>
    <axis xyz="0 0 0"/>
    <limit lower="0" upper="0" effort="0" velocity="0"/>
  </joint>
  <joint name="AGV__link_loadingplate_JOINT_3" type="fixed">
    <parent link="AGV__link_loadingplate"/>
    <child link="AGV__link_leftgear"/>
    <origin xyz="0.86434 -0.40766  0.24228" rpy="-1.57395e+00 -3.18700e-02  1.20000e-04"/>
    <axis xyz="0 0 0"/>
    <limit lower="0" upper="0" effort="0" velocity="0"/>
  </joint>
  <joint name="AGV__link_loadingplate_JOINT_4" type="fixed">
    <parent link="AGV__link_loadingplate"/>
    <child link="AGV__link_rightgear2"/>
    <origin xyz="-0.86391 -0.40925 -0.25368" rpy="-1.57395e+00 -3.18700e-02  1.20000e-04"/>
    <axis xyz="0 0 0"/>
    <limit lower="0" upper="0" effort="0" velocity="0"/>
  </joint>
  <joint name="AGV__link_loadingplate_JOINT_5" type="fixed">
    <parent link="AGV__link_loadingplate"/>
    <child link="AGV__link_leftgear2"/>
    <origin xyz="-0.87795 -0.40787  0.18672" rpy="-1.57395e+00 -3.18700e-02  1.20000e-04"/>
    <axis xyz="0 0 0"/>
    <limit lower="0" upper="0" effort="0" velocity="0"/>
  </joint>
  <joint name="AGV__link_topplate_JOINT_0" type="fixed">
    <parent link="AGV__link_topplate"/>
    <child link="AGV__link_motor"/>
    <origin xyz="-0.01114  0.04217 -0.43284" rpy="-1.00e-05  2.08e-03  0.00e+00"/>
    <axis xyz="0 0 0"/>
    <limit lower="0" upper="0" effort="0" velocity="0"/>
  </joint>
  <joint name="AGV__link_topplate_JOINT_6" type="prismatic">
    <parent link="AGV__link_topplate"/>
    <child link="AGV__link_loadingplate"/>
    <origin xyz="0.0000e+00 4.0032e-01 3.1000e-04" rpy="3.150e-03  2.187e-02 -2.000e-05"/>
    <axis xyz="0 0 1"/>
    <limit lower="0.0" upper="0.3" effort="-1.0" velocity="-1.0"/>
  </joint>
  <link name="AGV__link_leftplate">
    <inertial>
      <mass value="432.31"/>
      <origin xyz="0 0 0" rpy="0 0 0"/>
      <inertia ixx="26.0634" ixy="0" ixz="0" iyy="184.903" iyz="0" izz="158.909"/>
    </inertial>
    <collision name="AGV__collision">
      <origin xyz="0 0 0" rpy="0 0 0"/>
      <geometry>
        <box size="2.1 0.01 0.85"/>
      </geometry>
    </collision>
    <visual name="AGV__visual">
      <origin xyz="0 0 0" rpy="0 0 0"/>
      <geometry>
        <box size="2.1 0.01 0.85"/>
      </geometry>
    </visual>
  </link>
  <link name="AGV__link_bottomplate">
    <inertial>
      <mass value="432.31"/>
      <origin xyz="0 0 0" rpy="0 0 0"/>
      <inertia ixx="26.0634" ixy="0" ixz="0" iyy="184.903" iyz="0" izz="158.909"/>
    </inertial>
    <collision name="AGV__collision">
      <origin xyz="0 0 1" rpy="1.5708 0     0"/>
      <geometry>
        <box size="2.1 0.01 0.85"/>
      </geometry>
    </collision>
    <visual name="AGV__visual">
      <origin xyz="0 0 1" rpy="1.5708 0     0"/>
      <geometry>
        <box size="2.1 0.01 0.85"/>
      </geometry>
    </visual>
  </link>
  <link name="AGV__link_leftgear">
    <inertial>
      <mass value="20"/>
      <origin xyz="0 0 0" rpy="0 0 0"/>
      <inertia ixx="0" ixy="0" ixz="0" iyy="0" iyz="0" izz="0"/>
    </inertial>
    <collision name="AGV__collision">
      <origin xyz="0 0 0" rpy="0 0 0"/>
      <geometry>
        <mesh filename="package://battery_agv/meshes/axis_gear.stl" scale="1 1 1"/>
      </geometry>
    </collision>
    <visual name="AGV__visual">
      <origin xyz="0 0 0" rpy="0 0 0"/>
      <geometry>
        <mesh filename="package://battery_agv/meshes/axis_gear.stl" scale="1 1 1"/>
      </geometry>
    </visual>
  </link>
  <link name="AGV__link_leftgear2">
    <inertial>
      <mass value="20"/>
      <origin xyz="0 0 0" rpy="0 0 0"/>
      <inertia ixx="0" ixy="0" ixz="0" iyy="0" iyz="0" izz="0"/>
    </inertial>
    <collision name="AGV__collision">
      <origin xyz="0 0 0" rpy="0 0 0"/>
      <geometry>
        <mesh filename="package://battery_agv/meshes/axis_gear.stl" scale="1 1 1"/>
      </geometry>
    </collision>
    <visual name="AGV__visual">
      <origin xyz="0 0 0" rpy="0 0 0"/>
      <geometry>
        <mesh filename="package://battery_agv/meshes/axis_gear.stl" scale="1 1 1"/>
      </geometry>
    </visual>
  </link>
  <link name="AGV__link_leftwheel">
    <inertial>
      <mass value="10.3358"/>
      <origin xyz="0 0 0" rpy="0 0 0"/>
      <inertia ixx="0.107579" ixy="0" ixz="0" iyy="0.107579" iyz="0" izz="0.206717"/>
    </inertial>
    <collision name="AGV__collision">
      <origin xyz="0 0 0" rpy="0 0 0"/>
      <geometry>
        <cylinder radius="0.2" length="0.07"/>
      </geometry>
    </collision>
    <visual name="AGV__visual">
      <origin xyz="0 0 0" rpy="0 0 0"/>
      <geometry>
        <cylinder radius="0.2" length="0.07"/>
      </geometry>
    </visual>
  </link>
  <link name="AGV__link_leftwheel0">
    <inertial>
      <mass value="10.3358"/>
      <origin xyz="0 0 0" rpy="0 0 0"/>
      <inertia ixx="0.107579" ixy="0" ixz="0" iyy="0.107579" iyz="0" izz="0.206717"/>
    </inertial>
    <collision name="AGV__collision">
      <origin xyz="0 0 0" rpy="0 0 0"/>
      <geometry>
        <cylinder radius="0.2" length="0.07"/>
      </geometry>
    </collision>
    <visual name="AGV__visual">
      <origin xyz="0 0 0" rpy="0 0 0"/>
      <geometry>
        <cylinder radius="0.2" length="0.07"/>
      </geometry>
    </visual>
  </link>
  <link name="AGV__link_loadingplate">
    <inertial>
      <mass value="432.31"/>
      <origin xyz="0 0 0" rpy="0 0 0"/>
      <inertia ixx="26.0634" ixy="0" ixz="0" iyy="184.903" iyz="0" izz="158.909"/>
    </inertial>
    <collision name="AGV__collision">
      <origin xyz="0 0 0" rpy="0 0 0"/>
      <geometry>
        <box size="2.1 0.01 0.85"/>
      </geometry>
    </collision>
    <visual name="AGV__visual">
      <origin xyz="0 0 0" rpy="0 0 0"/>
      <geometry>
        <box size="2.1 0.01 0.85"/>
      </geometry>
    </visual>
  </link>
  <link name="AGV__link_motor">
    <inertial>
      <mass value="1"/>
      <origin xyz="0 0 0" rpy="0 0 0"/>
      <inertia ixx="0.166667" ixy="0" ixz="0" iyy="0.166667" iyz="0" izz="0.166667"/>
    </inertial>
    <collision name="AGV__collision">
      <origin xyz="0 0 0" rpy="0 0 0"/>
      <geometry>
        <mesh filename="package://battery_agv/meshes/stepperMotor3.stl" scale="1 1 1"/>
      </geometry>
    </collision>
    <visual name="AGV__visual">
      <origin xyz="0 0 0" rpy="0 0 0"/>
      <geometry>
        <mesh filename="package://battery_agv/meshes/stepperMotor3.stl" scale="1 1 1"/>
      </geometry>
    </visual>
  </link>
  <link name="AGV__link_rightgear">
    <inertial>
      <mass value="20"/>
      <origin xyz="0 0 0" rpy="0 0 0"/>
      <inertia ixx="0" ixy="0" ixz="0" iyy="0" iyz="0" izz="0"/>
    </inertial>
    <collision name="AGV__collision">
      <origin xyz="0 0 0" rpy="0 0 0"/>
      <geometry>
        <mesh filename="package://battery_agv/meshes/axis_gear.stl" scale="1 1 1"/>
      </geometry>
    </collision>
    <visual name="AGV__visual">
      <origin xyz="0 0 0" rpy="0 0 0"/>
      <geometry>
        <mesh filename="package://battery_agv/meshes/axis_gear.stl" scale="1 1 1"/>
      </geometry>
    </visual>
  </link>
  <link name="AGV__link_rightgear2">
    <inertial>
      <mass value="20"/>
      <origin xyz="0 0 0" rpy="0 0 0"/>
      <inertia ixx="0" ixy="0" ixz="0" iyy="0" iyz="0" izz="0"/>
    </inertial>
    <collision name="AGV__collision">
      <origin xyz="0 0 0" rpy="0 0 0"/>
      <geometry>
        <mesh filename="package://battery_agv/meshes/axis_gear.stl" scale="1 1 1"/>
      </geometry>
    </collision>
    <visual name="AGV__visual">
      <origin xyz="0 0 0" rpy="0 0 0"/>
      <geometry>
        <mesh filename="package://battery_agv/meshes/axis_gear.stl" scale="1 1 1"/>
      </geometry>
    </visual>
  </link>
  <link name="AGV__link_rightplate">
    <inertial>
      <mass value="432.31"/>
      <origin xyz="0 0 0" rpy="0 0 0"/>
      <inertia ixx="26.0634" ixy="0" ixz="0" iyy="184.903" iyz="0" izz="158.909"/>
    </inertial>
    <collision name="AGV__collision">
      <origin xyz="0 0 0" rpy="0 0 0"/>
      <geometry>
        <box size="2.1 0.01 0.85"/>
      </geometry>
    </collision>
    <visual name="AGV__visual">
      <origin xyz="0 0 0" rpy="0 0 0"/>
      <geometry>
        <box size="2.1 0.01 0.85"/>
      </geometry>
    </visual>
  </link>
  <link name="AGV__link_rightwheel">
    <inertial>
      <mass value="10.3358"/>
      <origin xyz="0 0 0" rpy="0 0 0"/>
      <inertia ixx="0.107579" ixy="0" ixz="0" iyy="0.107579" iyz="0" izz="0.206717"/>
    </inertial>
    <collision name="AGV__collision">
      <origin xyz="0 0 0" rpy="0 0 0"/>
      <geometry>
        <cylinder radius="0.2" length="0.07"/>
      </geometry>
    </collision>
    <visual name="AGV__visual">
      <origin xyz="0 0 0" rpy="0 0 0"/>
      <geometry>
        <cylinder radius="0.2" length="0.07"/>
      </geometry>
    </visual>
  </link>
  <link name="AGV__link_rightwheel0">
    <inertial>
      <mass value="10.3358"/>
      <origin xyz="0 0 0" rpy="0 0 0"/>
      <inertia ixx="0.107579" ixy="0" ixz="0" iyy="0.107579" iyz="0" izz="0.206717"/>
    </inertial>
    <collision name="AGV__collision">
      <origin xyz="0 0 0" rpy="0 0 0"/>
      <geometry>
        <cylinder radius="0.2" length="0.07"/>
      </geometry>
    </collision>
    <visual name="AGV__visual">
      <origin xyz="0 0 0" rpy="0 0 0"/>
      <geometry>
        <cylinder radius="0.2" length="0.07"/>
      </geometry>
    </visual>
  </link>
  <link name="AGV__link_topplate">
    <inertial>
      <mass value="432.31"/>
      <origin xyz="0 0 0" rpy="0 0 0"/>
      <inertia ixx="26.0634" ixy="0" ixz="0" iyy="184.903" iyz="0" izz="158.909"/>
    </inertial>
    <collision name="AGV__collision">
      <origin xyz="0 0 0" rpy="0   -0.01  0"/>
      <geometry>
        <box size="2.1 0.01 0.85"/>
      </geometry>
    </collision>
    <visual name="AGV__visual">
      <origin xyz="0 0 0" rpy="0   -0.01  0"/>
      <geometry>
        <box size="2.1 0.01 0.85"/>
      </geometry>
    </visual>
  </link>
</robot>

mesh는 package로 넣어야 하는 듯 한다. urdf로 R2D2를 만든 사람은 공간 감각이 뛰어나다.

http://wiki.ros.org/urdf/Tutorials/Building%20a%20Visual%20Robot%20Model%20with%20URDF%20from%20Scratch

잘 되다고 생각했으나, 문제가 있었다. 로봇이 제대로 움직이는지 확인하기 위해 joint_state_publisher를 실행해야 하는데, 프로세스가 죽는다. 왜 그런지 확인하기 어려웠는데, python 코드를 수정하여 어디에서 문제되는지 확인했다.

833 [rospy.simtime][INFO] 2022-10-09 13:09:14,685: initializing /clock core topic
834 [rospy.simtime][INFO] 2022-10-09 13:09:14,688: connected to core topic /clock
835 [rosout][INFO] 2022-10-09 13:09:14,760: Centering
836 [rospy.core][INFO] 2022-10-09 13:09:14,798: signal_shutdown [atexit]
837 [rospy.impl.masterslave][INFO] 2022-10-09 13:09:14,801: atexit

여기를 보면 centering 하다가 죽었음을 알았다. 왜 그런지 알 수 없으니, stdout에 표시된 코드를 보면 joint_state_publiser_gui의 182번 줄에서 죽었음을 확인했다.

QStandardPaths: wrong ownership on runtime directory /run/user/1000, 1000 instead of 0
QStandardPaths: wrong ownership on runtime directory /run/user/1000, 1000 instead of 0
Traceback (most recent call last):
  File "/opt/ros/noetic/lib/joint_state_publisher_gui/joint_state_publisher_gui", line 52, in <module>
    jsp_gui = joint_state_publisher_gui.JointStatePublisherGui("Node: " + rospy.get_name(),
  File "/opt/ros/noetic/lib/python3/dist-packages/joint_state_publisher_gui/__init__.py", line 125, in __init__
    self.center()
  File "/opt/ros/noetic/lib/python3/dist-packages/joint_state_publisher_gui/__init__.py", line 182, in center
    joint_info['slider'].setValue(self.valueToSlider(joint['zero'], joint))
TypeError: setValue(self, int): argument 1 has unexpected type 'float'
[joint_state_publisher_gui-1] process has died [pid 11275, exit code 1, cmd /opt/ros/noetic/lib/joint_state_publisher_gui/joint_state_publisher_gui __name:=joint_state_publisher_gui __log:=/root/.ros/log/b95997f0-47a6-11ed-a96e-2cf05d88e0ec/joint_state_publisher_gui-1.log].
log file: /root/.ros/log/b95997f0-47a6-11ed-a96e-2cf05d88e0ec/joint_state_publisher_gui-1*.log

해당부 코드를 고쳐보고, 로그를 출력시켜 보면

75     def center_event(self, event):
176         self.center()
177 
178     def center(self):
179         rospy.loginfo("Centering")
180         for name, joint_info in self.joint_map.items():
181             ##debug
182             rospy.loginfo("debug")
183             joint = joint_info['joint']
184             rospy.loginfo(joint)
185             joint_info['slider'].setValue(self.valueToSlider(joi    nt['zero'], joint))

결과를 다시 보면 argument 1이 min으로 들어온 -1.79..e+308임을 알았다.

866 [rosout][INFO] 2022-10-09 13:13:17,733: Centering
867 [rosout][INFO] 2022-10-09 13:13:17,735: debug
868 [rosout][INFO] 2022-10-09 13:13:17,736: {'min': -1.79769e+308, 'max': 1.79769e+308, 'zero': 0, 'position': 0}
869 [rospy.core][INFO] 2022-10-09 13:13:17,780: signal_shutdown [atexit]

limit를 적은 값으로 수정하면 된다.

 24   <joint name="AGV__link_bottomplate_JOINT_4" type="revolute">
 25     <parent link="AGV__link_bottomplate"/>
 26     <child link="AGV__link_leftwheel"/>
 27     <origin xyz="0.73669 -0.27702  1.05254" rpy="1.5708 0     0"/>
 28     <axis xyz="0 0 1"/>
 29     <limit lower="-0.2" upper="0.5" effort="-1.0" velocity="-1.0"/>
 30   </joint>   

그런데 해당 부분은 바퀴라서 type을 continuous로 수정해도 된다. sdf가 continuous type을 선택할 수 없었다. 이거 찾는다고 거의 4시간을 썼다. TF 표시는 gazebo가 실행되면 제대로 표시된다.

이 글 공유하기:

  • Tweet
발행일 2022-10-09글쓴이 이대원
카테고리 ROS 태그 mesh, ros, sdf, stl, urdf

댓글 남기기응답 취소

이 사이트는 Akismet을 사용하여 스팸을 줄입니다. 댓글 데이터가 어떻게 처리되는지 알아보세요.

글 내비게이션

이전 글

gmapping slam으로 지도 만들기

다음 글

sdf, urdf, blender로 모델 만들기

2025 7월
일 월 화 수 목 금 토
 12345
6789101112
13141516171819
20212223242526
2728293031  
6월    

최신 글

  • DC 모터 모델링 2025-07-03
  • 모터 개론 2025-06-22
  • common mode, differential mode 2025-05-11
  • signal conditioner, 신호 처리기 2025-05-10
  • strain gage 2025-05-09

카테고리

  • 산업계측제어기술사
  • 삶 자국
    • 책과 영화
    • 투자
  • 생활코딩
    • LEGO
    • ROS
    • tensorflow
  • 전기기사
  • 피아노 악보

메타

  • 로그인
  • 엔트리 피드
  • 댓글 피드
  • WordPress.org

페이지

  • 소개
  • 잔여 작업 조회
    • 작업 추가
    • 작업의 사진 조회
    • 작업 수정 페이지
  • 사진
    • GPS 입력된 사진
    • 사진 조회
  • 위치
    • 하기 휴가 방문지
    • 해외 출장

태그

android bash c docker driver FSM gps java kernel LEGO linux mysql network program opcua open62541 plc programmers python raspberry reinforcementLearning ros state space system program tensorflow transfer function 경제 미국 민수 삼국지 세계사 실기 에너지 역사 유전자 일본 임베디드 리눅스 전기기사 조선 중국 채윤 코딩 테스트 통계 한국사 한국어

팔로우하세요

  • Facebook
now0930 일지
WordPress로 제작.
 

댓글 로드중...