
📘 RBQ ROS2 SDK 소개
RBQ ROS2 SDK 메뉴얼에 오신 것을 환영합니다.
- 이 가이드는 ROS2를 통해 RBQ 로봇을 시뮬레이션과 실제 하드웨어에서 제어하고 시각화하는 방법을 빠르게 시작할 수 있도록 도와줍니다.
이 SDK가 제공하는 기능
이 SDK는 다음과 같은 주요 기능을 제공합니다:
- 로봇 제어: 자세 제어, 보행 전환, 위치 기반 내비게이션 실행
- 센서 피드백 스트리밍: IMU, 발 접촉, 배터리 상태 등 지속적인 데이터 제공
- 비전 데이터 스트리밍: 전방, 후방, 하방 및 좌우 카메라 데이터를 제공하여 인지 및 내비게이션 지원
- RViz2 시각화: 로봇 상태 및 LiDAR 등 센서를 실시간으로 시각화
💻 시스템 요구사항
| 구성 요소 | 필요 환경 |
|---|---|
| 운영체제 | |
| ROS 2 배포판 | |
| Python 버전 |
📝 아래의 모든 CLI 명령어는 메인 디렉토리에서 실행하는 것을 기준으로 합니다.
🛠️ 환경 설정
이 패키지는
Ubuntu 22.04및ROS 2 Humble에서 테스트되었습니다. 설치는 다음 명령어로 진행합니다.bashbash scripts/install/ros.bashROS Humble 환경 불러오기:
bashsource /opt/ros/humble/setup.bashrosdep 초기화 및 의존성 업데이트:
bashsudo rosdep init && rosdep update
📦 설치
ros2디렉토리로 이동 후 ROS 의존성 설치bashcd ros2 rosdep install --from-paths src -y --ignore-srcrbq_ros2패키지 빌드bashcolcon build --symlink-install
▶️ 노드 실행
rbq_driver실행- 시뮬레이션 환경에서는
-s인자 추가
- 시뮬레이션 환경에서는
source ros2/install/local_setup.bash
ros2 run rbq_driver rbq_driverRBQ 드라이버는 ROS 2에서 RBQ 제어에 필요한 모든 토픽을 포함하고 있습니다
rbq_driver 실행 시 시작되는 노드들:
- 로봇 상태 (Robot state) publisher
- 센서 피드백 퍼블리셔 (IMU, 배터리, 발 접촉)
- 비전 데이터 퍼블리셔 (전방, 후방, 좌우, 하방 카메라)
- 상위 제어 명령 (High-level command) subscriber
rbq_description실행bashsource ros2/install/local_setup.bash ros2 launch rbq_description description.launch.py
🧪 활성 토픽 확인
source ros2/install/local_setup.bash
ros2 topic list로봇 상태값
🦿 1. 보행 토픽 (Gait State)
Gait state는 로봇의 현재 보행 모드나 자세 모드를 의미합니다. 이 상태 전환은 상위 제어, 센서 조건, 내부 로직에 의해 발생합니다.

사용 가능한 보행 :
| State ID | 상태 | 설명 |
|---|---|---|
| -2 | Fall Mode | 예기치 않게 균형을 잃었을 때 진입하는 모드 |
| -1 | Control Off | 모든 구동기가 비활성화됨 |
| 0 | Sitting | 낮은 자세, 바닥에 앉아 있는 상태 |
| 1 | Standing | 기본 자세, 보행 준비 상태 |
| 2 | Walk Mode | 트롯 보행 모드 |
| 3 | Aim Mode | 조준을 위한 조준 자세 |
| 4 | Stairs Mode | 카메라 센서를 이용한 계단 적응 보행 모드 |
| 5 | Wave Mode | 워크 보행 모드 |
| 6 | Run Mode | 고속 보행 모드 (지원되는 경우) |
| 30 | RL Trot | 강화학습 트롯 보행 |
| 31 | RL Front Walk | 강화학습 물구나무 보행 |
| 33 | RL Left Walk | 강화학습 레프트 워크 보행 |
| 34 | RL Right Walk | 강화학습 라이트 워크 보행 |
| 35 | RL Bound | 강화학습 바운드 보행 |
| 36 | RL Pace | 강화학습 페이스 보행 |
| 37 | RL Pronk | 강화학습 프롱크 보행 |
| 38-41 | RL 3Leg | 강화학습 3다리 보행 (HR, HL, FR, FL) |
| 42 | RL Trot Vision | 강화학습 비전 트롯 보행 |
| 45 | RL Trot Run | 강화학습 트롯 런 보행 |
| 46 | RL Silent | 강화학습 사일런트 보행 |
두 번째 열에 있는 **사용 가능한 명령(Available Commands)**은 각 보행 상태에서 사용할 수 있는 명령을 보여줍니다. 반대로, **공통 명령(Common Commands)**과 **전원 제어(Power Control)**는 보행 상태와 관계없이 항상 사용할 수 있습니다.
참고: 모든 보행 전환은 특정
gait_id값을 사용하는 통합된rbq/motion/switchGait토픽을 사용합니다.
사용 가능한 gait_id 값은 위의 "사용 가능한 보행 상태(Available Gait States)" 표를 참조하세요.
| 보행 상태 (Gait State) | 사용 가능한 명령(Available Commands) | 공통 명령(Common Commands) | 전원 제어(Power Control) |
|---|---|---|---|
| Control Off | rbq/motion/autoStart | rbq/powerControl/setPortState # PDU Port ID int8 PDU_PORT_48V_LEG = 0x00 int8 PDU_PORT_48V_ADD = 0x01 int8 PDU_PORT_48V_EXT = 0x02 int8 PDU_PORT_12V_VisionPC = 0x10 int8 PDU_PORT_12V_COMM = 0x11 int8 PDU_PORT_12V_Lidar = 0x12 int8 PDU_PORT_12V_CCTV = 0x13 int8 PDU_PORT_12V_THER = 0x14 int8 PDU_PORT_12V_IRLed = 0x15 int8 PDU_PORT_12V_Speaker = 0x16 int8 PDU_PORT_5V_CAMERAS = 0x20 int8 PDU_PORT_5V_AUDIO_SIDE_CAM_USBHUB = 0x21 | |
| Sitting Mode | rbq/motion/canCheck | rbq/motion/switchGait (gait_id: 0-46) rbq/motion/cmd_highLevel rbq/motion/emergency rbq/motion/staticLock rbq/motion/staticReady rbq/motion/staticGround rbq/gamepad/switchControlMode (true:HighLevel Mode, false:JoyStick Mode) | |
| Standing Mode | rbq/motion/cmd_navigateTo rbq/stateEstimation/comEstimationCompensation | ||
| Walk Mode | - | ||
| Stairs Mode | - | ||
| Run Mode | - | ||
| Wave Mode | rbq/motion/cmd_navigateTo | ||
| RL Mode | - | ||
| Fall Mode | rbq/motion/recoveryFlex rbq/motion/switchGait (gait_id: 1) | ||
📡 2. 로우 레벨 토픽 (Low-level State Topics)
이 토픽들은 로봇의 내부 상태, 즉 자세, 센서값, 시스템 상태에 대한 실시간 피드백을 제공합니다.
| 토픽 | 데이터 구조 | 설명 |
|---|---|---|
| rbq/status/robot_status | std_msgs/Header header bool con_start bool ready_pos bool ground_pos bool force_con bool ext_joy bool is_standing bool can_check bool find_home int8 gait_id bool is_fall int8 docking_state bool imu_success | 이 메시지는 로봇 상태 정보를 포함하며 50Hz로 발행됩니다. 모터 제어 상태, 위치 상태, 통신 상태, 보행 정보, 도킹 상태를 포함합니다. 사용 가능한 gait_id 값은 위의 "사용 가능한 보행" 표를 참조하세요. # Docking States int8 DOCKING_MAX_FAIL_CNT_REACHED = -6 int8 DOCKING_MARKER_POS_INVALID_ROTATION = -5 int8 DOCKING_MARKER_POS_INVALID_TOO_FAR = -4 int8 DOCKING_MARKER_POS_INVALID_WRONG_DIR = -3 int8 DOCKING_MARKER_NOT_FOUND = -2 int8 DOCKING_FAILED = -1 int8 DOCKING_OPERATION_MODE = 0 int8 DOCKING_APPROACH_OFFSET = 1 int8 DOCKING_APPROACH = 2 int8 DOCKING_APPROACH_WIDE = 3 int8 DOCKING_SIT_DOWN = 4 int8 DOCKING_SUCCESS = 5 int8 DOCKING_SUCCESS_CHARGING = 6 int8 DOCKING_SUCCESS_NO_CHARGING = 7 |
| rbq/powerControl/battery_status | std_msgs/Header header string identifier float64 charge_percentage float64 current float64 voltage float64[] temperatures uint8 status | # Status uint8 STATUS_UNKNOWN = 0 uint8 STATUS_MISSING = 1 uint8 STATUS_CHARGING = 2 uint8 STATUS_DISCHARGING = 3 uint8 STATUS_BOOTING = 4 |
| rbq/stateEstimation/footStates | std_msgs/Header header geometry_msgs/Point[] foot_position_rt_body geometry_msgs/Point[] foot_velocity_rt_body uint8[] contact | 로컬 바디 프레임 기준의 발 위치와 속도입니다. 바디 프레임의 원점은 로봇 몸체의 중심에 있으며, 앞쪽 방향은 +x, 왼쪽 방향은 +y, 위쪽 방향은 +z로 정의됩니다. 모든 배열은 4개의 요소를 포함합니다 (각 다리당 하나). # Contact uint8 CONTACT_UNKNOWN = 0 uint8 CONTACT_MADE = 1 uint8 CONTACT_LOST = 2 # Leg number Leg num 0 : Right-Hind leg (RH) Leg num 1 : Left-Hind Leg (LH) Leg num 2 : Right-Front Leg (RF) Leg num 3 : Left-Front Leg (LF) |
| rbq/joint/joint_status | std_msgs/Header header bool[] connected int8[] temperature int8[] motor_temp bool[] status_fet bool[] status_run bool[] status_init bool[] status_mod bool[] status_non_ctr bool[] status_bat bool[] status_calib bool[] status_mt_err bool[] status_jam bool[] status_cur bool[] status_big bool[] status_inp bool[] status_flt bool[] status_tmp bool[] status_ps1 bool[] status_ps2 bool[] status_rsvd float32[] position_ref float32[] position_enc float32[] velocity float32[] torque_ref float32[] current float32[] kp float32[] kd int32[] owner | 이 메시지는 연결 상태, 온도, 모터 상태 플래그, 제어 데이터를 포함한 상세한 관절 정보를 포함합니다. 각 관절에 대해 50Hz로 발행됩니다. |
상태(State) 메시지는 다음과 같이 정의됩니다:
- RobotStatus
# DOCKING_STATE
int8 DOCKING_MAX_FAIL_CNT_REACHED = -6 # (중단 시퀀스) 최대 도킹 재시도 횟수 도달 (10회)
int8 DOCKING_MARKER_POS_INVALID_ROTATION = -5 # (중단 시퀀스) 마커 회전 각도가 +-40도 초과
int8 DOCKING_MARKER_POS_INVALID_TOO_FAR = -4 # (중단 시퀀스) 마커가 5m 이상 너무 멀리 있음
int8 DOCKING_MARKER_POS_INVALID_WRONG_DIR = -3 # (중단 시퀀스) 마커가 로봇 전면에서 감지됨
int8 DOCKING_MARKER_NOT_FOUND = -2 # (중단 시퀀스) 마커를 찾을 수 없음
int8 DOCKING_FAILED = -1 # 도킹 실패 --> 자동 재시도
int8 DOCKING_OPERATION_MODE = 0 # 로봇이 정상 작동 중
int8 DOCKING_APPROACH_OFFSET = 1 # 1차 오프셋으로 충전기에 도달
int8 DOCKING_APPROACH = 2 # 2차 충전기에 도달
int8 DOCKING_APPROACH_WIDE = 3 # 3차 넓은 자세로 충전기에 도달
int8 DOCKING_SIT_DOWN = 4 # 충전기에 앉기
int8 DOCKING_SUCCESS = 5 # 도킹 성공 : 충전기 연결됨
int8 DOCKING_SUCCESS_CHARGING = 6 # 도킹 성공 : 충전 중
int8 DOCKING_SUCCESS_NO_CHARGING = 7 # 도킹 성공 : 충전 안됨
# gait_state constants
int8 STATE_FALL = -2 # Fall Mode - 예상치 못한 균형 상실 시 트리거됨
int8 STATE_OFF = -1 # Control Off - 모든 액추에이터 비활성화
int8 STATE_SIT = 0 # Sitting - 낮은 자세로 바닥에 휴식
int8 STATE_STAND = 1 # Standing - 중립 자세로 보행 준비
int8 STATE_WALK = 2 # Walk Mode - walking Trot 보행
int8 STATE_AIM = 3 # Aim Mode - 타겟팅을 위한 조준 자세
int8 STATE_STAIRS = 4 # Stairs Mode - 카메라 센서를 사용한 계단 적응 보행
int8 STATE_WAVE = 5 # Wave Mode - walking Walk 보행
int8 STATE_RUN = 6 # Run Mode - 고속 보행 (지원되는 경우)
int8 STATE_RL_TROT = 30 # RL Trot - 강화 학습 Trot 보행
int8 STATE_RL_FRONT_WALK = 31 # RL Front Walk - 강화 학습 Front Walk 보행
int8 STATE_RL_LEFT_WALK = 33 # RL Left Walk - 강화 학습 Left Walk 보행
int8 STATE_RL_RIGHT_WALK = 34 # RL Right Walk - 강화 학습 Right Walk 보행
int8 STATE_RL_BOUND = 35 # RL Bound - 강화 학습 Bound 보행
int8 STATE_RL_PACE = 36 # RL Pace - 강화 학습 Pace 보행
int8 STATE_RL_PRONK = 37 # RL Pronk - 강화 학습 Pronk 보행
int8 STATE_RL_3LEG_HR = 38 # RL 3Leg HR - 강화 학습 3-Leg 보행 (Hind Right)
int8 STATE_RL_3LEG_HL = 39 # RL 3Leg HL - 강화 학습 3-Leg 보행 (Hind Left)
int8 STATE_RL_3LEG_FR = 40 # RL 3Leg FR - 강화 학습 3-Leg 보행 (Front Right)
int8 STATE_RL_3LEG_FL = 41 # RL 3Leg FL - 강화 학습 3-Leg 보행 (Front Left)
int8 STATE_RL_TROT_VISION = 42 # RL Trot Vision - 강화 학습 Vision을 사용한 Trot 보행
int8 STATE_RL_TROT_RUN = 45 # RL Trot Run - 강화 학습 Trot Run 보행
int8 STATE_RL_SILENT = 46 # RL Silent - 강화 학습 Silent 보행
std_msgs/Header header
bool con_start # 모터 제어 활성화 (1 = 활성화, 0 = 비활성화)
bool ready_pos # 로봇이 준비 위치에 있음 (1 = 준비됨, 0 = 준비 안됨)
bool ground_pos # 로봇이 바닥/앉은 위치에 있음 (1 = 앉음, 0 = 앉지 않음)
bool force_con # 힘 제어 모드 활성화 (1 = 활성화, 0 = 비활성화)
bool ext_joy # 외부 조이스틱 연결됨 (1 = 연결됨, 0 = 연결 안됨)
bool is_standing # 로봇이 서 있음 (1 = 서있음, 0 = 서있지 않음)
bool can_check # CAN 통신 확인 (1 = 성공, 0 = 실패)
bool find_home # 엔코더 홈 찾기 상태 (1 = 성공, 0 = 실패)
int8 gait_id # 현재 보행 모드 식별자 (GAIT_STATE 열거형에 정의된 값 반환)
bool is_fall # 낙하 감지 상태 (1 = 로봇이 넘어짐, 0 = 정상)
int8 docking_state # 도킹 프로세스 상태 (DOCKING_STATE 열거형에 정의된 값 반환)
bool imu_success # IMU 연결 상태 (1 = 성공, 0 = 실패)- JointStatus
std_msgs/Header header
# 관절 상세 정보
# 연결 및 온도 상태
bool[] connected # 관절 연결 상태 (true = 연결됨, false = 연결 안됨)
int8[] temperature # 보드 온도 (섭씨)
int8[] motor_temp # 모터 온도 (섭씨)
# 모터 상태 플래그
bool[] status_fet # FET (전계 효과 트랜지스터) 상태 (true = ON, false = OFF)
bool[] status_run # 모터 실행 상태 (true = 실행 중, false = 정지)
bool[] status_init # 초기화 상태 (true = 초기화됨, false = 초기화 안됨)
bool[] status_mod # 제어 모드 상태 (true = 위치 제어, false = 토크 제어)
bool[] status_non_ctr # non 카운트 오류 (true = 오류, false = 정상)
bool[] status_bat # 배터리 상태 (true = 배터리 부족, false = 정상)
bool[] status_calib # 보정 상태 (true = 보정 모드, false = 정상)
bool[] status_mt_err # 모터 오류 상태 (true = 오류, false = 정상)
bool[] status_jam # JAM 오류 상태 (true = 걸림, false = 정상)
bool[] status_cur # 과전류 오류 (true = 과전류, false = 정상)
bool[] status_big # 큰 위치 오류 (true = 큰 오류, false = 정상)
bool[] status_inp # 입력 오류 (true = 입력 오류, false = 정상)
bool[] status_flt # FET 드라이버 결함 오류 (true = 결함, false = 정상)
bool[] status_tmp # 온도 오류 (true = 과온, false = 정상)
bool[] status_ps1 # 위치 제한 오류 - 하한 (true = 제한 도달, false = 정상)
bool[] status_ps2 # 위치 제한 오류 - 상한 (true = 제한 도달, false = 정상)
bool[] status_rsvd # 예약된 상태 비트
# 제어 데이터
float32[] position_ref # 기준 위치 (라디안)
float32[] position_enc # 엔코더 위치 (라디안)
float32[] velocity # 관절 속도 (rad/s)
float32[] torque_ref # 기준 토크 (Nm)
float32[] current # 모터 전류 (암페어)
float32[] kp # 비례 이득 (P 이득)
float32[] kd # 미분 이득 (D 이득)
int32[] owner # 관절 소유자 ID (어떤 컨트롤러가 이 관절을 소유하는지)- BatteryState
# Status
uint8 STATUS_UNKNOWN = 0
uint8 STATUS_MISSING = 1
uint8 STATUS_CHARGING = 2
uint8 STATUS_DISCHARGING = 3
uint8 STATUS_BOOTING = 4
std_msgs/Header header
string identifier
float64 charge_percentage
float64 current
float64 voltage
float64[] temperatures
uint8 status- FootStates
# Contact constants
uint8 CONTACT_UNKNOWN = 0
uint8 CONTACT_MADE = 1
uint8 CONTACT_LOST = 2
std_msgs/Header header
# Arrays for 4 legs (FL, FR, RL, RR)
geometry_msgs/Point[] foot_position_rt_body # Foot position relative to body frame (4 elements)
geometry_msgs/Point[] foot_velocity_rt_body # Foot velocity relative to body frame (4 elements)
uint8[] contact # Contact state for each foot (4 elements)로봇 제어
🎮 3. 제어 토픽 (Command Topics)
다음 토픽들은 RBQ 로봇에 상위 제어 및 내비게이션 명령을 보내는 데 사용됩니다.
모든 명령은 표준 ROS2 메시지 타입 또는 사용자 정의 rbq_msgs 정의를 따릅니다.
제어 토픽은 다음과 같이 정의됩니다:
| 토픽 | 설명 |
|---|---|
| rbq/motion/autoStart | 관절 위치를 초기화하고 관절 제어를 시작합니다 AutoStart 프로세스는 'RobotStatus' 토픽을 통해 확인할 수 있습니다 CAN 확인 → 홈 찾기 → 제어 시작 플래그가 활성화됨 |
| rbq/motion/emergency | 비상 정지 - 로봇의 다리 관절 전원을 강제로 차단합니다. 이 동작은 로봇에 충격을 줄 수 있습니다. |
| rbq/motion/switchGait | gait_id 매개변수를 사용하여 로봇 보행 모드를 전환합니다. 사용 가능한 gait_id 값은 위의 "사용 가능한 보행" 표를 참조하세요. |
| rbq/motion/recoveryFlex rbq/motion/switchGait (gait_id: 1) | 'recoveryFlex' 토픽은 로봇이 Fall 모드에 있을 때만 적용됩니다. 특정 관절 동작을 통해 로봇을 앉은 모드로 복귀시키도록 명령합니다. 또는 'switchGait' 토픽에 gait_id: 1 (Standing)을 사용하여 Fall 모드에서 복구할 수 있습니다. |
| rbq/motion/switchControlMode | HighLevel Command 모드를 활성화하거나 비활성화합니다. `true`로 설정하면 HighLevel Command 모드가 활성화되어 `rbq/motion/cmd_highLevel` 토픽에서 명령을 수신합니다. `false`로 설정하면 Joystick 제어 모드가 활성화됩니다. |
📍중요: HighLevelCommand를 통해 로봇을 실제로 움직이려면 먼저
rbq/gamepad/switchControlMode를true로 설정하세요.
(true : HighLevel Mode , false : JoyStick Mode)
상위 제어 명령 토픽은 다음과 같이 정의됩니다:
| 토픽 | 데이터 구조 | 설명 |
|---|---|---|
| rbq/motion/cmd_highLevel | std_msgs/Header header string identifier float64 roll float64 pitch float64 yaw float64 vel_x float64 vel_y float64 omega_z float64 delta_body_h float64 delta_foot_h int8 gait_state bool gait_transition | 현재 보행 상태에 따른 로봇 제어를 위한 상위 제어 명령 토픽. (사용 가능한 gait_id 값은 위의 "사용 가능한 보행" 표를 참조하세요) • Standing Mode: roll, pitch, yaw (ZYX 오일러 각)에 따라 로봇 몸체 자세를 조정합니다. body_H 매개변수는 로봇 몸체의 높이를 지정합니다 범위: Roll: -25~25°, Pitch: -20~20°, Yaw: -25~25°, Delta_body_h: -0.15~0.05m • Walk Mode: 트롯 보행 상태에서 로봇의 로컬 좌표계 기준 이동 속도를 설정합니다. Vx, Vy는 전진 속도, 측방향 속도를 나타내고 Wz는 회전 속도를 나타냅니다. 트롯 보행 중 delta_body_H는 기본 몸체 높이에서의 몸체 높이를 설정하는 데 사용되고, foot_H는 발 높이를 설정하는 데 사용되며, pitch는 몸체의 피치 각도를 설정하는 데 사용됩니다. 범위: Vx: -1.0~1.2m/s, Vy: -0.4~0.4m/s, Wz: -75~75°/s Delta_body_h: -0.15~+0.05m, Delta_foot_h: -0.06~+0.04m • Stairs Mode: 계단 내비게이션을 위한 전진, 측방향, 회전 속도 범위: Vx: -0.5~0.5m/s, Vy: -0.2~0.2m/s, Wz: -15~15°/s • Run Mode: 고속 이동 제어를 위한 전진, 측방향, 회전 속도 범위: Vx: -1.0~1.8m/s, Vy: -0.6~0.6m/s, Wz: -75~75°/s • Wave Mode: 저속 이동 제어를 위한 전진, 측방향, 회전 속도 범위: Vx: -0.3~0.3m/s, Vy: -0.2~0.2m/s, Wz: -20~20°/s • RL TROT Mode: 향상된 속도 제어를 갖춘 강화학습 트롯 보행 범위: Vx: -1.5~2.0m/s, Vy: -1.0~1.0m/s, Wz: -1.8~1.8rad/s • RL TROT VISION Mode: 비전 통합을 갖춘 강화학습 트롯 범위: Vx: -1.5~2.0m/s, Vy: -1.0~1.0m/s, Wz: -1.8~1.8rad/s |
| rbq/motion/cmd_navigateTo | geometry_msgs/Pose pose uint8 mode | 로봇을 지정된 위치로 이동시키는 내비게이션 명령: # 접근 모드: 0: 목표로 회전 → 직선 보행 → 목표 yaw로 회전 1: 목표 yaw로 회전 → 목표로 대각선 보행 2: 목표로 대각선 보행 → 목표 yaw로 회전 3: 목표 yaw로 회전하면서 동시에 대각선 보행 4: 넓은 다리 보행을 사용한 접근 모드 3 |
상위 제어 명령(High-Level Command)의 메시지는 다음과 같이 정의됩니다:
- HighLevelCommand
std_msgs/Header header # ROS 메시지 헤더 (타임스탬프와 frame_id 포함)
string identifier # 명령 추적/로깅용 식별자
float64 roll # 몸체 roll 각도 (도 단위, ZYX 오일러 각)
float64 pitch # 몸체 pitch 각도 (도 단위, ZYX 오일러 각)
float64 yaw # 몸체 yaw 각도 (도 단위, ZYX 오일러 각)
float64 vel_x # X 방향 선형 속도 (m/s)
float64 vel_y # Y 방향 선형 속도 (m/s)
float64 omega_z # Z축 주위 각속도 (rad/s)
float64 delta_body_h # 기본값에서 몸체 높이 조정 (m)
float64 delta_foot_h # 기본값에서 발 높이 조정 (m)
int8 gait_state # 목표 보행 상태 (위에 정의된 상수 사용)
bool gait_transition # 명령 실행 중 보행 전환 활성화(true)/비활성화(false)💡 예제: 사용자 정의 자세로 Standing 모드 (roll: 15°, pitch: 30°, yaw: 20°)
ros2 topic pub --once rbq/motion/cmd_highLevel rbq_msgs/msg/HighLevelCommand \
'{header: {stamp: {sec: 0, nanosec: 0}, frame_id: "base"}, identifier: "standing_pose", roll: 15.0, pitch: 30.0, yaw: 20.0, vel_x: 0.0, vel_y: 0.0, omega_z: 0.0, delta_body_h: 0.0, delta_foot_h: 0.0, gait_state: 1, gait_transition: false}'기타 토픽 (Other Topics)
📷 4. 비전 토픽 (Vision Topics)
- PTZ 카메라 제어 토픽 (PTZ Camera Control Topics)
| 토픽 | 설명 |
|---|---|
| rbq/ptzCamera/setPanTiltZoom | Float32MultiArray를 사용한 PTZ 카메라 제어 명령 [pan, tilt, zoom] |
💡 example:
ros2 topic pub --once rbq/ptzCamera/setPanTiltZoom std_msgs/msg/Float32MultiArray "{data: [0.0, 0.0, 1.0]}"- 카메라 센서 토픽 (Camera Sensor Topics)
카메라 센서는 로봇 주변의 여러 위치에서 RGB, IR, 깊이 이미지를 제공합니다. 이미지는 원시 및 압축 형식으로 발행되며 해당 카메라 보정 정보와 함께 제공됩니다.
📍 하드웨어 정보: 카메라 사양, FOV, 변환 행렬에 대한 자세한 내용은 Visual Sensors Hardware Manual을 참조하세요.
| 카메라 | 이미지 타입 | 형식 | 토픽명 |
|---|---|---|---|
| Bottom (0-3) | IR | Raw | rbq/vision/sensor_bottom_0/ir rbq/vision/sensor_bottom_1/ir rbq/vision/sensor_bottom_2/ir rbq/vision/sensor_bottom_3/ir |
| Compressed | rbq/vision/sensor_bottom_0/ir/compressed rbq/vision/sensor_bottom_1/ir/compressed rbq/vision/sensor_bottom_2/ir/compressed rbq/vision/sensor_bottom_3/ir/compressed | ||
| Camera Info | rbq/vision/sensor_bottom_0/ir/camera_info rbq/vision/sensor_bottom_1/ir/camera_info rbq/vision/sensor_bottom_2/ir/camera_info rbq/vision/sensor_bottom_3/ir/camera_info | ||
| Depth | Raw | rbq/vision/sensor_bottom_0/depth rbq/vision/sensor_bottom_1/depth rbq/vision/sensor_bottom_2/depth rbq/vision/sensor_bottom_3/depth | |
| Compressed | rbq/vision/sensor_bottom_0/depth/compressed rbq/vision/sensor_bottom_1/depth/compressed rbq/vision/sensor_bottom_2/depth/compressed rbq/vision/sensor_bottom_3/depth/compressed | ||
| Camera Info | rbq/vision/sensor_bottom_0/depth/camera_info rbq/vision/sensor_bottom_1/depth/camera_info rbq/vision/sensor_bottom_2/depth/camera_info rbq/vision/sensor_bottom_3/depth/camera_info | ||
| Front/Rear | RGB | Raw | rbq/vision/sensor_front/rgb rbq/vision/sensor_rear/rgb |
| Compressed | rbq/vision/sensor_front/rgb/compressed rbq/vision/sensor_rear/rgb/compressed | ||
| Camera Info | rbq/vision/sensor_front/rgb/camera_info rbq/vision/sensor_rear/rgb/camera_info | ||
| IR | Raw | rbq/vision/sensor_front/ir rbq/vision/sensor_rear/ir | |
| Compressed | rbq/vision/sensor_front/ir/compressed rbq/vision/sensor_rear/ir/compressed | ||
| Camera Info | rbq/vision/sensor_front/ir/camera_info rbq/vision/sensor_rear/ir/camera_info | ||
| Depth | Raw | rbq/vision/sensor_front/depth rbq/vision/sensor_rear/depth | |
| Compressed | rbq/vision/sensor_front/depth/compressed rbq/vision/sensor_rear/depth/compressed | ||
| Camera Info | rbq/vision/sensor_front/depth/camera_info rbq/vision/sensor_rear/depth/camera_info |
🖼️ RViz 시각화
GUI와 함께 RViz2 실행
RViz의 왼쪽 GUI를 통해 로봇을 동시에 시각화하고 명령을 전송할 수 있습니다.
먼저 워크스페이스 디렉토리로 이동하세요:
bashcd <your workspace>/RBQ그런 다음 RViz를 실행하세요:
source ros2/install/local_setup.bash
ros2 launch rbq_description description.launch.py
📘 도움
이 저장소를 사용하는 동안 문제가 발생하면, 자유롭게 issue를 등록해 주세요.
🤝 기여
자유롭게 기여해 주세요!
👥 기여자
이 프로젝트는 Rainbow-Robotics에서 제공합니다.
Rainbow-Robotics 기여자:
Gurbann
Jinwon Seo
