{"id":5218,"date":"2022-10-09T15:25:39","date_gmt":"2022-10-09T06:25:39","guid":{"rendered":"https:\/\/now0930.pe.kr\/wordpress\/?p=5218"},"modified":"2022-10-09T23:28:40","modified_gmt":"2022-10-09T14:28:40","slug":"sdf-urdf","status":"publish","type":"post","link":"https:\/\/now0930.pe.kr\/wordpress\/sdf-urdf\/","title":{"rendered":"sdf? urdf?"},"content":{"rendered":"\n<p>urdf\ub85c \ubaa8\ub378\uc744 \uadf8\ub9ac\ub824\uba74 \uac01 \uc88c\ud45c\uac12\ub97c \ubaa8\ub450 \uc54c\uc544\uc57c \ud55c\ub2e4. \uc218\uce58\ub97c \ub123\uc5b4\uc57c \ub418\ub294\ub370 \uc2dc\uac04 \ub9ce\uc774 \uac78\ub9b0\ub2e4. \ub2e4\ud589\ud788\ub3c4 gazebo\uac00 \uc81c\uacf5\ud558\ub294 model \uc5d0\ub514\ud130\ub85c \uc0ac\uac01\ud615, \ubc14\ud034 \ub4f1 \uc744 \uc27d\uac8c \uadf8\ub9b4 \uc218 \uc788\ub2e4. \uc6d0\ud558\ub294 \uadf8\ub9bc\uc774 \uc5c6\ub2e4\uba74 \ubb34\ub8cc \ud504\ub85c\uadf8\ub7a8\uc778 blender\ub85c \uc2a4\ucf00\uce58\ud55c \ub2e4\uc74c stl, dae \ud30c\uc77c\ub85c export \ud6c4 gazebo\uc5d0\uc11c import\ud558\uba74 \ub9cc\uc871\ub3c4\uac00 \ub192\uc544\uc9c4\ub2e4.<\/p>\n\n\n\n<p>\uadf8\ub7f0\ub370 ros\uac00 urdf\ub97c \uc815\uc2dd\uc73c\ub85c \uc9c0\uc6d0\ud558\uace0, sdf\ub294 \uc9c0\uc6d0\ud558\uc9c0 \uc54a\ub294 \ub4ef \ud558\ub2e4. sdf\ub9cc\uc73c\ub85c\ub294 joint_state_publisher, robot_state_publisher\ub97c \uc81c\ub300\ub85c \uc774\uc6a9\ud560 \uc218 \uc5c6\ub2e4. <a href=\"https:\/\/newscrewdriver.com\/2018\/07\/31\/ros-notes-urdf-vs-gazebo-sdf\/\">sdf\uc640 urdf\ub294 \uc0ac\uc6a9 \ubd84\uc57c\uac00 \ub2e4\ub974\uace0, \ud55c \ud615\uc2dd\uc774 \ud655\uc7a5\ud558\ub294 \uac1c\ub150\uc740 \uc544\ub2c8\ub2e4.<\/a> ros\uc5d0\uc11c \ubaa8\ub378\uc744 \ubd88\ub7ec \uc81c\uc5b4\ud558\uae30 \uc704\ud574\uc11c\ub294 \uc5b4\ub5bb\uac8c\ub4e0 sdf\ub97c urdf\ub85c \ubc14\uafd4\uc57c \ud55c\ub2e4\uace0 \uacb0\ub860\uc744 \ub0c8\ub2e4. \ub2e4\ud589\ud788 \uad00\ub828 \uc2a4\ud06c\ub9bd\ud2b8\ub97c \ucc3e\uc744 \uc218 \uc788\uc5c8\ub2e4.<\/p>\n\n\n\n<p><a href=\"https:\/\/ik-test.readthedocs.io\/en\/latest\/pysdf\/\">https:\/\/ik-test.readthedocs.io\/en\/latest\/pysdf\/<\/a><\/p>\n\n\n\n<p>\uc2e4\ud589\ud558\uba74 sdf 1.7\uc740 \uc9c0\uc6d0\ud558\uc9c0 \uc54a\uc9c0\ub9cc, parse.py\uc758 supported_sdf_versions\uc5d0 1.7\uc744 \ucd94\uac00\ud558\uba74 \ud070 \ubb34\ub9ac\uc5c6\uc774 \uc0ac\uc6a9\ud560 \uc218 \uc788\ub2e4.(\uc624\ud508\uc18c\uc2a4\uc758 \uc704\ub300\ud568!!)<\/p>\n\n\n\n<pre class=\"EnlighterJSRAW\" data-enlighter-language=\"generic\" data-enlighter-theme=\"\" data-enlighter-highlight=\"\" data-enlighter-linenumbers=\"\" data-enlighter-lineoffset=\"\" data-enlighter-title=\"\" data-enlighter-group=\"\"> 22 mesh_path_env_name='MESH_WORKSPACE_PATH'\n 23 if mesh_path_env_name in os.environ:\n 24   catkin_ws_path = os.environ[mesh_path_env_name]\n 25 else:\n 26   catkin_ws_path = os.path.expanduser('~') + '\/catkin_ws\/src\/'\n 27 supported_sdf_versions = [1.4, 1.5, 1.6, 1.7]<\/pre>\n\n\n\n<p>mesh \ud30c\uc77c \ubd80\ubd84\uc744 \ub123\ub294 \ubd80\ubd84\uc774 \uc798 \uc548\ub418\ub294\ub370, stl \uc704\uce58\ub97c export\ub85c \ub123\uc5b4\uc8fc\uba74 \ub41c\ub2e4. \ucc3e\uc740  stl, dae \ubaa8\ub450 OR\ub85c \ub123\uc5b4\uc8fc\ub294\ub370, \ud574\ub2f9 \ubd80\ubd84\uc744 \ucc3e\uc544 \uc815\ud655\ud558\uac8c \uc218\uc815\ud574\uc57c \ud55c\ub2e4.<\/p>\n\n\n\n<pre class=\"EnlighterJSRAW\" data-enlighter-language=\"generic\" data-enlighter-theme=\"\" data-enlighter-highlight=\"\" data-enlighter-linenumbers=\"\" data-enlighter-lineoffset=\"\" data-enlighter-title=\"\" data-enlighter-group=\"\">now0930@amd2004:~\/ros_test\/workspace\/src\/battery_agv$ tree\n.\n\u251c\u2500\u2500 CMakeLists.txt\n\u251c\u2500\u2500 include\n\u2502\u00a0\u00a0 \u2514\u2500\u2500 battery_agv\n\u251c\u2500\u2500 launch\n\u2502\u00a0\u00a0 \u251c\u2500\u2500 robot_description.launch\n\u2502\u00a0\u00a0 \u2514\u2500\u2500 staion.launch\n\u251c\u2500\u2500 meshes\n\u2502\u00a0\u00a0 \u251c\u2500\u2500 axis_gear.stl\n\u2502\u00a0\u00a0 \u251c\u2500\u2500 stepperMotor.stl\n\u2502\u00a0\u00a0 \u2514\u2500\u2500 stepperMotor3.stl\n\u251c\u2500\u2500 models\n\u2502\u00a0\u00a0 \u2514\u2500\u2500 AGV\n\u2502\u00a0\u00a0     \u251c\u2500\u2500 axis_gear.stl\n\u2502\u00a0\u00a0     \u251c\u2500\u2500 model.config\n\u2502\u00a0\u00a0     \u251c\u2500\u2500 model.sdf\n\u2502\u00a0\u00a0     \u251c\u2500\u2500 stepperMotor.stl\n\u2502\u00a0\u00a0     \u2514\u2500\u2500 stepperMotor3.stl\n\u251c\u2500\u2500 package.xml\n\u251c\u2500\u2500 src\n\u2502\u00a0\u00a0 \u2514\u2500\u2500 red_green_light.py\n\u251c\u2500\u2500 urdf\n\u2502\u00a0\u00a0 \u251c\u2500\u2500 agv.urdf\n\u2502\u00a0\u00a0 \u2514\u2500\u2500 agv.xacro\n\u2514\u2500\u2500 worlds\n    \u2514\u2500\u2500 testbed2\n\n9 directories, 16 files<\/pre>\n\n\n\n<pre class=\"EnlighterJSRAW\" data-enlighter-language=\"generic\" data-enlighter-theme=\"\" data-enlighter-highlight=\"\" data-enlighter-linenumbers=\"\" data-enlighter-lineoffset=\"\" data-enlighter-title=\"\" data-enlighter-group=\"\">&lt;?xml version=\"1.0\"?>\n&lt;robot xmlns:xacro=\"http:\/\/www.ros.org\/wiki\/xacro\" name=\"AGV\">\n  &lt;joint name=\"AGV__link_bottomplate_JOINT_0\" type=\"fixed\">\n    &lt;parent link=\"AGV__link_bottomplate\"\/>\n    &lt;child link=\"AGV__link_topplate\"\/>\n    &lt;origin xyz=\"0      -0.00667  1.86611\" rpy=\"1.5708 0     0.01\"\/>\n    &lt;axis xyz=\"0 0 0\"\/>\n    &lt;limit lower=\"0\" upper=\"0\" effort=\"0\" velocity=\"0\"\/>\n  &lt;\/joint>\n  &lt;joint name=\"AGV__link_bottomplate_JOINT_2\" type=\"fixed\">\n    &lt;parent link=\"AGV__link_bottomplate\"\/>\n    &lt;child link=\"AGV__link_leftplate\"\/>\n    &lt;origin xyz=\"-8.80000e-04 -4.18110e-01  1.42999e+00\" rpy=\"0.e+00  0.e+00 -2.e-05\"\/>\n    &lt;axis xyz=\"0 0 0\"\/>\n    &lt;limit lower=\"0\" upper=\"0\" effort=\"0\" velocity=\"0\"\/>\n  &lt;\/joint>\n  &lt;joint name=\"AGV__link_bottomplate_JOINT_3\" type=\"fixed\">\n    &lt;parent link=\"AGV__link_bottomplate\"\/>\n    &lt;child link=\"AGV__link_rightplate\"\/>\n    &lt;origin xyz=\"8.80000e-04 4.12490e-01 1.42998e+00\" rpy=\"-3.14159  0       0\"\/>\n    &lt;axis xyz=\"0 0 0\"\/>\n    &lt;limit lower=\"0\" upper=\"0\" effort=\"0\" velocity=\"0\"\/>\n  &lt;\/joint>\n  &lt;joint name=\"AGV__link_bottomplate_JOINT_4\" type=\"revolute\">\n    &lt;parent link=\"AGV__link_bottomplate\"\/>\n    &lt;child link=\"AGV__link_leftwheel\"\/>\n    &lt;origin xyz=\"0.73669 -0.27702  1.05254\" rpy=\"1.5708 0     0\"\/>\n    &lt;axis xyz=\"0 0 1\"\/>\n    &lt;limit lower=\"-1.79769e+308\" upper=\"1.79769e+308\" effort=\"-1.0\" velocity=\"-1.0\"\/>\n  &lt;\/joint>\n  &lt;joint name=\"AGV__link_bottomplate_JOINT_5\" type=\"revolute\">\n    &lt;parent link=\"AGV__link_bottomplate\"\/>\n    &lt;child link=\"AGV__link_rightwheel\"\/>\n    &lt;origin xyz=\"0.73669 0.27702 1.05434\" rpy=\"1.5708 0     0\"\/>\n    &lt;axis xyz=\"0 0 1\"\/>\n    &lt;limit lower=\"-1.79769e+308\" upper=\"1.79769e+308\" effort=\"-1.0\" velocity=\"-1.0\"\/>\n  &lt;\/joint>\n  &lt;joint name=\"AGV__link_bottomplate_JOINT_6\" type=\"fixed\">\n    &lt;parent link=\"AGV__link_bottomplate\"\/>\n    &lt;child link=\"AGV__link_rightwheel0\"\/>\n    &lt;origin xyz=\"-0.73669  0.27702  1.05254\" rpy=\"1.5708 0     0\"\/>\n    &lt;axis xyz=\"0 0 0\"\/>\n    &lt;limit lower=\"0\" upper=\"0\" effort=\"0\" velocity=\"0\"\/>\n  &lt;\/joint>\n  &lt;joint name=\"AGV__link_bottomplate_JOINT_7\" type=\"fixed\">\n    &lt;parent link=\"AGV__link_bottomplate\"\/>\n    &lt;child link=\"AGV__link_leftwheel0\"\/>\n    &lt;origin xyz=\"-0.73669 -0.27702  1.05254\" rpy=\"1.5708 0     0\"\/>\n    &lt;axis xyz=\"0 0 0\"\/>\n    &lt;limit lower=\"0\" upper=\"0\" effort=\"0\" velocity=\"0\"\/>\n  &lt;\/joint>\n  &lt;joint name=\"AGV__link_loadingplate_JOINT_2\" type=\"fixed\">\n    &lt;parent link=\"AGV__link_loadingplate\"\/>\n    &lt;child link=\"AGV__link_rightgear\"\/>\n    &lt;origin xyz=\"0.87839 -0.40904 -0.19812\" rpy=\"-1.57395e+00 -3.18700e-02  1.20000e-04\"\/>\n    &lt;axis xyz=\"0 0 0\"\/>\n    &lt;limit lower=\"0\" upper=\"0\" effort=\"0\" velocity=\"0\"\/>\n  &lt;\/joint>\n  &lt;joint name=\"AGV__link_loadingplate_JOINT_3\" type=\"fixed\">\n    &lt;parent link=\"AGV__link_loadingplate\"\/>\n    &lt;child link=\"AGV__link_leftgear\"\/>\n    &lt;origin xyz=\"0.86434 -0.40766  0.24228\" rpy=\"-1.57395e+00 -3.18700e-02  1.20000e-04\"\/>\n    &lt;axis xyz=\"0 0 0\"\/>\n    &lt;limit lower=\"0\" upper=\"0\" effort=\"0\" velocity=\"0\"\/>\n  &lt;\/joint>\n  &lt;joint name=\"AGV__link_loadingplate_JOINT_4\" type=\"fixed\">\n    &lt;parent link=\"AGV__link_loadingplate\"\/>\n    &lt;child link=\"AGV__link_rightgear2\"\/>\n    &lt;origin xyz=\"-0.86391 -0.40925 -0.25368\" rpy=\"-1.57395e+00 -3.18700e-02  1.20000e-04\"\/>\n    &lt;axis xyz=\"0 0 0\"\/>\n    &lt;limit lower=\"0\" upper=\"0\" effort=\"0\" velocity=\"0\"\/>\n  &lt;\/joint>\n  &lt;joint name=\"AGV__link_loadingplate_JOINT_5\" type=\"fixed\">\n    &lt;parent link=\"AGV__link_loadingplate\"\/>\n    &lt;child link=\"AGV__link_leftgear2\"\/>\n    &lt;origin xyz=\"-0.87795 -0.40787  0.18672\" rpy=\"-1.57395e+00 -3.18700e-02  1.20000e-04\"\/>\n    &lt;axis xyz=\"0 0 0\"\/>\n    &lt;limit lower=\"0\" upper=\"0\" effort=\"0\" velocity=\"0\"\/>\n  &lt;\/joint>\n  &lt;joint name=\"AGV__link_topplate_JOINT_0\" type=\"fixed\">\n    &lt;parent link=\"AGV__link_topplate\"\/>\n    &lt;child link=\"AGV__link_motor\"\/>\n    &lt;origin xyz=\"-0.01114  0.04217 -0.43284\" rpy=\"-1.00e-05  2.08e-03  0.00e+00\"\/>\n    &lt;axis xyz=\"0 0 0\"\/>\n    &lt;limit lower=\"0\" upper=\"0\" effort=\"0\" velocity=\"0\"\/>\n  &lt;\/joint>\n  &lt;joint name=\"AGV__link_topplate_JOINT_6\" type=\"prismatic\">\n    &lt;parent link=\"AGV__link_topplate\"\/>\n    &lt;child link=\"AGV__link_loadingplate\"\/>\n    &lt;origin xyz=\"0.0000e+00 4.0032e-01 3.1000e-04\" rpy=\"3.150e-03  2.187e-02 -2.000e-05\"\/>\n    &lt;axis xyz=\"0 0 1\"\/>\n    &lt;limit lower=\"0.0\" upper=\"0.3\" effort=\"-1.0\" velocity=\"-1.0\"\/>\n  &lt;\/joint>\n  &lt;link name=\"AGV__link_leftplate\">\n    &lt;inertial>\n      &lt;mass value=\"432.31\"\/>\n      &lt;origin xyz=\"0 0 0\" rpy=\"0 0 0\"\/>\n      &lt;inertia ixx=\"26.0634\" ixy=\"0\" ixz=\"0\" iyy=\"184.903\" iyz=\"0\" izz=\"158.909\"\/>\n    &lt;\/inertial>\n    &lt;collision name=\"AGV__collision\">\n      &lt;origin xyz=\"0 0 0\" rpy=\"0 0 0\"\/>\n      &lt;geometry>\n        &lt;box size=\"2.1 0.01 0.85\"\/>\n      &lt;\/geometry>\n    &lt;\/collision>\n    &lt;visual name=\"AGV__visual\">\n      &lt;origin xyz=\"0 0 0\" rpy=\"0 0 0\"\/>\n      &lt;geometry>\n        &lt;box size=\"2.1 0.01 0.85\"\/>\n      &lt;\/geometry>\n    &lt;\/visual>\n  &lt;\/link>\n  &lt;link name=\"AGV__link_bottomplate\">\n    &lt;inertial>\n      &lt;mass value=\"432.31\"\/>\n      &lt;origin xyz=\"0 0 0\" rpy=\"0 0 0\"\/>\n      &lt;inertia ixx=\"26.0634\" ixy=\"0\" ixz=\"0\" iyy=\"184.903\" iyz=\"0\" izz=\"158.909\"\/>\n    &lt;\/inertial>\n    &lt;collision name=\"AGV__collision\">\n      &lt;origin xyz=\"0 0 1\" rpy=\"1.5708 0     0\"\/>\n      &lt;geometry>\n        &lt;box size=\"2.1 0.01 0.85\"\/>\n      &lt;\/geometry>\n    &lt;\/collision>\n    &lt;visual name=\"AGV__visual\">\n      &lt;origin xyz=\"0 0 1\" rpy=\"1.5708 0     0\"\/>\n      &lt;geometry>\n        &lt;box size=\"2.1 0.01 0.85\"\/>\n      &lt;\/geometry>\n    &lt;\/visual>\n  &lt;\/link>\n  &lt;link name=\"AGV__link_leftgear\">\n    &lt;inertial>\n      &lt;mass value=\"20\"\/>\n      &lt;origin xyz=\"0 0 0\" rpy=\"0 0 0\"\/>\n      &lt;inertia ixx=\"0\" ixy=\"0\" ixz=\"0\" iyy=\"0\" iyz=\"0\" izz=\"0\"\/>\n    &lt;\/inertial>\n    &lt;collision name=\"AGV__collision\">\n      &lt;origin xyz=\"0 0 0\" rpy=\"0 0 0\"\/>\n      &lt;geometry>\n        &lt;mesh filename=\"package:\/\/battery_agv\/meshes\/axis_gear.stl\" scale=\"1 1 1\"\/>\n      &lt;\/geometry>\n    &lt;\/collision>\n    &lt;visual name=\"AGV__visual\">\n      &lt;origin xyz=\"0 0 0\" rpy=\"0 0 0\"\/>\n      &lt;geometry>\n        &lt;mesh filename=\"package:\/\/battery_agv\/meshes\/axis_gear.stl\" scale=\"1 1 1\"\/>\n      &lt;\/geometry>\n    &lt;\/visual>\n  &lt;\/link>\n  &lt;link name=\"AGV__link_leftgear2\">\n    &lt;inertial>\n      &lt;mass value=\"20\"\/>\n      &lt;origin xyz=\"0 0 0\" rpy=\"0 0 0\"\/>\n      &lt;inertia ixx=\"0\" ixy=\"0\" ixz=\"0\" iyy=\"0\" iyz=\"0\" izz=\"0\"\/>\n    &lt;\/inertial>\n    &lt;collision name=\"AGV__collision\">\n      &lt;origin xyz=\"0 0 0\" rpy=\"0 0 0\"\/>\n      &lt;geometry>\n        &lt;mesh filename=\"package:\/\/battery_agv\/meshes\/axis_gear.stl\" scale=\"1 1 1\"\/>\n      &lt;\/geometry>\n    &lt;\/collision>\n    &lt;visual name=\"AGV__visual\">\n      &lt;origin xyz=\"0 0 0\" rpy=\"0 0 0\"\/>\n      &lt;geometry>\n        &lt;mesh filename=\"package:\/\/battery_agv\/meshes\/axis_gear.stl\" scale=\"1 1 1\"\/>\n      &lt;\/geometry>\n    &lt;\/visual>\n  &lt;\/link>\n  &lt;link name=\"AGV__link_leftwheel\">\n    &lt;inertial>\n      &lt;mass value=\"10.3358\"\/>\n      &lt;origin xyz=\"0 0 0\" rpy=\"0 0 0\"\/>\n      &lt;inertia ixx=\"0.107579\" ixy=\"0\" ixz=\"0\" iyy=\"0.107579\" iyz=\"0\" izz=\"0.206717\"\/>\n    &lt;\/inertial>\n    &lt;collision name=\"AGV__collision\">\n      &lt;origin xyz=\"0 0 0\" rpy=\"0 0 0\"\/>\n      &lt;geometry>\n        &lt;cylinder radius=\"0.2\" length=\"0.07\"\/>\n      &lt;\/geometry>\n    &lt;\/collision>\n    &lt;visual name=\"AGV__visual\">\n      &lt;origin xyz=\"0 0 0\" rpy=\"0 0 0\"\/>\n      &lt;geometry>\n        &lt;cylinder radius=\"0.2\" length=\"0.07\"\/>\n      &lt;\/geometry>\n    &lt;\/visual>\n  &lt;\/link>\n  &lt;link name=\"AGV__link_leftwheel0\">\n    &lt;inertial>\n      &lt;mass value=\"10.3358\"\/>\n      &lt;origin xyz=\"0 0 0\" rpy=\"0 0 0\"\/>\n      &lt;inertia ixx=\"0.107579\" ixy=\"0\" ixz=\"0\" iyy=\"0.107579\" iyz=\"0\" izz=\"0.206717\"\/>\n    &lt;\/inertial>\n    &lt;collision name=\"AGV__collision\">\n      &lt;origin xyz=\"0 0 0\" rpy=\"0 0 0\"\/>\n      &lt;geometry>\n        &lt;cylinder radius=\"0.2\" length=\"0.07\"\/>\n      &lt;\/geometry>\n    &lt;\/collision>\n    &lt;visual name=\"AGV__visual\">\n      &lt;origin xyz=\"0 0 0\" rpy=\"0 0 0\"\/>\n      &lt;geometry>\n        &lt;cylinder radius=\"0.2\" length=\"0.07\"\/>\n      &lt;\/geometry>\n    &lt;\/visual>\n  &lt;\/link>\n  &lt;link name=\"AGV__link_loadingplate\">\n    &lt;inertial>\n      &lt;mass value=\"432.31\"\/>\n      &lt;origin xyz=\"0 0 0\" rpy=\"0 0 0\"\/>\n      &lt;inertia ixx=\"26.0634\" ixy=\"0\" ixz=\"0\" iyy=\"184.903\" iyz=\"0\" izz=\"158.909\"\/>\n    &lt;\/inertial>\n    &lt;collision name=\"AGV__collision\">\n      &lt;origin xyz=\"0 0 0\" rpy=\"0 0 0\"\/>\n      &lt;geometry>\n        &lt;box size=\"2.1 0.01 0.85\"\/>\n      &lt;\/geometry>\n    &lt;\/collision>\n    &lt;visual name=\"AGV__visual\">\n      &lt;origin xyz=\"0 0 0\" rpy=\"0 0 0\"\/>\n      &lt;geometry>\n        &lt;box size=\"2.1 0.01 0.85\"\/>\n      &lt;\/geometry>\n    &lt;\/visual>\n  &lt;\/link>\n  &lt;link name=\"AGV__link_motor\">\n    &lt;inertial>\n      &lt;mass value=\"1\"\/>\n      &lt;origin xyz=\"0 0 0\" rpy=\"0 0 0\"\/>\n      &lt;inertia ixx=\"0.166667\" ixy=\"0\" ixz=\"0\" iyy=\"0.166667\" iyz=\"0\" izz=\"0.166667\"\/>\n    &lt;\/inertial>\n    &lt;collision name=\"AGV__collision\">\n      &lt;origin xyz=\"0 0 0\" rpy=\"0 0 0\"\/>\n      &lt;geometry>\n        &lt;mesh filename=\"package:\/\/battery_agv\/meshes\/stepperMotor3.stl\" scale=\"1 1 1\"\/>\n      &lt;\/geometry>\n    &lt;\/collision>\n    &lt;visual name=\"AGV__visual\">\n      &lt;origin xyz=\"0 0 0\" rpy=\"0 0 0\"\/>\n      &lt;geometry>\n        &lt;mesh filename=\"package:\/\/battery_agv\/meshes\/stepperMotor3.stl\" scale=\"1 1 1\"\/>\n      &lt;\/geometry>\n    &lt;\/visual>\n  &lt;\/link>\n  &lt;link name=\"AGV__link_rightgear\">\n    &lt;inertial>\n      &lt;mass value=\"20\"\/>\n      &lt;origin xyz=\"0 0 0\" rpy=\"0 0 0\"\/>\n      &lt;inertia ixx=\"0\" ixy=\"0\" ixz=\"0\" iyy=\"0\" iyz=\"0\" izz=\"0\"\/>\n    &lt;\/inertial>\n    &lt;collision name=\"AGV__collision\">\n      &lt;origin xyz=\"0 0 0\" rpy=\"0 0 0\"\/>\n      &lt;geometry>\n        &lt;mesh filename=\"package:\/\/battery_agv\/meshes\/axis_gear.stl\" scale=\"1 1 1\"\/>\n      &lt;\/geometry>\n    &lt;\/collision>\n    &lt;visual name=\"AGV__visual\">\n      &lt;origin xyz=\"0 0 0\" rpy=\"0 0 0\"\/>\n      &lt;geometry>\n        &lt;mesh filename=\"package:\/\/battery_agv\/meshes\/axis_gear.stl\" scale=\"1 1 1\"\/>\n      &lt;\/geometry>\n    &lt;\/visual>\n  &lt;\/link>\n  &lt;link name=\"AGV__link_rightgear2\">\n    &lt;inertial>\n      &lt;mass value=\"20\"\/>\n      &lt;origin xyz=\"0 0 0\" rpy=\"0 0 0\"\/>\n      &lt;inertia ixx=\"0\" ixy=\"0\" ixz=\"0\" iyy=\"0\" iyz=\"0\" izz=\"0\"\/>\n    &lt;\/inertial>\n    &lt;collision name=\"AGV__collision\">\n      &lt;origin xyz=\"0 0 0\" rpy=\"0 0 0\"\/>\n      &lt;geometry>\n        &lt;mesh filename=\"package:\/\/battery_agv\/meshes\/axis_gear.stl\" scale=\"1 1 1\"\/>\n      &lt;\/geometry>\n    &lt;\/collision>\n    &lt;visual name=\"AGV__visual\">\n      &lt;origin xyz=\"0 0 0\" rpy=\"0 0 0\"\/>\n      &lt;geometry>\n        &lt;mesh filename=\"package:\/\/battery_agv\/meshes\/axis_gear.stl\" scale=\"1 1 1\"\/>\n      &lt;\/geometry>\n    &lt;\/visual>\n  &lt;\/link>\n  &lt;link name=\"AGV__link_rightplate\">\n    &lt;inertial>\n      &lt;mass value=\"432.31\"\/>\n      &lt;origin xyz=\"0 0 0\" rpy=\"0 0 0\"\/>\n      &lt;inertia ixx=\"26.0634\" ixy=\"0\" ixz=\"0\" iyy=\"184.903\" iyz=\"0\" izz=\"158.909\"\/>\n    &lt;\/inertial>\n    &lt;collision name=\"AGV__collision\">\n      &lt;origin xyz=\"0 0 0\" rpy=\"0 0 0\"\/>\n      &lt;geometry>\n        &lt;box size=\"2.1 0.01 0.85\"\/>\n      &lt;\/geometry>\n    &lt;\/collision>\n    &lt;visual name=\"AGV__visual\">\n      &lt;origin xyz=\"0 0 0\" rpy=\"0 0 0\"\/>\n      &lt;geometry>\n        &lt;box size=\"2.1 0.01 0.85\"\/>\n      &lt;\/geometry>\n    &lt;\/visual>\n  &lt;\/link>\n  &lt;link name=\"AGV__link_rightwheel\">\n    &lt;inertial>\n      &lt;mass value=\"10.3358\"\/>\n      &lt;origin xyz=\"0 0 0\" rpy=\"0 0 0\"\/>\n      &lt;inertia ixx=\"0.107579\" ixy=\"0\" ixz=\"0\" iyy=\"0.107579\" iyz=\"0\" izz=\"0.206717\"\/>\n    &lt;\/inertial>\n    &lt;collision name=\"AGV__collision\">\n      &lt;origin xyz=\"0 0 0\" rpy=\"0 0 0\"\/>\n      &lt;geometry>\n        &lt;cylinder radius=\"0.2\" length=\"0.07\"\/>\n      &lt;\/geometry>\n    &lt;\/collision>\n    &lt;visual name=\"AGV__visual\">\n      &lt;origin xyz=\"0 0 0\" rpy=\"0 0 0\"\/>\n      &lt;geometry>\n        &lt;cylinder radius=\"0.2\" length=\"0.07\"\/>\n      &lt;\/geometry>\n    &lt;\/visual>\n  &lt;\/link>\n  &lt;link name=\"AGV__link_rightwheel0\">\n    &lt;inertial>\n      &lt;mass value=\"10.3358\"\/>\n      &lt;origin xyz=\"0 0 0\" rpy=\"0 0 0\"\/>\n      &lt;inertia ixx=\"0.107579\" ixy=\"0\" ixz=\"0\" iyy=\"0.107579\" iyz=\"0\" izz=\"0.206717\"\/>\n    &lt;\/inertial>\n    &lt;collision name=\"AGV__collision\">\n      &lt;origin xyz=\"0 0 0\" rpy=\"0 0 0\"\/>\n      &lt;geometry>\n        &lt;cylinder radius=\"0.2\" length=\"0.07\"\/>\n      &lt;\/geometry>\n    &lt;\/collision>\n    &lt;visual name=\"AGV__visual\">\n      &lt;origin xyz=\"0 0 0\" rpy=\"0 0 0\"\/>\n      &lt;geometry>\n        &lt;cylinder radius=\"0.2\" length=\"0.07\"\/>\n      &lt;\/geometry>\n    &lt;\/visual>\n  &lt;\/link>\n  &lt;link name=\"AGV__link_topplate\">\n    &lt;inertial>\n      &lt;mass value=\"432.31\"\/>\n      &lt;origin xyz=\"0 0 0\" rpy=\"0 0 0\"\/>\n      &lt;inertia ixx=\"26.0634\" ixy=\"0\" ixz=\"0\" iyy=\"184.903\" iyz=\"0\" izz=\"158.909\"\/>\n    &lt;\/inertial>\n    &lt;collision name=\"AGV__collision\">\n      &lt;origin xyz=\"0 0 0\" rpy=\"0   -0.01  0\"\/>\n      &lt;geometry>\n        &lt;box size=\"2.1 0.01 0.85\"\/>\n      &lt;\/geometry>\n    &lt;\/collision>\n    &lt;visual name=\"AGV__visual\">\n      &lt;origin xyz=\"0 0 0\" rpy=\"0   -0.01  0\"\/>\n      &lt;geometry>\n        &lt;box size=\"2.1 0.01 0.85\"\/>\n      &lt;\/geometry>\n    &lt;\/visual>\n  &lt;\/link>\n&lt;\/robot><\/pre>\n\n\n\n<p>mesh\ub294 package\ub85c \ub123\uc5b4\uc57c \ud558\ub294 \ub4ef \ud55c\ub2e4. urdf\ub85c R2D2\ub97c \ub9cc\ub4e0 \uc0ac\ub78c\uc740 \uacf5\uac04 \uac10\uac01\uc774 \ub6f0\uc5b4\ub098\ub2e4.<\/p>\n\n\n\n<figure class=\"wp-block-embed\"><div class=\"wp-block-embed__wrapper\">\nhttp:\/\/wiki.ros.org\/urdf\/Tutorials\/Building%20a%20Visual%20Robot%20Model%20with%20URDF%20from%20Scratch\n<\/div><\/figure>\n\n\n\n<figure class=\"wp-block-image size-full\"><img loading=\"lazy\" decoding=\"async\" width=\"2560\" height=\"1440\" src=\"https:\/\/now0930.pe.kr\/wordpress\/wp-content\/uploads\/2022\/10\/\uc2a4\ud06c\ub9b0\uc0f7-2022-10-09-15-25-06.png\" alt=\"\" class=\"wp-image-5222\" srcset=\"https:\/\/now0930.pe.kr\/wordpress\/wp-content\/uploads\/2022\/10\/\uc2a4\ud06c\ub9b0\uc0f7-2022-10-09-15-25-06.png 2560w, https:\/\/now0930.pe.kr\/wordpress\/wp-content\/uploads\/2022\/10\/\uc2a4\ud06c\ub9b0\uc0f7-2022-10-09-15-25-06-2048x1152.png 2048w, https:\/\/now0930.pe.kr\/wordpress\/wp-content\/uploads\/2022\/10\/\uc2a4\ud06c\ub9b0\uc0f7-2022-10-09-15-25-06-768x432.png 768w, https:\/\/now0930.pe.kr\/wordpress\/wp-content\/uploads\/2022\/10\/\uc2a4\ud06c\ub9b0\uc0f7-2022-10-09-15-25-06-1536x864.png 1536w, https:\/\/now0930.pe.kr\/wordpress\/wp-content\/uploads\/2022\/10\/\uc2a4\ud06c\ub9b0\uc0f7-2022-10-09-15-25-06-1568x882.png 1568w\" sizes=\"auto, (max-width: 2560px) 100vw, 2560px\" \/><\/figure>\n\n\n\n<p>\uc798 \ub418\ub2e4\uace0 \uc0dd\uac01\ud588\uc73c\ub098, \ubb38\uc81c\uac00 \uc788\uc5c8\ub2e4. \ub85c\ubd07\uc774 \uc81c\ub300\ub85c \uc6c0\uc9c1\uc774\ub294\uc9c0 \ud655\uc778\ud558\uae30 \uc704\ud574 joint_state_publisher\ub97c \uc2e4\ud589\ud574\uc57c \ud558\ub294\ub370, \ud504\ub85c\uc138\uc2a4\uac00 \uc8fd\ub294\ub2e4. \uc65c \uadf8\ub7f0\uc9c0 \ud655\uc778\ud558\uae30 \uc5b4\ub824\uc6e0\ub294\ub370, python \ucf54\ub4dc\ub97c \uc218\uc815\ud558\uc5ec \uc5b4\ub514\uc5d0\uc11c \ubb38\uc81c\ub418\ub294\uc9c0 \ud655\uc778\ud588\ub2e4.<\/p>\n\n\n\n<pre class=\"EnlighterJSRAW\" data-enlighter-language=\"generic\" data-enlighter-theme=\"\" data-enlighter-highlight=\"\" data-enlighter-linenumbers=\"\" data-enlighter-lineoffset=\"\" data-enlighter-title=\"\" data-enlighter-group=\"\">833 [rospy.simtime][INFO] 2022-10-09 13:09:14,685: initializing \/clock core topic\n834 [rospy.simtime][INFO] 2022-10-09 13:09:14,688: connected to core topic \/clock\n835 [rosout][INFO] 2022-10-09 13:09:14,760: Centering\n836 [rospy.core][INFO] 2022-10-09 13:09:14,798: signal_shutdown [atexit]\n837 [rospy.impl.masterslave][INFO] 2022-10-09 13:09:14,801: atexit<\/pre>\n\n\n\n<p>\uc5ec\uae30\ub97c \ubcf4\uba74 centering \ud558\ub2e4\uac00 \uc8fd\uc5c8\uc74c\uc744 \uc54c\uc558\ub2e4. \uc65c \uadf8\ub7f0\uc9c0 \uc54c \uc218 \uc5c6\uc73c\ub2c8, stdout\uc5d0 \ud45c\uc2dc\ub41c \ucf54\ub4dc\ub97c \ubcf4\uba74 joint_state_publiser_gui\uc758 182\ubc88 \uc904\uc5d0\uc11c \uc8fd\uc5c8\uc74c\uc744 \ud655\uc778\ud588\ub2e4.<\/p>\n\n\n\n<pre class=\"EnlighterJSRAW\" data-enlighter-language=\"generic\" data-enlighter-theme=\"\" data-enlighter-highlight=\"\" data-enlighter-linenumbers=\"\" data-enlighter-lineoffset=\"\" data-enlighter-title=\"\" data-enlighter-group=\"\">QStandardPaths: wrong ownership on runtime directory \/run\/user\/1000, 1000 instead of 0\nQStandardPaths: wrong ownership on runtime directory \/run\/user\/1000, 1000 instead of 0\nTraceback (most recent call last):\n  File \"\/opt\/ros\/noetic\/lib\/joint_state_publisher_gui\/joint_state_publisher_gui\", line 52, in &lt;module>\n    jsp_gui = joint_state_publisher_gui.JointStatePublisherGui(\"Node: \" + rospy.get_name(),\n  File \"\/opt\/ros\/noetic\/lib\/python3\/dist-packages\/joint_state_publisher_gui\/__init__.py\", line 125, in __init__\n    self.center()\n  File \"\/opt\/ros\/noetic\/lib\/python3\/dist-packages\/joint_state_publisher_gui\/__init__.py\", line 182, in center\n    joint_info['slider'].setValue(self.valueToSlider(joint['zero'], joint))\nTypeError: setValue(self, int): argument 1 has unexpected type 'float'\n[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].\nlog file: \/root\/.ros\/log\/b95997f0-47a6-11ed-a96e-2cf05d88e0ec\/joint_state_publisher_gui-1*.log\n<\/pre>\n\n\n\n<p>\ud574\ub2f9\ubd80 \ucf54\ub4dc\ub97c \uace0\uccd0\ubcf4\uace0, \ub85c\uadf8\ub97c \ucd9c\ub825\uc2dc\ucf1c \ubcf4\uba74<\/p>\n\n\n\n<pre class=\"EnlighterJSRAW\" data-enlighter-language=\"generic\" data-enlighter-theme=\"\" data-enlighter-highlight=\"\" data-enlighter-linenumbers=\"\" data-enlighter-lineoffset=\"\" data-enlighter-title=\"\" data-enlighter-group=\"\">75     def center_event(self, event):\n176         self.center()\n177 \n178     def center(self):\n179         rospy.loginfo(\"Centering\")\n180         for name, joint_info in self.joint_map.items():\n181             ##debug\n182             rospy.loginfo(\"debug\")\n183             joint = joint_info['joint']\n184             rospy.loginfo(joint)\n185             joint_info['slider'].setValue(self.valueToSlider(joi    nt['zero'], joint))\n<\/pre>\n\n\n\n<p>\uacb0\uacfc\ub97c \ub2e4\uc2dc \ubcf4\uba74 argument 1\uc774 min\uc73c\ub85c \ub4e4\uc5b4\uc628 -1.79..e+308\uc784\uc744 \uc54c\uc558\ub2e4.<\/p>\n\n\n\n<pre class=\"EnlighterJSRAW\" data-enlighter-language=\"generic\" data-enlighter-theme=\"\" data-enlighter-highlight=\"\" data-enlighter-linenumbers=\"\" data-enlighter-lineoffset=\"\" data-enlighter-title=\"\" data-enlighter-group=\"\">866 [rosout][INFO] 2022-10-09 13:13:17,733: Centering\n867 [rosout][INFO] 2022-10-09 13:13:17,735: debug\n868 [rosout][INFO] 2022-10-09 13:13:17,736: {'min': -1.79769e+308, 'max': 1.79769e+308, 'zero': 0, 'position': 0}\n869 [rospy.core][INFO] 2022-10-09 13:13:17,780: signal_shutdown [atexit]\n<\/pre>\n\n\n\n<p>limit\ub97c \uc801\uc740 \uac12\uc73c\ub85c \uc218\uc815\ud558\uba74 \ub41c\ub2e4.<\/p>\n\n\n\n<pre class=\"EnlighterJSRAW\" data-enlighter-language=\"generic\" data-enlighter-theme=\"\" data-enlighter-highlight=\"\" data-enlighter-linenumbers=\"\" data-enlighter-lineoffset=\"\" data-enlighter-title=\"\" data-enlighter-group=\"\"> 24   &lt;joint name=\"AGV__link_bottomplate_JOINT_4\" type=\"revolute\">\n 25     &lt;parent link=\"AGV__link_bottomplate\"\/>\n 26     &lt;child link=\"AGV__link_leftwheel\"\/>\n 27     &lt;origin xyz=\"0.73669 -0.27702  1.05254\" rpy=\"1.5708 0     0\"\/>\n 28     &lt;axis xyz=\"0 0 1\"\/>\n 29     &lt;limit lower=\"-0.2\" upper=\"0.5\" effort=\"-1.0\" velocity=\"-1.0\"\/>\n 30   &lt;\/joint>   <\/pre>\n\n\n\n<p>\uadf8\ub7f0\ub370 \ud574\ub2f9 \ubd80\ubd84\uc740 \ubc14\ud034\ub77c\uc11c type\uc744 continuous\ub85c \uc218\uc815\ud574\ub3c4 \ub41c\ub2e4. sdf\uac00 continuous type\uc744 \uc120\ud0dd\ud560 \uc218 \uc5c6\uc5c8\ub2e4. \uc774\uac70 \ucc3e\ub294\ub2e4\uace0 \uac70\uc758 4\uc2dc\uac04\uc744 \uc37c\ub2e4. TF \ud45c\uc2dc\ub294 gazebo\uac00 \uc2e4\ud589\ub418\uba74 \uc81c\ub300\ub85c \ud45c\uc2dc\ub41c\ub2e4.<\/p>\n","protected":false},"excerpt":{"rendered":"<p>urdf\ub85c \ubaa8\ub378\uc744 \uadf8\ub9ac\ub824\uba74 \uac01 \uc88c\ud45c\uac12\ub97c \ubaa8\ub450 \uc54c\uc544\uc57c \ud55c\ub2e4. \uc218\uce58\ub97c \ub123\uc5b4\uc57c \ub418\ub294\ub370 \uc2dc\uac04 \ub9ce\uc774 \uac78\ub9b0\ub2e4. \ub2e4\ud589\ud788\ub3c4 gazebo\uac00 \uc81c\uacf5\ud558\ub294 model \uc5d0\ub514\ud130\ub85c \uc0ac\uac01\ud615, [&hellip;]<\/p>\n","protected":false},"author":1,"featured_media":0,"comment_status":"open","ping_status":"open","sticky":false,"template":"","format":"standard","meta":{"site-sidebar-layout":"default","site-content-layout":"","ast-site-content-layout":"default","site-content-style":"default","site-sidebar-style":"default","ast-global-header-display":"","ast-banner-title-visibility":"","ast-main-header-display":"","ast-hfb-above-header-display":"","ast-hfb-below-header-display":"","ast-hfb-mobile-header-display":"","site-post-title":"","ast-breadcrumbs-content":"","ast-featured-img":"","footer-sml-layout":"","ast-disable-related-posts":"","theme-transparent-header-meta":"","adv-header-id-meta":"","stick-header-meta":"","header-above-stick-meta":"","header-main-stick-meta":"","header-below-stick-meta":"","astra-migrate-meta-layouts":"default","ast-page-background-enabled":"default","ast-page-background-meta":{"desktop":{"background-color":"var(--ast-global-color-5)","background-image":"","background-repeat":"repeat","background-position":"center center","background-size":"auto","background-attachment":"scroll","background-type":"","background-media":"","overlay-type":"","overlay-color":"","overlay-opacity":"","overlay-gradient":""},"tablet":{"background-color":"","background-image":"","background-repeat":"repeat","background-position":"center center","background-size":"auto","background-attachment":"scroll","background-type":"","background-media":"","overlay-type":"","overlay-color":"","overlay-opacity":"","overlay-gradient":""},"mobile":{"background-color":"","background-image":"","background-repeat":"repeat","background-position":"center center","background-size":"auto","background-attachment":"scroll","background-type":"","background-media":"","overlay-type":"","overlay-color":"","overlay-opacity":"","overlay-gradient":""}},"ast-content-background-meta":{"desktop":{"background-color":"var(--ast-global-color-4)","background-image":"","background-repeat":"repeat","background-position":"center center","background-size":"auto","background-attachment":"scroll","background-type":"","background-media":"","overlay-type":"","overlay-color":"","overlay-opacity":"","overlay-gradient":""},"tablet":{"background-color":"var(--ast-global-color-4)","background-image":"","background-repeat":"repeat","background-position":"center center","background-size":"auto","background-attachment":"scroll","background-type":"","background-media":"","overlay-type":"","overlay-color":"","overlay-opacity":"","overlay-gradient":""},"mobile":{"background-color":"var(--ast-global-color-4)","background-image":"","background-repeat":"repeat","background-position":"center center","background-size":"auto","background-attachment":"scroll","background-type":"","background-media":"","overlay-type":"","overlay-color":"","overlay-opacity":"","overlay-gradient":""}},"jetpack_post_was_ever_published":false,"_jetpack_newsletter_access":"","_jetpack_dont_email_post_to_subs":false,"_jetpack_newsletter_tier_id":0,"_jetpack_memberships_contains_paywalled_content":false,"_jetpack_memberships_contains_paid_content":false,"footnotes":""},"categories":[1049],"tags":[1086,1044,1084,1085,1054],"class_list":["post-5218","post","type-post","status-publish","format-standard","hentry","category-ros","tag-mesh","tag-ros","tag-sdf","tag-stl","tag-urdf"],"jetpack_featured_media_url":"","jetpack_sharing_enabled":true,"_links":{"self":[{"href":"https:\/\/now0930.pe.kr\/wordpress\/wp-json\/wp\/v2\/posts\/5218","targetHints":{"allow":["GET"]}}],"collection":[{"href":"https:\/\/now0930.pe.kr\/wordpress\/wp-json\/wp\/v2\/posts"}],"about":[{"href":"https:\/\/now0930.pe.kr\/wordpress\/wp-json\/wp\/v2\/types\/post"}],"author":[{"embeddable":true,"href":"https:\/\/now0930.pe.kr\/wordpress\/wp-json\/wp\/v2\/users\/1"}],"replies":[{"embeddable":true,"href":"https:\/\/now0930.pe.kr\/wordpress\/wp-json\/wp\/v2\/comments?post=5218"}],"version-history":[{"count":8,"href":"https:\/\/now0930.pe.kr\/wordpress\/wp-json\/wp\/v2\/posts\/5218\/revisions"}],"predecessor-version":[{"id":5229,"href":"https:\/\/now0930.pe.kr\/wordpress\/wp-json\/wp\/v2\/posts\/5218\/revisions\/5229"}],"wp:attachment":[{"href":"https:\/\/now0930.pe.kr\/wordpress\/wp-json\/wp\/v2\/media?parent=5218"}],"wp:term":[{"taxonomy":"category","embeddable":true,"href":"https:\/\/now0930.pe.kr\/wordpress\/wp-json\/wp\/v2\/categories?post=5218"},{"taxonomy":"post_tag","embeddable":true,"href":"https:\/\/now0930.pe.kr\/wordpress\/wp-json\/wp\/v2\/tags?post=5218"}],"curies":[{"name":"wp","href":"https:\/\/api.w.org\/{rel}","templated":true}]}}