Let’s go!

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

  • gmapping slam으로 지도 만들기

    여기 있는 gmapping, slam 튜토리얼을 했다. 튜토리얼은 상당히 쉽게 구성되어 있으나, 내가 실재로 해보면 잘 안된다. 왜 그런지 확인하기 위해 삽질을 했다. 해당 사이트에서 다운로드 받을 수 있는 rosbag 파일에 어떤 토픽이 저장되어 있는지 궁금했다. rqt가 제공하는 rosbag 플러그인으로 어떤 데이터가 있는지 확인했다.

    rosbag play로 실행하면 뭐가 잘못 되었는지 다음 메세지를 보았다. debug 레벨을 켜라는 소리인 듯 한데…

    [ WARN] [1664664315.511464153]: MessageFilter [target=odom ]: Dropped 100.00% of messages so far. Please turn the [ros.gmapping.message_filter] rosconsole logger to DEBUG for more information.

    rosconsole로 message filter 현재 상태를 확인하고 변경할 수 있다.

    root:workspace$rosconsole get /slam_gmapping ros.gmapping.message_filter
    info
    root:workspace$rosconsole set slam_gmapping ros.gmapping.message_filter debug

    rosbag에 -a 옵션을 주고 모든 데이터를 저장하면 지도를 만들 수 있다. 아래와 같이 tf와 scan 데이터만 저장한 다음 rosbag play를 실행하면 tf tree가 끊어져 있다. 정확하게는 basefoot_print와 base_link가 끊겨져 있고, scanner_link가 없다.

    ros@workspace$rosbag record /tf /laser/scan
    [ INFO] [1664767902.638118674]: Subscribing to /laser/scan
    [ INFO] [1664767902.642276643]: Subscribing to /tf
    [ INFO] [1664767902.645339564]: Recording to '2022-10-03-03-31-42.bag'.
    ros@workspace$ros@bag$rosbag play --clock 2022-10-03-03-31-42.bag

    하나씩 해 보다가 /tf_static까지 record 해 보았다. 아, 힘들었다^^!

    ros@bag$rosbag record -o mydata /tf /tf_static /laser/scan
    [ INFO] [1664769638.007469286]: Subscribing to /laser/scan
    [ INFO] [1664769638.011680347]: Subscribing to /tf
    [ INFO] [1664769638.014193685]: Subscribing to /tf_static
    [ INFO] [1664769638.298793651, 1626.350000000]: Recording to 'mydata_2022-10-03-04-00-38.bag'.

    record한 결과를 보면 지도가 잘 생성됨을 확인했다. tf_tree를 보면

    위 빠진 tf_tree와 다르게 base_footprint와 base_link가, base_link와 scanner_link가 연결되었다. 왜 이렇게 결정되었는지 확인해 보면, urdf에 fixed라고 joint를 정의해서 그렇다. 아래 urdf를 정의한 부분을 확인해 보면 fixed로 joint를 정의했기 때문에 tf_static을 필요로 한다.

     42 
     43         <joint name = "base_footprint_fixed" type = "fixed">
     44                 <origin xyz = "0 0 0.03" rpy = "0 0 0"/>
     45                 <parent link = "base_footprint"/>
     46                 <child link = "base_link"/>
     47         </joint>
     48 
    
    146         <joint name = "left_wheel_joint" type = "continuous">
    147                 <origin xyz = "0.1 0.15 0" rpy = "0 0 0"/>
    148                 <parent link = "base_link"/>
    149                 <child link = "left_wheel"/>
    150                 <axis xyz = "0 1 0"/>
    151 
    152         </joint>
    153 
    154         <joint name = "left_wheel_joint_back" type = "continuous">
    155                 <origin xyz = "-0.1 0.15 0" rpy = "0 0 0"/>
    156                 <parent link = "base_link"/>
    157                 <child link = "left_wheel_back"/>
    158                 <axis xyz = "0 1 0"/>
    159 
    160         </joint>
    161 
    162 
    
    
    205         <joint name = "head_scanner" type = "fixed">
    206                 <!-- rpy를 수정하면 카메라 각도가 바뀜-->
    207                 <origin xyz = "0.15 0 0" rpy = "0 0 0"/>
    208                 <parent link = "base_link"/>
    209                 <child link = "scanner_link"/>
    210         </joint>
    211 

    기록한 rosbag 파이을 보면, scan, tf, tf_static 3개가 들어가 있다.

  • gazebo plug in으로 robot move

    로봇을 불렀으면, cmd_vel 토픽으로 움직이고 싶다. 찾다보니 gazebo가 제공하는 plugin로 움직일 수 있음을 알았다. 플러그인 설정으로 어느 토픽을 읽어서 모델을 움직일지 결정한다.

    https://classic.gazebosim.org/tutorials?tut=ros_gzplugins

    gcamp_gazebo 샘플 프로그램을 참조 했다. gazebo로 로봇을 움직이려면 필요한 몇 개 파일을 만들어야 한다.

    now0930@amd2004:~/ros_test/workspace/src/wander_bot$ tree
    .
    ├── CMakeLists.txt
    ├── gazebo_world.launch
    ├── launch
    │   ├── hello.launch
    │   ├── my_world.launch
    │   └── robot_description.launch
    ├── log.txt
    ├── package.xml
    ├── src
    │   └── red_green_light.py
    ├── urdf
    │   ├── robot.gazebo
    │   ├── robot.xacro
    │   └── test.urdf
    └── worlds
        ├── my_world
        └── my_world2
    
    4 directories, 13 files

    roslaunch로 launch에 있는 my_world.launch에서 시작한다.

    oot@amd2004:/home/ros_test/workspace/src/wander_bot# cat launch/my_world.launch 
    <?xml version="1.0" encoding="UTF-8"?>
    
    <launch>
    	<!-- Robot pose -->
    	<arg name="x" default="0"/>
    	<arg name="y" default="0"/>
    	<arg name="z" default="0"/>
    	<arg name="roll" default="0"/>
    	<arg name="pitch" default="0"/>
    	<arg name="yaw" default="0"/>
    	<arg name="model_name"   default="agv_number1"/>
    
    
    
    			<!-- We resume the logic in empty_world.launch, changing only the name of the world to be launched -->
    		<include file="$(find gazebo_ros)/launch/empty_world.launch">
    			<arg name="world_name" value="$(find wander_bot)/worlds/my_world2"/>
    			<arg name="use_sim_time" value="true"/>
    				<!-- more default parameters can be changed here -->
    		</include>
    		<arg name="package_name"  default="wander_bot" />
    		<arg name="path"   value="(find $(arg package_name))" />
    		<arg name="dollar" value="$" />
    
    		<include file="$(arg dollar)$(arg path)/launch/robot_description.launch"/> 
    
    			<!-- Spawn My Robot -->
    			<!--
    				<node name="urdf_spawner" pkg="gazebo_ros" type="spawn_model" respawn="false" output="screen" 
    				args="-urdf -param robot_description -model $(arg model_name) 
    				-x $(arg x) -y $(arg y) -z $(arg z)
    				-R $(arg roll) -P $(arg pitch) -Y $(arg yaw)"/>
    			-->
    				<node name="urdf_spawner" pkg="gazebo_ros" type="spawn_model" respawn="false" output="screen" 
    					args="-urdf -param robot_description -model $(arg model_name) 
    					-x $(arg x) -y $(arg y) -z $(arg z)
    					-R $(arg roll) -P $(arg pitch) -Y $(arg yaw)"/>
    
    
    				<node name="test_node" pkg="wander_bot" type="red_green_light.py"
    					args="/cmd_vel">
    			</node>
    		</launch>
    
        <include file="$(arg dollar)$(arg path)/launch/robot_description.launch"/> 

    launch가 robot description을 실행하는데, command로 robot.xacro로 세부 설정을 한다. command가 아닌 다른 방식으로는 모델이 움직이지 않는다. robot description 내부에는 robot_description, joint_state_publisher, robot_state_publisher 3개를 설정한다.

    now0930@amd2004:~/ros_test/workspace/src/wander_bot$ cat launch/robot_description.launch 
    <?xml version="1.0"?>
    <launch>
    
    	<!-- send urdf to param server -->
    	<!-- xacro -->
    
    	<param name="robot_description" command="$(find xacro)/xacro --inorder '$(find wander_bot)/urdf/robot.xacro'" />
    
    		<!-- urdf or raw xml file -->
    		<!-- <param name="robot_description" command="cat $(find museumGuide)/urdf_model/peoplebot.xml" /> -->
    
    			<!-- Send fake joint values-->
    		<node name="joint_state_publisher" pkg="joint_state_publisher" type="joint_state_publisher">
    			<param name="use_gui" value="False"/>
    		</node>
    
    		<!-- Send robot states to tf -->
    		<node name="robot_state_publisher" pkg="robot_state_publisher" type="robot_state_publisher" respawn="false" output="screen"/>
    
    	</launch>
    

    robot.xacro를 보면

    now0930@amd2004:~/ros_test/workspace/src/wander_bot$ cat urdf/robot.xacro 
    <?xml version="1.0" ?>
    <robot name="mobile_robot" xmlns:xacro="http://www.ros.org/wiki/xacro">
    	<material name="blue">
    		<color rgba = "0 0 0.8 1"/>
    	</material>
    
    	<material name="gray">
    		<color rgba = "1 1 1 1"/>
    	</material>
    
    	<material name="blueviolet">
    		<color rgba = "0.54 0.16 0.88 1"/>
    	</material>
    
    	<link name = "base_footprint"/>
    
    	<xacro:include filename="$(find wander_bot)/urdf/robot.gazebo" />
    
    	<link name="base_link">
    		<visual>
    			<origin xyz="0 0 0" rpy = "0 0 0"/>
    			<geometry>
    				<box size = "0.3 0.24 0.1" rpy = "0 0 0" />
    			</geometry>
    			<material name = "gray"/>
    
    		</visual>
    		<collision>
    			<origin xyz="0 0 0.03" rpy = "0 0 0"/>
    			<geometry>
    				<box size = "0.3 0.25 0.1" />
    			</geometry>
    
    		</collision>
    		<inertial>
    			<mass value = "1.0" />
    			<inertia  ixx="1.0" ixy="0.0"  ixz="0.0"  iyy="1.0"  iyz="0.0"  izz="1.0" />
    		</inertial>
    
    	</link>
    
    
    	<joint name = "base_footprint_fixed" type = "fixed">
    		<origin xyz = "0 0 0.03" rpy = "0 0 0"/>
    		<parent link = "base_footprint"/>
    		<child link = "base_link"/>
    	</joint>
    
    
    	<link name = "left_wheel">
    		<visual>
    			<origin xyz = "0 0 0" rpy = "1.570796 0 0" />
    			<geometry>
    				<cylinder length = "0.05" radius = "0.08" />
    			</geometry>
    			<material name ="blue"/>
    
    		</visual>
    		<collision>
    			<origin xyz = "0 0 0" rpy = "1.570796 0 0" />
    			<geometry>
    				<cylinder length = "0.05" radius = "0.08" />
    			</geometry>
    
    		</collision>
    		<inertial>
    			<mass value = "1.0" />
    			<inertia  ixx="1.0" ixy="0.0"  ixz="0.0"  iyy="1.0"  iyz="0.0"  izz="1.0" />
    		</inertial>
    
    
    
    	</link>
    
    	<link name = "right_wheel">
    		<visual>
    			<origin xyz = "0 0 0" rpy = "1.570796 0 0" />
    			<geometry>
    				<cylinder length = "0.05" radius = "0.08" />
    			</geometry>
    			<material name ="blue"/>
    
    		</visual>
    		<collision>
    			<origin xyz = "0 0 0" rpy = "1.570796 0 0" />
    			<geometry>
    				<cylinder length = "0.05" radius = "0.08" />
    			</geometry>
    
    		</collision>
    
    		<inertial>
    			<mass value = "1.0" />
    			<inertia  ixx="1.0" ixy="0.0"  ixz="0.0"  iyy="1.0"  iyz="0.0"  izz="1.0" />
    		</inertial>
    
    	</link>
    
    
    	<joint name = "left_wheel_joint" type = "continuous">
    		<origin xyz = "0.1 0.15 0" rpy = "0 0 0"/>
    		<parent link = "base_link"/>
    		<child link = "left_wheel"/>
    		<axis xyz = "0 1 0"/>
    
    	</joint>
    
    	<joint name = "right_wheel_joint" type = "continuous">
    		<origin xyz = "0.1 -0.15 0" rpy = "0 0 0"/>
    		<parent link = "base_link"/>
    		<child link = "right_wheel"/>
    		<axis xyz = "0 1 0" />
    
    	</joint>
    
    	<link name="scanner_link">
    		<visual>
    			<origin xyz="0 0 0" rpy = "0 0 0"/>
    			<geometry>
    				<cylinder length="0.05" radius="0.035"/>
    			</geometry>
    			<material name = "blueviolet"/>
    
    		</visual>
    		<collision>
    			<origin xyz="0 0 0" rpy = "0 0 0"/>
    			<geometry>
    				<cylinder length="0.05" radius="0.035"/>
    			</geometry>
    
    		</collision>
    		<inertial>
    			<mass value = "1.0" />
    			<inertia  ixx="1.0" ixy="0.0"  ixz="0.0"  iyy="10.0"  iyz="0.0"  izz="1.0" />
    		</inertial>
    
    	</link>
    
    	<joint name = "head_scanner" type = "fixed">
    		<origin xyz = "0.15 0 0" rpy = "0 1.5708 0"/>
    		<parent link = "base_link"/>
    		<child link = "scanner_link"/>
    	</joint>
    
    
    	<ros>
    		<namespace>/</namespace>
    		<argument>/cmd_vel:=cmd_vel</argument>
    	</ros>
    
    </robot>
    

    여기에 gazebo 파일을 설정해야 한다.

    now0930@amd2004:~/ros_test/workspace/src/wander_bot/urdf$ cat robot.gazebo 
    <?xml version="1.0"?>
    <robot>
    	<gazebo>
    		<plugin name="differential_drive_controller" filename="libgazebo_ros_diff_drive.so">
    			<legacyMode>false</legacyMode>
    			<updateRate>10</updateRate>
    			<alwaysOn>true</alwaysOn>
    			<leftJoint>left_wheel_joint</leftJoint>
    			<rightJoint>right_wheel_joint</rightJoint>
    			<torque>10</torque>
    			<robotBaseFrame>base_footprint</robotBaseFrame>
    			<wheelSeparation>0.4</wheelSeparation>
    			<wheelDiameter>0.2</wheelDiameter>
    			<publishWheelTF>false</publishWheelTF>
    			<publishTf>1</publishTf>
    			<commandTopic>cmd_vel</commandTopic>
    			<odometryTopic>odom</odometryTopic>
    			<odometryFrame>odom</odometryFrame>
    			<publishWheelJointState>false</publishWheelJointState>
    			<rosDebugLevel>na</rosDebugLevel>
    			<wheelAcceleration>0</wheelAcceleration>
    			<wheelTorque>5</wheelTorque>
    			<odometrySource>world</odometrySource>
    			<publishOdomTF>true</publishOdomTF>
    
    		</plugin>
    	</gazebo>
    
    </robot>
    

    모두 설정하고 roslaunch를 하면, 관성 모멘트가 잘못 되었는지 이상하게 움직인다.

  • gazebo에서 spawn model

    gazebo에서 spawn model

    물리 엔진을 가지고 있는 gazebo로 로봇을 만들지 않고도 쉽게 테스트 해 볼 수 있다. 기본 설정 파일이 있는데, 사용자가 취향에 맞춰 자유롭게 환경 설정을 할 수도 있다. 빈 공간에 각종 모듈을 불러 내 공간에 넣고, gazebo tutorial을 따르면 로봇도 spawn 가능하다.

    Programming Robots With Ros 책 144p에 보면 간단한 python 파일을 만들고 gazebo에 로딩하는 내용이 있다.

    http://wiki.ros.org/simulator_gazebo/Tutorials/SpawningObjectInSimulation

    https://github.com/ros-simulation/gazebo_ros_pkgs/issues/864

    사용자가 만든 urdf 파일을 gazebo 가상 환경에 spawn 할 수 있다. 다만 inetia를 모두 입력해야(틀린 값이라도 입력해야) gazebo가 인식한다. spawn_model가 gazebo_ros 패키지에 포함되어 있다. inetia 값을 입력하지 않으면 로딩이 안된다. 중간에 나오는 spawn service failed는 무시해도 괜찮은 듯 하다. 어쨋든 굴러 가니까.

    [INFO] [1662392890.824294, 55.975000]: Spawn status: SpawnModel: Entity pushed to spawn queue, but spawn service timed out waiting for entity to appear in simulation under the name agv_number1
    [ERROR] [1662392890.827400, 55.975000]: Spawn service failed. Exiting.
    https://github.com/ros-simulation/gazebo_ros_pkgs/issues/864

    launch 파일이다.

    <?xml version="1.0" encoding="UTF-8"?>
    
    <launch>
    	<!-- Robot pose -->
    	<arg name="x" default="0"/>
    	<arg name="y" default="0"/>
    	<arg name="z" default="1"/>
    	<arg name="roll" default="3.14"/>
    	<arg name="pitch" default="2"/>
    	<arg name="yaw" default="0"/>
    	<arg name="model_name"   default="agv_number1"/>
    
    		<!--<param name="robot_description" command = "cat $(find wander_bot)/urdf/robot.urdf"/>-->
    
    			<!-- We resume the logic in empty_world.launch, changing only the name of the world to be launched -->
    		<include file="$(find gazebo_ros)/launch/empty_world.launch">
    			<arg name="world_name" value="$(find wander_bot)/worlds/my_world"/>
    			<arg name="use_sim_time" value="true"/>
    				<!-- more default parameters can be changed here -->
    		</include>
    
    		<param name="robot_description" textfile = "$(find wander_bot)/urdf/robot.urdf" /> 
    			<!-- Spawn My Robot -->
    			<!--
    				<node name="urdf_spawner" pkg="gazebo_ros" type="spawn_model" respawn="false" output="screen" 
    				args="-urdf -param robot_description -model $(arg model_name) 
    				-x $(arg x) -y $(arg y) -z $(arg z)
    				-R $(arg roll) -P $(arg pitch) -Y $(arg yaw)"/>
    			-->
    				<node name="urdf_spawner" pkg="gazebo_ros" type="spawn_model" respawn="false" output="screen" 
    					args="-urdf -param robot_description -model $(arg model_name) 
    					-x $(arg x) -y $(arg y) -z $(arg z)
    					-R $(arg roll) -P $(arg pitch) -Y $(arg yaw)"/>
    
    
    				<node name="test_node" pkg="wander_bot" type="red_green_light.py"
    					args="/cmd_vel">
    			</node>
    		</launch>

    urdf 파일이다.

    <?xml version="1.0" ?>
    <robot name="mobile_robot" xmlns:xacro="http://www.ros.org/wiki/xacro">
    	<material name="blue">
    		<color rgba = "0 0 0.8 1"/>
    	</material>
    
    	<material name="gray">
    		<color rgba = "1 1 1 1"/>
    	</material>
    
    	<material name="blueviolet">
    		<color rgba = "0.54 0.16 0.88 1"/>
    	</material>
    
    
    
    	<link name = "base_footprint"/>
    
    	<link name="base_link">
    		<visual>
    			<origin xyz="0 0 0" rpy = "0 0 0"/>
    			<geometry>
    				<box size = "0.3 0.24 0.1" rpy = "0 0 0" />
    			</geometry>
    			<material name = "gray"/>
    
    		</visual>
    		<collision>
    			<origin xyz="0 0 0.03" rpy = "0 0 0"/>
    			<geometry>
    				<box size = "0.3 0.25 0.1" />
    			</geometry>
    
    		</collision>
    		<inertial>
    			<mass value = "1.0" />
    			<inertia  ixx="1.0" ixy="0.0"  ixz="0.0"  iyy="100.0"  iyz="0.0"  izz="1.0" />
    		</inertial>
    
    	</link>
    
    
    	<joint name = "base_footprint_fixed" type = "fixed">
    		<origin xyz = "0 0 0.03" rpy = "0 0 0"/>
    		<parent link = "base_footprint"/>
    		<child link = "base_link"/>
    	</joint>
    
    
    	<link name = "left_wheel">
    		<visual>
    			<origin xyz = "0 0 0" rpy = "1.570796 0 0" />
    			<geometry>
    				<cylinder length = "0.05" radius = "0.08" />
    			</geometry>
    			<material name ="blue"/>
    
    		</visual>
    		<collision>
    			<origin xyz = "0 0 0" rpy = "1.570796 0 0" />
    			<geometry>
    				<cylinder length = "0.05" radius = "0.08" />
    			</geometry>
    
    		</collision>
    		<inertial>
    			<mass value = "1.0" />
    			<inertia  ixx="1.0" ixy="0.0"  ixz="0.0"  iyy="100.0"  iyz="0.0"  izz="1.0" />
    		</inertial>
    
    
    
    	</link>
    
    	<link name = "right_wheel">
    		<visual>
    			<origin xyz = "0 0 0" rpy = "1.570796 0 0" />
    			<geometry>
    				<cylinder length = "0.05" radius = "0.08" />
    			</geometry>
    			<material name ="blue"/>
    
    		</visual>
    		<collision>
    			<origin xyz = "0 0 0" rpy = "1.570796 0 0" />
    			<geometry>
    				<cylinder length = "0.05" radius = "0.08" />
    			</geometry>
    
    		</collision>
    
    		<inertial>
    			<mass value = "1.0" />
    			<inertia  ixx="1.0" ixy="0.0"  ixz="0.0"  iyy="100.0"  iyz="0.0"  izz="1.0" />
    		</inertial>
    
    	</link>
    
    
    	<joint name = "left_wheel_joint" type = "continuous">
    		<origin xyz = "0.1 0.15 0" rpy = "0 0 0"/>
    		<parent link = "base_link"/>
    		<child link = "left_wheel"/>
    		<axis xyz = "0 1 0"/>
    
    	</joint>
    
    	<joint name = "right_wheel_joint" type = "continuous">
    		<origin xyz = "0.1 -0.15 0" rpy = "0 0 0"/>
    		<parent link = "base_link"/>
    		<child link = "right_wheel"/>
    		<axis xyz = "0 1 0" />
    
    	</joint>
    
    	<link name="scanner_link">
    		<visual>
    			<origin xyz="0 0 0" rpy = "0 0 0"/>
    			<geometry>
    				<cylinder length="0.05" radius="0.035"/>
    			</geometry>
    			<material name = "blueviolet"/>
    
    		</visual>
    		<collision>
    			<origin xyz="0 0 0" rpy = "0 0 0"/>
    			<geometry>
    				<cylinder length="0.05" radius="0.035"/>
    			</geometry>
    
    		</collision>
    		<inertial>
    			<mass value = "1.0" />
    			<inertia  ixx="1.0" ixy="0.0"  ixz="0.0"  iyy="100.0"  iyz="0.0"  izz="1.0" />
    		</inertial>
    
    	</link>
    
    	<joint name = "head_scanner" type = "fixed">
    		<origin xyz = "0.15 0 0" rpy = "0 1.5708 0"/>
    		<parent link = "base_link"/>
    		<child link = "scanner_link"/>
    	</joint>
    
    </robot>

    직접 해보기도 좋지만, 남이 한 프로젝트를 보는게 더 빠르다.

  • 코로나 디바이드 시대가 온다

    코로나 디바이드 시대가 온다

    isbn: 9791192044064

    코비드 19를 겪으면서 양극화가 어떻게 진행되었는지를 설명한다. 디지털, 기업, 지역 양극화 3가지 관점으로 바라보았고, 양극화 정도가 심해졌다고 한다.

    코로나를 겪으면서 표현되는 양극화가 반드시 나쁘지는 않다. 지금까지 우리가 경험했던 시스템이 인류에게 편리함을 줬지만 환경에 많은 부담을 주었다. 코로나 19는 지금까지 부담을 받은 환경이 인류에게 주는 경고라고 인식해야 한다. 출퇴근으로 자동차가 뱉어내는 탄소 배출량이 코로나 19로 인한 재택근무로 바뀌어 배출량이 줄어 들었다. 기업은 업무 효율이 떨어질 수 있으나, 장기적으로 바라보면 탄소 배출량이 줄어들어 환경에 대한 부담이 적어진다. 여행을 가기 위해 이용하는 항공기 역시 환경에 많은 부담을 준다.

    코로나가 과거 탄소를 많이 소비하는 시대가 틀렸음을 증명했고, 탄소 중립으로 가기 위한 시작점으로 인식해야 한다. 양극화는 기존 시스템이 틀렸다고 보면 이를 보완하기 위해 새로운 방법으로 복지, 정부 지출, 투자 등 을 고려해야 한다.