# Driver Demo

**What you’ll do**
- `Driver`클래스를 사용하여 UART 포트열고 초기화 합니다.
- **명령 입력** ($v, \omega$)을 내부 스레드를 이용해 일정주기로 유지합니다.
- `setCommand(v, omega)`로 목표값을 설정하고 일정 시간 송신합니다.

**Prerequisites**
- {doc}`SDK Guide </page/SDK/sdk_guide>`
- {doc}`Linux Port Setup </page/Setup_Test/linux_port_setup>` (Ubuntu)

**Next**
- {doc}`Driver Observe </page/SDK/tutorials/driver_observe>`
- {doc}`C++ API Reference </page/SDK/sdk_reference>`

---

이 튜토리얼은 `KMC_HARDWARE::Driver`를 사용하여 가장 기본적인 주행 명령 송신을 구현하는 방법을 다룹니다.

```{admonition} 주의
:class: warning

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

---

## 1. 목표

1. 시리얼 포트를 열고 통신 옵션을 설정합니다.
2. 내부 스레드가 **명령 입력**과 **속도 요청**을 처리하는 것을 이해합니다.
3. `setCommand()`로 고정 명령을 넣고 일정 시간 동안 송신을 유지합니다.

---

## 2. 배경

UART 통신에서 타이밍은 매우 중요합니다. 사용자 코드가 복잡한 연산(인지/계획)을 수행하느라 통신 주기가 밀리면, 차량은 제어 명령을 제때 받지 못해 정지하거나 불안정해질 수 있습니다.
`KMC_HARDWARE::Driver`는 이 문제를 해결하기 위해 별도의 I/O 스레드를 사용합니다.
- **Main Thread** (User): `setCommand(v, omega)`를 호출하여 **목표값**을 업데이트합니다. 
- **Driver Thread** (Internal): 설정된 주기(예: $100\,\mathrm{Hz}$)에 맞춰 가장 최신의 목표값을 UART로 송신합니다.

---

## 3. 준비

- 포트 문자열 예: `/dev/ttyKMC` (환경마다 다름)
- 보드가 사용하는 baud (예: `115200`, `921600`)
- RTS/CTS 하드웨어 플로우컨트롤(필수) 활성화
- USB 권한 설정(예: Ubuntu `dialout`)

---

## 4. 단계별 구현 가이드

### 단계 1) 필요한 include

`KMC_driver.hpp `헤더 하나만 include하면 `Driver` 클래스와 관련 옵션 구조체를 모두 사용할 수 있습니다.

```cpp
#include "KMC_driver.hpp"
```

---

### 단계 2) CLI 뼈대 (port, seconds)

프로그램 실행 시 포트 경로와 실행 시간을 인자로 받을 수 있도록 구성합니다.

```cpp
#include <cstdio>
#include <cstdlib>
#include <string>

int main(int argc, char **argv) {
  // 인자가 없으면 기본값 사용 (/dev/ttyKMC, 5초)
  const std::string port = (argc > 1) ? argv[1] : "/dev/ttyKMC";
  int seconds = (argc > 2) ? std::atoi(argv[2]) : 5;
  if (seconds <= 0) seconds = 5;

  return 0;
}
```

---

### 단계 3) `Driver` 객체 생성 및 옵션 설정

`Driver`는 실행 중에 다음을 설정해야 합니다.

- port
- baud/RTS/CTS 같은 시리얼 설정
- **명령 입력**, **속도 요청**, **보조 명령**을 몇 $\mathrm{Hz}$로 돌릴지
- timeout 시간

이 설정을`Driver::Options` 구조체로 전달합니다. 필드 정의는 {ref}`Driver::Options <sdk-driver-options>`를 참고하세요.

```cpp
  KMC_HARDWARE::Driver drv;
  KMC_HARDWARE::Driver::Options opt;
  opt.port = port;

  // 1. 시리얼 설정
  opt.serial.baudrate = 115200;           // 보드 설정에 맞추기
  opt.serial.hw_flow_control = true;      // RTS/CTS 사용
  opt.serial.rts_always_on = true;        // RTS assert 유지(기본값)

  // 2. 루프 주기(Hz) 설정
  opt.control_rate_hz = 100.0;        // 명령 입력 송신 주기 (100 Hz)
  opt.vehicle_speed_rate_hz = 1.0;    // 속도 요청 주기 (최소화)

  // 3. 안전 옵션
  // 데모에서는 한번 setCommand()하는 명령을 구현하는 튜토리얼이므로, timeout을 끕니다.
  opt.command_timeout_ms = 0;
```

- `control_rate_hz`: 차량 제어의 부드러움을 결정합니다. $200 \sim 400,\mathrm{Hz}$을 권장합니다.
- `vehicle_speed_rate_hz`: 이 예제에서는 송신에 집중하기 위해 수신 요청 주기를 $1,\mathrm{Hz}$로 낮췄습니다.

```{admonition} 참고
:class: note

이 데모는 `command_timeout_ms=0`으로 타임아웃을 꺼 둡니다. 실제 운용에서는 {doc}`SDK Guide </page/SDK/sdk_guide>`의 권장 패턴처럼 주기 업데이트 + 타임아웃을 사용하세요.
```

---

### 단계 4) `start()` 호출

```cpp
  if (!drv.start(opt)) {
    std::fprintf(stderr, "Failed to open %s\n", port.c_str());
    return 2;
  }
```

`start()`의 동작:
1. 시리얼 포트를 열고
2. 입력 버퍼를 비우고
3. 내부 I/O 스레드를 생성해 **명령 입력**/**속도 요청**/**보조 명령** 루프를 시작합니다.

---

### 단계 5) 명령 설정

차량에 보낼 목표 속도를 설정합니다.


```cpp
  // 전진 속도 0.5 m/s, 회전 각속도 0.0 rad/s (직진)
  drv.setCommand(0.5f, 0.0f);
```
* 이 함수는 UART로 즉시 데이터를 보내지 않습니다. 내부 변수를 thread-safe하게 업데이트만 합니다.
* 실제 전송은 백그라운드 스레드가 다음 주기가 되었을 때 수행합니다.

---

### 단계 6) 실행 루프 유지 및 종료

이 단계에서는 일정 시간 동안 루프를 유지하고 주기적으로 상태를 출력합니다.

```cpp
  #include <thread>
  #include <chrono>

  // ... (main 내부)

  const auto t0 = std::chrono::steady_clock::now();
  auto next_status = t0;

  while (std::chrono::steady_clock::now() - t0 < std::chrono::seconds(seconds)) {
    const auto now = std::chrono::steady_clock::now();

    // 1초마다 상태 출력
    if (now >= next_status) {
      const auto elapsed =
          std::chrono::duration_cast<std::chrono::seconds>(now - t0).count();
      std::printf("[running] t=%llds cmd=0.5 m/s\n",
                  static_cast<long long>(elapsed));
      next_status += std::chrono::seconds(1);
    }
    std::this_thread::sleep_for(std::chrono::milliseconds(10));
  }

  // 종료 처리
  drv.setCommand(0.0f, 0.0f); // 정지 명령
  drv.stop();                 // 스레드 종료 및 포트 close
```

`stop()`의 동작:
- 내부 스레드 종료 + join
- Best-effort로 `(0,0)`을 여러 번 송신(optional)
- port 닫기

---

## 5. Result

아래 코드는 SDK 리포지토리의 `examples/Driver_Basic/driver_demo.cpp`와 동일한 내용입니다.

```cpp
#include "KMC_driver.hpp"

#include <chrono>
#include <cstdio>
#include <cstdlib>
#include <string>
#include <thread>

int main(int argc, char **argv) {
  const std::string port = (argc > 1) ? argv[1] : "/dev/ttyKMC";
  int seconds = (argc > 2) ? std::atoi(argv[2]) : 5;
  if (seconds <= 0) seconds = 5;

  KMC_HARDWARE::Driver drv;
  KMC_HARDWARE::Driver::Options opt;
  opt.port = port;
  opt.serial.baudrate = 115200;

  opt.control_rate_hz = 100.0;
  opt.vehicle_speed_rate_hz = 1.0;
  opt.command_timeout_ms = 0;

  if (!drv.start(opt)) {
    std::fprintf(stderr, "Failed to open %s\n", port.c_str());
    return 2;
  }

  const auto t0 = std::chrono::steady_clock::now();
  auto next_status = t0;

  // Demo: command a small forward speed (constant value).
  drv.setCommand(0.5f, 0.0f);

  while (std::chrono::steady_clock::now() - t0 < std::chrono::seconds(seconds)) {
    const auto now = std::chrono::steady_clock::now();
    if (now >= next_status) {
      const auto elapsed =
          std::chrono::duration_cast<std::chrono::seconds>(now - t0).count();
      std::printf("[running] t=%llds cmd=0.5 m/s\n",
                  static_cast<long long>(elapsed));
      next_status += std::chrono::seconds(1);
    }
    std::this_thread::sleep_for(std::chrono::milliseconds(10));
  }

  drv.setCommand(0.0f, 0.0f);
  drv.stop();
  return 0;
}
```
