ALICE M1 Command Guide
info
모든 coommand들은 베이스 자세를 기준으로 시작합니다. 베이스 자세가 아니라면 초기설치 & 세팅 가이드 탭을 참고해주세요.
ALICE M1은 ROS2 토픽을 통해 로봇을 직접 제어할 수 있습니다.
아래 명령들은 모두 토픽 기반 커맨드이며, 모드별로 사용 방법이 다릅니다.
커맨드 입력 전에 반드시 Joint Limits을 확인해주세요.
ROS2 전용 지원
본 커맨드는 ROS2(humble, jazzy) 환경에서만 지원됩니다. ROS1/타 프레임워크에서는 동작을 보장하지 않습니다.
Joint Limits (공통)
| 관절명 | URDF | 각도 범위 |
|---|---|---|
| 머리 피치 | head_p | -40° ~ 40° |
| 머리 요 | head_y | -45° ~ 45° |
| 허리 요 | waist_y | -45° ~ 45° |
| 상부 허리 피치 | waist_upper_pitch | 0° ~ 90° |
| 하부 허리 피치 | waist_lower_pitch | 0° ~ 90° |
| 왼쪽 어깨 피치 | l_sh_p | -110° ~ 50° |
| 왼쪽 어깨 롤 | l_sh_r | -10° ~ 180° |
| 왼쪽 어깨 요 | l_sh_y | -70° ~ 70° |
| 왼쪽 팔꿈치 피치 | l_el_p | -80° ~ 0° |
| 왼쪽 손목 요 | l_wr_y | -75° ~ 75° |
| 왼쪽 손목 피치 | l_wr_p | -35° ~ 35° |
| 왼쪽 손목 롤 | l_wr_r | -45° ~ 15° |
| 오른쪽 어깨 피치 | r_sh_p | -50° ~ 110° |
| 오른쪽 어깨 롤 | r_sh_r | -180° ~ 10° |
| 오른쪽 어깨 요 | r_sh_y | -70° ~ 70° |
| 오른쪽 팔꿈치 피치 | r_el_p | 0° ~ 80° |
| 오른쪽 손목 요 | r_wr_y | -75° ~ 75° |
| 오른쪽 손목 피치 | r_wr_p | -35° ~ 35° |
| 오른쪽 손목 롤 | r_wr_r | -15° ~ 45° |
Command Types
- Position Control Command
- Trajectory Control Command
- End-Point Command
- Wheel Command
- Hand Command
개요
- Position 모드 제어 → 목표 위치로 joint 각도가 즉시 이동
- 제어 토픽:
/aeirobot/alice_mobile/command - 메시지 타입:
aeirobot_msgs/msg/Command
주의사항
명령을 보내는 즉시 목표 위치로 관절이 움직입니다. 현재 위치와 차이가 큰 명령을 보내면 로봇에 무리가 갈 수 있습니다.
Position Control 보다 시간 제어 기반의 Trajectory Control 사용을 권장드립니다.
머리 및 허리 Position 제어
데이터 형식
| 필드 | 데이터 |
|---|---|
msg.command | 3 |
msg.style | 2 |
msg.value[0] | head pitch (deg) |
msg.value[1] | head yaw (deg) |
msg.value[2] | waist yaw(deg) |
msg.value[3] | waist upper pitch (deg) |
msg.value[4] | waist lower pitch (deg) |
예시
ros2 topic pub --once /aeirobot/alice_mobile/command aeirobot_msgs/msg/Command \
"{command: 3, style: 2, value: [40.0, 0.0, 0.0, 50.0, 50.0]}"
양 팔 Position 제어
데이터 형식
| 필드 | 데이터 |
|---|---|
msg.command | 8 |
msg.style | 1 |
msg.value[0] | left shoulder pitch (deg) |
msg.value[1] | left shoulder roll (deg) |
msg.value[2] | left shoulder yaw (deg) |
msg.value[3] | left elbow pitch (deg) |
msg.value[4] | left wrist yaw (deg) |
msg.value[5] | left wrist pitch (deg) |
msg.value[6] | left wrist roll (deg) |
msg.value[7] | right shoulder pitch (deg) |
msg.value[8] | right shoulder roll (deg) |
msg.value[9] | right shoulder yaw (deg) |
msg.value[10] | right elbow pitch (deg) |
msg.value[11] | right wrist yaw (deg) |
msg.value[12] | right wrist pitch (deg) |
msg.value[13] | right wrist roll (deg) |
예시
ros2 topic pub --once /aeirobot/alice_mobile/command aeirobot_msgs/msg/Command \
"{command: 8, style: 1, value: [-10.0, 0.0, 0.0, -80.0, 0.0, -10.0, 0.0, -10.0, 0.0, 0.0, 80.0, 0.0, 10.0, 0.0]}"
개요
- Trajectory 모드 제어 → 현재 위치부터 목표 위치까지 지정된 시간 동안 joint 각도 이동
- 제어 토픽:
/aeirobot/alice_mobile/command - 메시지 타입:
aeirobot_msgs/msg/Command
머리 및 허리 Trajectory 제어
데이터 형식
| 필드 | 데이터 |
|---|---|
msg.command | 1 |
msg.style | 1 |
msg.value[0] | 목표 위치까지 움직일 시간 (sec) |
msg.value[1] | head pitch (deg) |
msg.value[2] | head yaw (deg) |
msg.value[3] | waist yaw(deg) |
msg.value[4] | waist upper pitch (deg) |
msg.value[5] | waist lower pitch (deg) |
예시
ros2 topic pub --once /aeirobot/alice_mobile/command aeirobot_msgs/msg/Command \
"{command: 1, style: 1, value: [4, 0.0, 0.0, 0.0, 20.0, 20.0]}"
양 팔 Trajectory 제어
데이터 형식
| 필드 | 데이터 |
|---|---|
msg.command | 1 |
msg.style | 2 |
msg.value[0] | 목표 위치까지 움직일 시간 (sec) |
msg.value[1] | left shoulder pitch (deg) |
msg.value[2] | left shoulder roll (deg) |
msg.value[3] | left shoulder yaw (deg) |
msg.value[4] | left elbow pitch (deg) |
msg.value[5] | left wrist yaw (deg) |
msg.value[6] | left wrist pitch (deg) |
msg.value[7] | left wrist roll (deg) |
msg.value[8] | right shoulder pitch (deg) |
msg.value[9] | right shoulder roll (deg) |
msg.value[10] | right shoulder yaw (deg) |
msg.value[11] | right elbow pitch (deg) |
msg.value[12] | right wrist yaw (deg) |
msg.value[13] | right wrist pitch (deg) |
msg.value[14] | right wrist roll (deg) |
예시
ros2 topic pub --once /aeirobot/alice_mobile/command aeirobot_msgs/msg/Command \
"{command: 1, style: 2, value: [2.0, -10.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, -10.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0]}"
Trajectory 제어 종료 판단
- 완료 여부 토픽:
/aeirobot/alice_mobile/trajectory_done - 메시지 타입:
std_msgs/msg/Bool
- trajectory 동작이 완료되면
true가 반환됩니다.
Trajectory 제어 중단
- 중단 토픽:
/aeirobot/alice_mobile/command - 메시지 타입:
aeirobot_msgs/msg/Command
데이터 형식
| 필드 | 데이터 |
|---|---|
| msg.command | 0 |
| msg.style | 0 |
| msg.value [ i ] | none |
예시
ros2 topic pub --once /aeirobot/alice_mobile/command aeirobot_msgs/msg/Command \
"{command: 0, style: 0, value: []}"
개요
- Endpoint 제어 → 로봇의 IK 기반으로 지정된 시간 동안 엔드이펙터를 글로벌 position으로 이동
- 제어 토픽:
/aeirobot/alice_mobile/arm_ik_target - 메시지 타입:
std_msgs/msg/Float32MultiArray
데이터 형식
| msg.data[i] | 입력 데이터 |
|---|---|
| 0 | 목표 위치까지 움직일 시간 (sec) |
| 1 | left hand X (m) |
| 2 | left hand Y (m) |
| 3 | left hand Z (m) |
| 4 | left hand Roll (deg) |
| 5 | left hand Pitch (deg) |
| 6 | left hand Yaw (deg) |
| 7 | right hand X (m) |
| 8 | right hand Y (m) |
| 9 | right hand Z (m) |
| 10 | right hand Roll (deg) |
| 11 | right hand Pitch (deg) |
| 12 | right hand Yaw (deg) |
- 해당 토픽을 사용하면 팔이 현재 위치부터 목표 위치까지 지정된 시간 동안 움직입니다.
참고 사항
- endpoint는
/tf의torso_linkframe 기준으로 입력합니다. (양 어깨의 중심이 torso_link)

-
endpoint 명령은 팔이 닿을 수 있는 유효 영역인지 확인해야 합니다. (몸/물체 충돌 가능성 점검)
-
팔 링크 길이:

예시: 상자를 집는 듯한 모션
ros2 topic pub --once /aeirobot/alice_mobile/arm_ik_target std_msgs/msg/Float32MultiArray \
"{layout: {dim: [], data_offset: 0}, data: [4.0, 0.45500001311302185, 0.20000000298023224, -0.25809988379478455, 18.715351104736328, 22.92640495300293, 7.517949104309082, 0.45500001311302185, -0.20000000298023224, -0.25809988379478455, -18.715351104736328, 22.92640495300293, -7.517949104309082]}"
endpoint 제어 종료 판단
- 완료 여부 토픽:
/aeirobot/alice_mobile/arm_ik_target_done - 메시지 타입:
std_msgs/msg/Bool
- endpoint 제어 완료 후, 로봇 엔드 이펙터의 목표 위치와 실제 위치 오차가 기준값 이하일 경우
true, 초과할 경우false가 반환됩니다.
endpoint 제어 중단
- 중단 토픽:
/aeirobot/alice_mobile/command - 메시지 타입:
aeirobot_msgs/msg/Command
데이터 형식
| 필드 | 데이터 |
|---|---|
| msg.command | 0 |
| msg.style | 0 |
| msg.value [ i ] | none |
예시
ros2 topic pub --once /aeirobot/alice_mobile/command aeirobot_msgs/msg/Command \
"{command: 0, style: 0, value: []}"
현재 팔 endpoint 위치 받아오기
/tf토픽의left_arm_link_7/right_arm_link_7이 손목 관절 위치입니다.torso_link기준 손목 위치에 z 방향으로 0.125m를 더하면 현재 endpoint 위치를 얻을 수 있습니다.
개요
- 휠(Wheel) 제어 → 바퀴의 속도를 기반으로 제어
- 제어 토픽:
/aeirobot/alice_mobile/cmd_vel - 메시지 타입:
geometry_msgs/msg/TwistStamped
주의사항
- 이 토픽으로 보내는 속도 명령은 현재 제어 명령을 즉시 덮어씁니다.
- 케이블/연결 장치가 당겨지지 않도록 주변을 정리하세요.
- 반드시 즉시 정지 가능한 오퍼레이터가 대기해야 합니다.
데이터 형식
| 방향 | 데이터 |
|---|---|
| Forwards | linear.x positive |
| Backwards | linear.x negative |
| Rotate Left | angular.z positive |
| Rotate Right | angular.z negative |
예시: 전진 명령
ros2 topic pub /aeirobot/alice_mobile/cmd_vel \
geometry_msgs/TwistStamped \
'{"twist": {"linear": {"x": 0.2}}}' -r 10
예시: 제자리 회전
ros2 topic pub /aeirobot/alice_mobile/cmd_vel \
geometry_msgs/TwistStamped \
'{"twist": {"angular": {"z": 0.35}}}' -r 10
예시: 정지
ros2 topic pub /aeirobot/alice_mobile/cmd_vel \
geometry_msgs/TwistStamped \
'{"twist":{"linear":{"x":0.0,"y":0.0},"angular":{"z":0.0}}}'
info
해당 과정은 Brainco Hand를 기준으로 설명됩니다. 만약 로봇에 장착된 hand가 brainco가 아니라면, 정상 작동을 보장하지 않습니다.
개요
- 손가락 제어 → position 기반으로 각 손가락 제어
- 제어 토픽:
/aeirobot_hand/set_angle - 메시지 타입:
aeirobot_hand_msgs/msg/SetAngle
데이터 형식
| 필드 | 데이터 |
|---|---|
| msg.status | "set_angle" |
| msg.hand_id | 왼손 : 2 / 오른손 : 1 |
| msg.angle[ 0 ] | Pinky Pitch |
| msg.angle[ 1 ] | Ring Pitch |
| msg.angle[ 2 ] | Middle Pitch |
| msg.angle[ 3 ] | Index Pitch |
| msg.angle[ 4 ] | Thumb Pitch |
| msg.angle[ 5 ] | Thumb Roll |
참고 사항
- msg.angle에는 0~1000 사이의 값이 들어갑니다.
- 1000 : 완전히 펼침
- 0 : 완전히 접음
예시: 왼손 다 펼침
ros2 topic pub --once /aeirobot_hand/set_angle aeirobot_hand_msgs/msg/SetAngle \
"{status: 'set_angle', hand_id: 2, angle: [1000, 1000, 1000, 1000, 1000, 1000]}"
예시: 오른손 다 접음
ros2 topic pub --once /aeirobot_hand/set_angle aeirobot_hand_msgs/msg/SetAngle \
"{status: 'set_angle', hand_id: 1, angle: [0, 0, 0, 0, 0, 0]}"
손가락 센서 데이터 받기
- 표면에 수직으로 들어오는 힘:
/touch_force_normal - 표면 접선 방향(미끄러짐 방향) 힘:
/touch_force_tangential - 힘이 들어오는 방향 (0~360도):
/touch_force_direction - 물체와의 근접도 (거리 기반 감지):
/touch_force_proximity - 각 손가락 센서 상태 (0 = normal / 1 = contact 등):
/touch_force_status - 메시지 타입:
std_msgs/msg/Float32MultiArray
데이터 형식
| 필드 | 데이터 |
|---|---|
| msg.data[ 0 ] | Thumb |
| msg.data[ 1 ] | Index |
| msg.data[ 2 ] | Middle |
| msg.data[ 3 ] | Ring |
| msg.data[ 4 ] | Pinky |