Quick Start#

What you’ll do

  • Ubuntu에서 UART 포트를 /dev/ttyKMC로 고정합니다.

  • SDK 예제로 차량에 \((v,\omega)\) 명령을 전송합니다.

  • 속도 요청으로 차량 속도 \(v\)(\(\mathrm{m/s}\))를 읽어 출력합니다.

Prerequisites

  • Ubuntu 20.04 이상, sudo 권한

  • 차량 전원 및 USB(UART) 연결

  • SDK 소스 코드

Next


주의

초기 테스트는 바퀴가 공중에 뜬 상태 또는 아주 낮은 속도에서 진행하세요.


1. 포트 설정 (/dev/ttyKMC)#

USB-Serial 장치를 꽂은 뒤 아래를 확인합니다.

ls -l /dev/ttyKMC
ls -l /dev/ttyUSB*
lsusb

/dev/ttyKMC가 이미 있다면 이 단계는 건너뛰어도 됩니다.

udev 규칙 추가 (권장)#

lsusb에서 확인한 VID:PID를 아래 규칙에 반영합니다.

sudo tee /etc/udev/rules.d/99-usb-serial-kmc.rules >/dev/null <<'EOF'
SUBSYSTEM=="tty", ATTRS{idVendor}=="0403", ATTRS{idProduct}=="6014", SYMLINK+="ttyKMC", MODE="0660", GROUP="dialout"
EOF

sudo udevadm control --reload-rules
sudo udevadm trigger
sudo usermod -aG dialout "$USER"

참고

  • idVendor, idProduct 값이 다르면 /dev/ttyKMC가 생성되지 않습니다.

  • dialout 그룹 적용은 로그아웃/로그인 후 반영됩니다.

USB 장치를 한 번 뺐다가 다시 꽂고, 링크가 생겼는지 확인합니다.

ls -l /dev/ttyKMC

2. SDK 빌드#

github repository에서 sdk를 clone합니다.

git clone https://github.com/Seo12044/KAIST_Mobility_Challenge_SDK.git
cd KAIST_Mobility_Challenge_SDK/

SDK 리포지토리 루트에서 빌드합니다.

cmake -S . -B build -DCMAKE_BUILD_TYPE=Release
cmake --build build -j

3. 제어 + 속도 읽기 예제 실행#

아래 예제는 명령 입력을 주기적으로 전송하면서, 속도 요청 결과를 출력합니다.

./build/driver_observe

출력 예시:

  • VehicleSpeed: ... m/s

문제 해결

  • 수신이 전혀 없으면 RTS/CTS가 활성화되어 있는지와 baud rate를 먼저 확인하세요.

  • /dev/ttyKMC 대신 /dev/ttyUSB0 같은 실제 포트를 직접 넣어도 됩니다.


4. ROS2 노드 실행#

ROS2를 사용한다면 kmc_hardware_driver_node 패키지를 빌드해 /cmd_vel로 제어할 수 있습니다.

4.1 빌드#

source /opt/ros/$ROS_DISTRO/setup.bash

cd KAIST_Mobility_Challenge_SDK/examples/Driver_ROS2

colcon build --symlink-install
source install/setup.bash

4.2 노드 실행 (속도, 배터리 publish)#

ros2 run kmc_hardware_driver_node kmc_hardware_driver_observe_node \
  --ros-args -p port:=/dev/ttyKMC -p baud:=115200 -p battery_hz:=1.0

4.3 제어 입력 (/cmd_vel)#

geometry_msgs/msg/Twist에서 linear.x\(v\)(\(\mathrm{m/s}\)), angular.z\(\omega\)(\(\mathrm{rad/s}\))입니다.

ros2 topic pub /cmd_vel geometry_msgs/msg/Twist \
  '{linear: {x: 0.5}, angular: {z: 0.0}}' -r 50

4.4 속도 확인 (/vehicle_speed)#

ros2 topic echo /vehicle_speed

추가 노드/토픽/파라미터는 ROS2 Driver Tutorials를 참고하세요.