[카테고리:] 생활코딩

  • iLO4

    iLO4

    128GB 서버용 하드 디스크를 사용하려다 보니 용량이 좀 부족한 듯 했다. 당근에서 500GB를 5만원에 구해와 교체 하기로 했다. 전에 SSD를 적출당한 12살 vostro 3750 노트북도 살려줘야 할 필요가 있고.

    전에 한번 노가다를 하여, 이번에는 docker로 쉽게 할 수 있었다. 그런데 어떻게든 OS를 설치할 때 9핀 출력 모니터가 있어야 했다. 전에 유용하게 사용했던 모니터를 이미 버렸다. gen8을 사면 iLO 기본을 사용할 수 있는데, 한번도 사용하지 않았다. 이번에 iLO를 사용하기로 결정했다.

    결과는 대박이다. 초기 업데이트가 안되어 remote console를 바로 사용할 수 없으나, 최신 프로그램으로 업데이트를 하면 html5로 접속 가능하다. 부팅 시작부터 화면을 인터넷을 볼 수 있다. 와! 정말 편리한 기능이다. 랜선 하나만 꼳으면 제어가 가능하다니. 접속 IP도 화면에 보이는데, 공유기를 통해 연결하면 대충 어느 IP인지 확인 가능하다.

    기본 버전으로는 remote console을 계속 사용할 수는 없고, 부팅 후 일정 시간이 지나면 화면만 보이고 입력을 인터넷으로 보낼 수 없다. 라인센스를 구매해야 그 이후에도 사용 가능하다. 돈 주고 라이센스를 사려다가 무선 키보드, 마우스를 서버에 직접 연결하여 사용했다. 화면은 일정 시간동안 보이니까 OS를 설치하는데 문제 없다.

    나중에 xhost로 원격으로 화면을 보면서 해 줘야할 필요가 있을 경우, iLO를 사용하면 편할 듯 하다. 실제 plex를 처음 설치하면 서버에 직접 접속하여 설정을 해야 하는데, 이렇게 하면 쉽다.

    이제 노트북을 살려야지.

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