RoboCasa State / Action ๋ช ์ธ
๊ทผ๊ฑฐ ํ์ผ:
env.py,gym_wrapper.py(PandaOmronKeyConverter),robosuite/controllers/parts/arm/osc.py,robosuite/controllers/config/robots/default_pandaomron.json
State (์ด 16์ฐจ์)
env.py: convert_state() ๊ธฐ์ค์ผ๋ก concatenate๋จ.
| ์ธ๋ฑ์ค | ์ฐจ์ | ํค | absolute / relative | ํํ |
|---|---|---|---|---|
| 0~2 | 3 | state.base_position |
absolute | xyz |
| 3~6 | 4 | state.base_rotation |
absolute | Quaternion (robot0_base_quat) |
| 7~9 | 3 | state.end_effector_position_relative |
relative (base โ EE) | xyz |
| 10~13 | 4 | state.end_effector_rotation_relative |
relative (base โ EE) | Quaternion (robot0_base_to_eef_quat) |
| 14~15 | 2 | state.gripper_qpos |
โ | joint position |
Action (์ด 12์ฐจ์)
env.py: convert_action() ๊ธฐ์ค์ผ๋ก ๋ถํด๋จ.
| ์ธ๋ฑ์ค | ์ฐจ์ | ํค | ์ค๋ช |
|---|---|---|---|
| 0~3 | 4 | action.base_motion |
๋ฒ ์ด์ค ์ด๋ (์๋ ์ฐธ๊ณ ) |
| 4 | 1 | action.control_mode |
์ ์ด ๋ชจ๋ ์ค์์น (์๋ ์ฐธ๊ณ ) |
| 5~7 | 3 | action.end_effector_position |
EE delta position, base frame ๊ธฐ์ค |
| 8~10 | 3 | action.end_effector_rotation |
EE delta rotation, base frame ๊ธฐ์ค, axis-angle |
| 11 | 1 | action.gripper_close |
๊ทธ๋ฆฌํผ ๋ซ๊ธฐ (0.5 threshold โ binary) |
base_motion (4์ฐจ์) ์์ธ
| ์ธ๋ฑ์ค | ๋์ | controller type | ์ค๋ช |
|---|---|---|---|
| 0~2 | robot0_base |
JOINT_VELOCITY |
๋ชจ๋ฐ์ผ ๋ฒ ์ด์ค x์๋ / y์๋ / yaw์๋ |
| 3 | robot0_torso |
JOINT_POSITION |
๋ชธํต ์์ง ๋ฆฌํํธ joint position (โ ๋์ด) |
control_mode (1์ฐจ์) ์์ธ
| ๊ฐ | base_mode | ๋์ |
|---|---|---|
| < 0.5 | -1 | Arm mode โ ๋ฒ ์ด์ค ๊ณ ์ , ํ๋ก ์กฐ์ (goal: achieved ๊ธฐ์ค) |
| โฅ 0.5 | +1 | Base mode โ ๋ฒ ์ด์ค ์ด๋, ํ ๋ชฉํ ์ ์ง (goal: desired ๊ธฐ์ค) |
EE Rotation: axis-angle์ ์ฐ๋ ์ด์
OSC controller(osc.py)๋ rotation input์ Rotation.from_rotvec() ์ผ๋ก ํด์ โ axis-angle ๊ณ ์ .
RPY(Euler angle) ๋์ axis-angle์ ์ฐ๋ ์ด์ :
- Gimbal lock ์์ โ RPY๋ ํน์ ์์ธ์์ ๋ ์ถ์ด ๊ฒน์ณ DOF๋ฅผ ์๋ singularity ๋ฐ์. EE๋ ์์ ํ์ ํ๋ฏ๋ก ์ค์ ๋ฌธ์ ๊ฐ ๋จ.
- Delta ์ ์ด์ ์์ฐ์ค๋ฌ์ โ "์ด ์ถ ๋ฐฉํฅ์ผ๋ก ฮธ๋งํผ ํ์ " ์๋ฏธ๊ฐ ์ง๊ด์ ์ด๊ณ ๋ณด๊ฐ์ด smooth. RPY delta๋ ์์ ์์กด์ฑ(rollโpitchโyaw) ๋๋ฌธ์ ํฉ์ฑ์ด ๋ณต์กํจ.
- ํฌ๊ธฐ = ํ์ ๋ โ ๋ฒกํฐ norm์ด ํ์ ๊ฐ์ด๋ผ output clipping์ด ์์ฐ์ค๋ฌ์. (
output_max: [0.5, 0.5, 0.5]rad)
RPY ์ ๋ ฅ์ ์ฝ๋์ ์ง์ํ์ง ์์. ํ์ํ๋ฉด wrapper์์ ๋ณํ ํ์:
from scipy.spatial.transform import Rotation axis_angle = Rotation.from_euler('xyz', rpy).as_rotvec()
์๋ฎฌ๋ ์ด์ ์ฐ๊ฒฐ ํ๋ฆ
policy output (12-dim)
โ convert_action() [env.py]
action dict (base_motion, control_mode, EE_pos, EE_rot, gripper_close)
โ unmap_action() [gym_wrapper.py]
{
robot0_right: concat(EE_pos[3], EE_rot[3]) โ OSC_POSE controller
robot0_right_gripper: threshold(gripper_close, 0.5) โ -1 or +1
robot0_base: base_motion[0:3] โ JOINT_VELOCITY controller
robot0_torso: base_motion[3:4] โ JOINT_POSITION controller
robot0_base_mode: threshold(control_mode, 0.5) โ -1 or +1
}
โ env.step() [robosuite]
MuJoCo simulation