rviz 12.7 update 실패->성공

osrf/ros:humble-desktop 도커 이미지를 설치하면 rviz 12.6가 설치된다. 가끔 node를 만들어 robot_description을 입력하면, rviz2가 제대로 표시 안할 경우가 있다. moveit_setup_assistant도 기존 설정 파일을 수정하면 robot_model_loader가 실행되지 않을 경우도 있다. 아마 12.6 버전의 문제인 듯 하여 버전을 올려 보기로 했다. 최신 버전은 12.8인데, humble이 사용할 수 있는 가장 최근 버전은 12.7이다. 12.8을 사용하면 display panel이 안보이는 듯 안정적으로 동작하지 않는다.

now0930@rygen3600:~/ros2/test/ws_root/ws_user$ git clone -b humble https://github.com/ros2/rviz.git
'rviz'에 복제합니다...
remote: Enumerating objects: 30445, done.
remote: Counting objects: 100% (4756/4756), done.
remote: Compressing objects: 100% (1181/1181), done.
remote: Total 30445 (delta 3857), reused 4031 (delta 3399), pack-reused 25689
오브젝트를 받는 중: 100% (30445/30445), 16.45 MiB | 16.27 MiB/s, 완료.
델타를 알아내는 중: 100% (22231/22231), 완료.
now0930@rygen3600:~/ros2/test/ws_root/ws_user$ cd rviz/
now0930@rygen3600:~/ros2/test/ws_root/ws_user/rviz$ git checkout 
브랜치가 'origin/humble'에 맞게 업데이트된 상태입니다.

branch를 선택하지 않고, default 값으로 humble에서 12.8을 컴파일 하고 있었다. 잘 동작되지 않아 2일을 날렸다. work space 구조도 각 패키지에 맞도록 세부적으로 나누어야 한다. 섞이면 컴파일 양도 많고, 각 패키지별로 옵션을 설정할 수 없다. workspace에 대한 내용은 여기에 있다. overlay, underlay를 정확하게 이해하지 않고 가 시간 날렸다.

rviz2 readme를 따라 complie 한다. 컴파일 중 ignition_math6_vendor가 없어 에러로 멈춘다.

CMake Error at CMakeLists.txt:64 (find_package):
  By not providing "Findignition_math6_vendor.cmake" in CMAKE_MODULE_PATH
  this project has asked CMake to find a package configuration file provided
  by "ignition_math6_vendor", but CMake did not find one.

  Could not find a package configuration file provided by
  "ignition_math6_vendor" with any of the following names:

    ignition_math6_vendorConfig.cmake
    ignition_math6_vendor-config.cmake

  Add the installation prefix of "ignition_math6_vendor" to CMAKE_PREFIX_PATH
  or set "ignition_math6_vendor_DIR" to a directory containing one of the
  above files.  If "ignition_math6_vendor" provides a separate development
  package or SDK, be sure it has been installed.

apt-cache로 ros-humble-ignition-math6-vendor를 검색하면, 해당 패키지가 설치되어 있다. dpkg로 어떤 파일들이 있는지 보면, 실재 파일은 없는 듯 하다.

root@rygen3600:/home/ros2_test# dpkg -L ros-humble-ignition-math6-vendor
/.
/opt
/opt/ros
/opt/ros/humble
/opt/ros/humble/share
/opt/ros/humble/share/ignition_math6_vendor
/opt/ros/humble/share/ignition_math6_vendor/package.xml
/usr
/usr/share
/usr/share/doc
/usr/share/doc/ros-humble-ignition-math6-vendor
/usr/share/doc/ros-humble-ignition-math6-vendor/changelog.Debian.gz
/usr/share/doc/ros-humble-ignition-math6-vendor/copyright
root@rygen3600:/home/ros2_test# 

ROS Index를 찾아보면 rviz2 github를 찾을 수 있는데, 이를 rviz에 있는 디렉토리에 받아주면 된다. ignition-math6-vendor가 gz_math6_vendor로 바뀐 느낌이다. CMakefile을 보면 project로 ignition_math6_vendor로 자기를 명명한다.

oot@rygen3600:/home/ros2_test/rviz# ls -alh
total 92K
drwxrwxr-x 17 1000 1000 4.0K Aug  8 21:43 .
drwxrwxr-x  7 1000 1000 4.0K Aug  6 20:45 ..
drwxrwxr-x  8 1000 1000 4.0K Aug  6 20:45 .git
drwxrwxr-x  3 1000 1000 4.0K Aug  6 20:45 .github
-rw-rw-r--  1 1000 1000   55 Aug  6 20:45 .gitignore
-rw-rw-r--  1 1000 1000   84 Aug  6 20:45 CODEOWNERS
-rw-rw-r--  1 1000 1000 1.7K Aug  6 20:45 LICENSE
-rw-rw-r--  1 1000 1000 8.2K Aug  6 20:45 README.md
drwxr-xr-x 11 root root 4.0K Aug  8 21:49 build
drwxrwxr-x  2 1000 1000 4.0K Aug  6 20:45 docs
drwxrwxr-x  5 1000 1000 4.0K Aug  8 21:43 gz_math6_vendor
drwxr-xr-x  7 root root 4.0K Aug  8 21:49 install
drwxr-xr-x 10 root root 4.0K Aug  8 21:44 log
drwxrwxr-x  6 1000 1000 4.0K Aug  6 20:45 rviz2
drwxrwxr-x  3 1000 1000 4.0K Aug  6 20:45 rviz_assimp_vendor
drwxrwxr-x  8 1000 1000 4.0K Aug  6 20:45 rviz_common
drwxrwxr-x  6 1000 1000 4.0K Aug  8 21:53 rviz_default_plugins
drwxrwxr-x  3 1000 1000 4.0K Aug  6 20:45 rviz_ogre_vendor
drwxrwxr-x  6 1000 1000 4.0K Aug  6 20:45 rviz_rendering
drwxrwxr-x  4 1000 1000 4.0K Aug  6 20:45 rviz_rendering_tests
drwxrwxr-x  7 1000 1000 4.0K Aug  8 20:54 rviz_visual_testing_framework
root@rygen3600:/home/ros2_test/rviz# 
root@rygen3600:/home/ros2_test/rviz# cd gz_math6_vendor/
root@rygen3600:/home/ros2_test/rviz/gz_math6_vendor# ls
CHANGELOG.rst	CONTRIBUTING.md  package.xml
CMakeLists.txt	LICENSE		 patches
root@rygen3600:/home/ros2_test/rviz/gz_math6_vendor# cat CMakeLists.txt 
cmake_minimum_required(VERSION 3.10)
project(ignition_math6_vendor)

find_package(ament_cmake_core REQUIRED)
find_package(ament_cmake_vendor_package REQUIRED)

find_package(ignition-math6 6.9.2 QUIET)

ament_vendor(ignition_math6_vendor
  SATISFIED ${ignition-math6_FOUND}
  VCS_URL https://github.com/ignitionrobotics/ign-math.git
  VCS_VERSION ignition-math6_6.9.2
  PATCHES patches
  CMAKE_ARGS
    -DBUILD_DOCS:BOOL=OFF
  GLOBAL_HOOK
)

find_package(ament_cmake_test REQUIRED)
if(BUILD_TESTING)
  find_package(ament_cmake_lint_cmake REQUIRED)
  find_package(ament_cmake_copyright REQUIRED)
  find_package(ament_cmake_xmllint REQUIRED)

  ament_lint_cmake()
  ament_copyright()
  ament_xmllint()
endif()

ament_package()

ros2 launch gdb

ros2를 gdb를 사용할 수 있다(대박!). 먼저 ros2 run 옵션으로 사용하는 포스트를 찾았다. 이러면 node를 만들 때 전달한 파라미터를 모두 넣어줘야 하여 어렵고 불편하다. 다행히 ros가 죽을 때 어떤 파일을 사용했는지 알려줬다.

[ERROR] [robot_model_tutorial-1]: process has died [pid 1919, exit code -11, cmd '/home/ros2_test/install/hello_moveit/lib/hello_moveit/robot_model_tutorial --ros-args --params-file /tmp/launch_params_2myb0p1i --params-file /tmp/launch_params_q_86u0o7 --params-file /tmp/launch_params_2dnzqmp1'].

node를 실행할 때, tmp 디렉토리에 파일로 만들어 이를 args로 전달한다. 다음과 같이 ros run으로 gdb를 붙일 수 있다.

ros2 run --prefix 'gdb -ex run --args' hello_moveit robot_model_tutorial --ros-args --params-file /tmp/launch_params_2myb0p1i --params-file /tmp/launch_params_q_86u0o7 --params-file /tmp/launch_params_2dnzqmp1

파라미터 입력이 귀찮으면, launch 옵션에 prefix로 넣어 사용할 수 있다. 단 터미널을 새로 만들어야 한다. 왜 그런지는 잘 모르겠는데, 일단 되니까 패스.

<사용하는 lanch file>
from launch import LaunchDescription
from launch_ros.actions import Node
from moveit_configs_utils import MoveItConfigsBuilder


def generate_launch_description():
    moveit_config = MoveItConfigsBuilder("hello").to_moveit_configs()

    my_node = Node(
        package="hello_moveit",
        executable="robot_model_tutorial",
        output="screen",
        parameters=[
            moveit_config.robot_description,
            moveit_config.robot_description_semantic,
            moveit_config.robot_description_kinematics,
        ],
    )

    return LaunchDescription([my_node])
<디버그용 lanch file>
from launch import LaunchDescription
from launch_ros.actions import Node
from moveit_configs_utils import MoveItConfigsBuilder


def generate_launch_description():
    moveit_config = MoveItConfigsBuilder("hello").to_moveit_configs()

    my_node = Node(
        package="hello_moveit",
        executable="robot_model_tutorial",
        prefix ="xterm -e gdb run --args",
        output="screen",
        parameters=[
            moveit_config.robot_description,
            moveit_config.robot_description_semantic,
            moveit_config.robot_description_kinematics,
        ],
    )

    return LaunchDescription([my_node])

gdb 기본 사용법은 여기 정리되어 있다.

MoveIt2 tutorial 따라하기(setFromIK)

인터넷에 공개된 MoveIt2 tutorial을 따라하다 보면 많은 사실을 학습할 수 있다. 다만 그대로 따라하면 그 감동이 적어, 내가 마음대로 해보기로 했다. ABB가 인터넷에 공개한 ABB_IRB2400 urdf 파일로 시작했다. 내가 한 삽질을 여기에 끄적인다.

setup assistant로 urdf 파일을 로딩하고, move_group, kinematics solver, pose 등을 설정하여 움직이는 Manuplator를 프로젝트 이름 + moveit_config 디렉토리에 저장했다. 기본으로 제공된 demo.launch.py을 실행하여 Rviz를 열고, 마우스 버튼으로 robotModel, MarkArray, panel을 추가했다. Planning with Path Constraints 부분에서 막혔는데,

start_state.setFromIK(joint_model_group, start_pose2);

를 실행하면

No kinematics solver instantiated for group '%s

메세지를 내고 프로그램이 죽는다. RobotState Class를 찾아보니 인자로 제공된 JointModelGroup에서 SolverInstance를 얻지 못하면 error 처리한다.

01278 bool moveit::core::RobotState::setFromIK(const JointModelGroup* jmg, const geometry_msgs::Pose& pose,
01279                                          unsigned int attempts, double timeout,
01280                                          const GroupStateValidityCallbackFn& constraint,
01281                                          const kinematics::KinematicsQueryOptions& options)
01282 {
01283   const kinematics::KinematicsBaseConstPtr& solver = jmg->getSolverInstance();
01284   if (!solver)
01285   {
01286     logError("No kinematics solver instantiated for group '%s'", jmg->getName().c_str());
01287     return false;
01288   }
01289   return setFromIK(jmg, pose, solver->getTipFrame(), attempts, timeout, constraint, options);
01290 }
01291 

JointModelGroup은 moveit setup assistanct가 설정하는 듯 한데, 어떻게 설정하는지 정확하게 설명되어 있지 않았다. moveit setup assistant로 설정할 때 kinematics solver를 선택하는 항목이 있는데, 나는 제대로 선택했는데 문제가 있다.

제공된 panda_arm 예제가 어떻게 돌아가는지 다시 살펴 보기로 했다. moveit2_tutorial에 panda_arm으로 제공된 항목을 찾아 move_group에 해당하는 부분을 launch 했다. moveit2_tutorial을 설치하면 moveit_resources에 panda_move_config가 있는데 여기 demo.launch.py를 실행해 보았다.

root@rygen3600:/home/ros2_test#ros2 launch moveit_resources_panda_moveit_config demo.launch.py
...
[move_group-4] [INFO] [1690614580.226886350] [move_group.move_group]: 
[move_group-4] 
[move_group-4] ********************************************************
[move_group-4] * MoveGroup using: 
[move_group-4] *     - ApplyPlanningSceneService
[move_group-4] *     - ClearOctomapService
[move_group-4] *     - CartesianPathService
[move_group-4] *     - ExecuteTrajectoryAction
[move_group-4] *     - GetPlanningSceneService
[move_group-4] *     - KinematicsService
[move_group-4] *     - MoveAction
[move_group-4] *     - MotionPlanService
[move_group-4] *     - QueryPlannersService
[move_group-4] *     - StateValidationService
[move_group-4] ********************************************************
[move_group-4] 

parameter가 어떻게 제공되는지 알아보기 위해 param list를 확인해 보고, 의심되는 kinematics_solver 값을 확인했다. robot_description에 solver를 설정할 수 있는데, moveit setup assistant가 설정한 값으로 동작하고 있다.

root@rygen3600:/home/ros2_test/src/hello_moveit/debug# ros2 param get /move_group robot_description_kinematics.panda_arm.kinematics_solver
String value is: kdl_kinematics_plugin/KDLKinematicsPlugin

내가 만든 ABB 로봇은 해당 node가 없다. 이제 문제가 무엇인지 알았다. launch할 때 해당 값을 넣어줘야 하는데, 내가 빼먹고 넣어주지 않았다. 이제 panda_arm demo 파일을 보고, 어떻게 설정해야 하는지 알아봐야 한다.

panda demo를 자세히 보니, 노드를 만들어서 robot_description에 kinematics를 설정해 주었다. 나는 ros run으로 해당 프로그램만 실행해주어 kinematics_solver가 설정되지 않았다. 아래 형식으로 노드를 만들어 준다.

root@rygen3600:/home/ros2_test# cat src/hello_moveit/launch/my_demo.launch.py 
from launch import LaunchDescription
from launch_ros.actions import Node
from moveit_configs_utils import MoveItConfigsBuilder


def generate_launch_description():
    moveit_config = MoveItConfigsBuilder("hello").to_moveit_configs()

    # MoveGroupInterface demo executable
    move_group_demo = Node(
        name="my_move_group_interface",
        package="hello_moveit",
        executable="planning",
        output="screen",
        parameters=[
            moveit_config.robot_description,
            moveit_config.robot_description_semantic,
            moveit_config.robot_description_kinematics,
        ],
    )

    return LaunchDescription([move_group_demo])

이제 새로운 문제가 있다. orientation constraint를 설정하면 로봇이 제대로 움직이지 않는다. interactive marker는 쉽게 planning 하는데, 프로그램으로 하면 짧은 거리도 planning이 높은 확율로 실패한다.

sdf, urdf, blender로 모델 만들기

gazebo 모델 에디터에서 원하는 모양을 그리기 너무 어렵다. 좌표를 수정하기 어렵고, 버그로 인해 객체가 가끔 보이지 않는다. 이번 기회에 오픈소스 프로그램 blender를 배워 3d로 직접 그리기로 했다.

쉬운 게 없다고, blender는 다른 세상이다. 기본인 mesh에서 solidify로 두께를 만든다 던가, cursor를 selection으로 이동하는 등 몇 가지 필수로 알아야 한다. 기본이 없는 상태에서 시작하면 시간을 너무 오래 쓴다. 2D 그림보다 3D 그림이 삼십배 시간이 많이 든다. 3D로 그릴 때 dimension 넣는 방법도 몰라 한참을 헤맸다.

디멘전까지 정확하게 넣었고, 잘 이동한 다음, 줄과 열을 맞춰 4~5개 객체를 통째로 stl로 출력했다. 자 이제 이 단순화된 그림을 gazebo 모델 에디터로 부르기만 하면 된다. 기존에 10개 넘었던 링크가 2개로 단순화 된다!

웬걸..망했다. gazebo는 대략적으로 형상과 재질을 설정하고, 무게와 관성 모멘트를 대충 넣어 주는데, stl을 불러오면 그런 거 하나도 없다. 눈에 어떻게 보이는지만 다르다. 결론은 복잡해도 gazebo에서 대략적으로 그려줘야 한다. 하루종일 그려준게 아까우니 urdf로 만든 파일에 geomery에서 mesh를 찾아 넣어 주기로 했다.

아. gazebo에서 그릴 때 좌표계를 확인하고 넣어 줬어야 했는데, 쓰기 어렵다 보니 일일히 신경쓰지 않았다. 웬걸. 스킨이 방향이 하나도 안 맞는gazebo 모델 에디터에서 원하는 모양을 그리기 너무 어렵다. 좌표를 수정하기 어렵고, 버그로 인해 객체가 가끔 보이지 않는다. 이번 기회에 오픈소스 프로그램 blender를 배워 3d로 직접 그리기로 했다.다. 이거 하는데 하루 종일 걸렸다. 알면 너무나 쉬운데, 모르면 너무 오래 걸린다.

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가 실행되면 제대로 표시된다.