Driver Read AllState#

What you’ll do

  • Driver에서 AllState 폴링(보조 명령)을 켜고, 큐에서 AllState를 처리합니다.

Prerequisites

Next


Driver에서 AllState(보조 명령)를 주기적으로 요청하고 큐에서 AllState를 처리합니다. 포트 open/Driver::start() 절차는 Driver Demo와 동일하므로, 여기서는 설정과 큐 처리만 정리합니다.


1. 목표#

  • AllState 폴링 활성화 (보조 명령)

  • tryPopMessage()AllState를 받아 출력


2. 단계별 구현 가이드#

단계 1) AllState 폴링 설정#

옵션 필드 의미는 Driver::Options를 기준으로 합니다.

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.poll_allstate = true;
opt.allstate_rate_hz = 10.0;
opt.allstate_motor_left = 0;
opt.allstate_motor_right = 1;

opt.command_timeout_ms = 0; // 명령 업데이트 없이 0,0 유지

단계 2) 큐에서 AllState만 처리#

while (auto msg = drv.tryPopMessage()) {
  if (auto* st = std::get_if<KMC_HARDWARE::AllState>(&*msg)) {
    std::printf(
        "AllState: id=%u pos=%.2f deg rpm=%.1f current=%.2f A temp=%.1f C "
        "err=0x%08X\n",
        st->id,
        st->position_deg,
        st->speed_rpm,
        st->current_A,
        st->temperature_C,
        st->error_code);
  }
}

참고

AllState.error_code의 비트 정의는 UART Protocol Reference의 AllState 섹션을 기준으로 해석합니다.


3. Result#

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

#include "KMC_driver.hpp"

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

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.poll_allstate = true;
  opt.allstate_rate_hz = 10.0;
  opt.allstate_motor_left = 0;
  opt.allstate_motor_right = 1;

  opt.command_timeout_ms = 0;

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

  drv.setCommand(0.0f, 0.0f);

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

  while (std::chrono::steady_clock::now() - t0 <
         std::chrono::seconds(seconds)) {
    while (auto msg = drv.tryPopMessage()) {
      if (auto* st = std::get_if<KMC_HARDWARE::AllState>(&*msg)) {
        std::printf(
            "AllState: id=%u pos=%.2f deg rpm=%.1f current=%.2f A temp=%.1f C "
            "err=0x%08X\n",
            st->id,
            st->position_deg,
            st->speed_rpm,
            st->current_A,
            st->temperature_C,
            st->error_code);
      }
    }
    std::this_thread::sleep_for(std::chrono::milliseconds(5));
  }

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