This documentation provides the description of the frames and devices associated with the teleoperation framework:
The inertial frame on the human side is defined as:
In the code, the oculusInertial
and oculusRoot
are used for calling the inertial frame. It is identified at the beginning of the teleoperation scenario. The z
axis of the frame is parallel to the gravity in the opposite direction,
while the x
and y
axes are parallel to the ground. The x
axis is toward the front of the human when starting the teleoperation processes, and the y
axis is identified according to the right-hand rule.
According to the Oculus documentation, the frame attached to the Oculus Virtual Reality (OVR) headset is defined by:
The x-z plane is aligned with the ground regardless of camera orientation.
As seen from the diagram, the coordinate system uses the following axis definitions:
- Y is positive in the up direction.
- X is positive to the right.
- Z is positive heading backwards.
Rotation is maintained as a unit quaternion, but can also be reported in yaw-pitch-roll form. Positive rotation is counter-clockwise.
However, the custom they have employed for defining the Euler angles and their composition order is different from ours.
The following line of code provides us with the rotation from inertial frame (attached to the human head at the beginning) to the Oculus headset at timestep t
expressed in the preferred coordinate system:
iDynTree::toEigen(m_oculusRoot_T_headOculus).block(0, 0, 3, 3)
= iDynTree::toEigen(iDynTree::Rotation::RPY(-desiredHeadOrientationVector(1),
desiredHeadOrientationVector(0),
desiredHeadOrientationVector(2)));
According to the measurement information we acquire from the Cyberith treadmill, we identify the inertial frame of Virtualizer as follows. The rotation of the operator (called player here) inside the treadmill is defined with playerOrientation
, and the rotation of it is expressed in coordinates associated with I_treadmill
. In order to express the rotation in inertial coordinates (in the code is mentioned by oculusInertial
), we perform the following transformation
rotz(- playerOrientation)= rotx(pi) * rotz(playerOrientation) * rotx(-pi)
The frame attached to the treadmill ring that rotates with the ring is called the teleoperaiton frame. At the beginning of the teleoperation scenario, when we start the processes, the teleoperation and inertial frames coincide.
Therefore, we have:
m_oculusInertial_R_teleopFrame = iDynTree::Rotation::RotZ(-playerOrientation);
When the human rotates inside the virtualizer, not only he has a rotation around the z
axis, but also the teleoperaition frame translates as the following figure shows:
To find the translation, we assume while the human rotating, he looks forward, and we compute the translation using the acquired oculus headset data.
The human and robot hand frames are defined similarly, i.e.,
What we are interested in the teleoperation scenario is the transformation m_teleopRobotFrame_T_handRobotFrame
, i.e., the transformation from the robot teleoperation frame to the robot hand frames
m_teleopRobotFrame_T_handRobotFrame
= m_teleopRobotFrame_T_teleopFrame * m_oculusInertial_T_teleopFrame.inverse()
* m_oculusInertial_T_handOculusFrame * m_handOculusFrame_T_handRobotFrame;
-
In this equation,
teleopRobotFrame
andteleopFrame
are the frames attached to the robot and human teleoperation frames. -
In the code, both the
oculusInertial
frame andoculusRoot
frame correspond to the inertial frame determined at the beginning of this document. -
The teleoperation frame is the frame attached to the virtualizer and rotating with that. At the initial time of the teleoperation scenario, the teleoperation and inertial frame match their location and their axes are parallel. However, the definition of the robot teleoperation frame is the same as robot imu frame , and is similar to the robot
root_link
frame:
- The z-axis is parallel to gravity but pointing upwards.
- The x-axis points behind the robot.
- The y-axis points laterally and is chosen according to the right-hand rule.
Following is the frame chain related to the perception system of the human:
When using the full-body suit to teleoperate the robot, the following are the frames attached to the human body links:
The following figure shows the frames attached to the iCub body links:
When we retarget using Xsens, the frames associated with the human links are transformed into the corresponding ones of the robot.
For more information regarding the correspondence of the frames, you can look at this configuration file.
Regarding the transformation of the frames, you can find them in this urdf file, and the transformation is done from the parent link (each link_name) to the child dummy link specified by _fake
, e.g., from root_link
to root_link_fake
.