Skip to content

Commit 5d61cda

Browse files
Add openXR module configuration files for iCubGenova09
1 parent 8c58dc1 commit 5d61cda

File tree

6 files changed

+121
-0
lines changed

6 files changed

+121
-0
lines changed
Lines changed: 8 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,8 @@
1+
remote_control_boards ("head")
2+
# Notice the order of the joint list is not wrong.
3+
# Indeed they are written according to the joint order of the icub-neck
4+
joints_list ("neck_pitch", "neck_roll", "neck_yaw")
5+
6+
smoothingTime 1.0
7+
PreparationSmoothingTime 3.0
8+
PreparationJointReferenceValues (0.0 , 0.0 , 0.0)
Lines changed: 6 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,6 @@
1+
remote_control_boards ("left_arm")
2+
joints_list ("l_thumb_proximal", "l_thumb_distal", "l_index_proximal", "l_index-distal", "l_middle-proximal", "l_middle-distal", "l_little-fingers")
3+
4+
useVelocity 1
5+
6+
fingersScaling (1, 3.5, 2, 3.5, 1, 3.5, 5)
Lines changed: 17 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,17 @@
1+
# additional rotations
2+
# the following rotation map the hand oculus frame and the hand robot frame
3+
handOculusFrame_R_handRobotFrame ((0.0 0.0 -1.0), (-1.0 0.0 0.0), (0.0 1.0 0.0))
4+
5+
# the following rotation map the teleoperation frame and the teleoperation robot
6+
# frame the Teleoperation robot frame chosen is "imu_frame" and according to iCub
7+
# CAD has:
8+
# The z-axis is parallel to gravity but pointing upwards.
9+
# The x-axis points behind the robot.
10+
# The y-axis points laterally and is chosen according to the right-hand rule.
11+
# the Teleoperation frame is attached to the virtualizer and the origin is the
12+
# same oculus inertial frame. In other words:
13+
# The z-axis is parallel to gravity but pointing upwards
14+
# The x-axis points forward
15+
# The y-axis points laterally and is chosen according to the right-hand rule.
16+
# So the rotation matrix is simply given by Rotz(pi)
17+
teleoperationRobotFrame_R_teleoperationFrame ((1.0 0.0 0.0), (0.0 1.0 0.0), (0.0 0.0 1.0))
Lines changed: 67 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,67 @@
1+
name openXRRetargeting
2+
3+
# ports
4+
leftHandPosePort /leftHandPose:o
5+
rightHandPosePort /rightHandPose:o
6+
rpcWalkingPort_name /walkingRpc
7+
8+
[GENERAL]
9+
samplingTime 0.01
10+
robot icub
11+
enableMoveRobot 1
12+
# the following value is a threshold used to update the teleoperation frame position
13+
# when the human rotates inside the virtualizer
14+
playerOrientationThreshold 0.2
15+
16+
# For kinematic scaling for task-space retargeting
17+
humanHeight 1.76
18+
# The robot arm span is the distance between the left and right index fingertips when the arms are aligned, i.e. T pose.
19+
robotArmSpan 1.0
20+
# If resetCameras !=0, the module will attempt to reset the cameras during the initialization phase.
21+
resetCameras 0
22+
# The leftCameraPort and rightCameraPort are needed only if resetCameras is 1
23+
leftCameraPort /icub/cam/left
24+
rightCameraPort /icub/cam/right
25+
26+
27+
# include head parameters
28+
[include HEAD_RETARGETING "headRetargetingParams.ini"]
29+
30+
# include fingers parameters
31+
[include LEFT_FINGERS_RETARGETING "leftFingersRetargetingParams.ini"]
32+
[include RIGHT_FINGERS_RETARGETING "rightFingersRetargetingParams.ini"]
33+
34+
# include hand parameters
35+
[include LEFT_HAND_RETARGETING "leftHandRetargetingParams.ini"]
36+
[include RIGHT_HAND_RETARGETING "rightHandRetargetingParams.ini"]
37+
38+
[OPENXR]
39+
root_frame_name openxr_origin
40+
left_hand_frame_name openxr_left_hand
41+
right_hand_frame_name openxr_right_hand
42+
head_frame_name openxr_head
43+
oculusOrientationPort /oculusOrientation:i
44+
oculusPositionPort /oculusPosition:i
45+
46+
move_icub_using_joypad 1
47+
deadzone 0.3
48+
fullscale 1.0
49+
scale_X 5.0
50+
scale_Y 5.0
51+
52+
53+
# {"/user/hand/left/input/menu/click", "vive_left_menu"},
54+
# {"/user/hand/left/input/trigger/click", "vive_left_trigger_click"},
55+
# {"/user/hand/left/input/squeeze/click", "vive_left_squeeze_click"},
56+
# {"/user/hand/left/input/trackpad/click", "vive_left_trackpad_click"},
57+
# {"/user/hand/right/input/menu/click", "vive_right_menu"},
58+
# {"/user/hand/right/input/trigger/click", "vive_right_trigger_click"},
59+
# {"/user/hand/right/input/squeeze/click", "vive_right_squeeze_click"},
60+
# {"/user/hand/right/input/trackpad/click", "vive_right_trackpad_click"}
61+
62+
prepare_walking_buttons_map (0, 0, 0, 0, 1, 0, 0, 0)
63+
start_walking_buttons_map (1, 0, 0, 0, 0, 0, 0, 0)
64+
left_fingers_squeeze_buttons_map (0, 0, 0, 0, 0, 0, 0, 0)
65+
left_fingers_release_buttons_map (0, 1, 0, 0, 0, 0, 0, 0)
66+
right_fingers_squeeze_buttons_map (0, 0, 0, 0, 0, 0, 0, 0)
67+
right_fingers_release_buttons_map (0, 0, 0, 0, 0, 1, 0, 0)
Lines changed: 6 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,6 @@
1+
remote_control_boards ("right_arm")
2+
joints_list ("r_thumb_proximal", "r_thumb_distal", "r_index_proximal", "r_index-distal", "r_middle-proximal", "r_middle-distal", "r_little-fingers")
3+
4+
useVelocity 1
5+
6+
fingersScaling (1, 3.5, 2, 3.5, 1, 3.5, 5)
Lines changed: 17 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,17 @@
1+
# additional rotations
2+
# the following rotation map the hand oculus frame and the hand robot frame
3+
handOculusFrame_R_handRobotFrame ((0.0 0.0 -1.0), (-1.0 0.0 0.0), (0.0 1.0 0.0))
4+
5+
# the following rotation map the teleoperation frame and the teleoperation robot
6+
# frame the Teleoperation robot frame chosen is "imu_frame" and according to iCub
7+
# CAD has:
8+
# The z-axis is parallel to gravity but pointing upwards.
9+
# The x-axis points behind the robot.
10+
# The y-axis points laterally and is chosen according to the right-hand rule.
11+
# the Teleoperation frame is attached to the virtualizer and the origin is the
12+
# same oculus inertial frame. In other words:
13+
# The z-axis is parallel to gravity but pointing upwards
14+
# The x-axis points forward
15+
# The y-axis points laterally and is chosen according to the right-hand rule.
16+
# So the rotation matrix is simply given by Rotz(pi)
17+
teleoperationRobotFrame_R_teleoperationFrame ((1.0 0.0 0.0), (0.0 1.0 0.0), (0.0 0.0 1.0))

0 commit comments

Comments
 (0)