<!--This does not replace URDF, and is not an extension of URDF.
This is a format for representing semantic information about the robot structure.
A URDF file must exist for this robot as well, where the joints and the links that are referenced are defined
-->
<robotname="romeo">
<!--GROUP STATES: Purpose: Define a named state for a particular group, in terms of joint values. This is useful to define states like 'folded arms'-->
<group_statename="half_sitting"group="all">
<jointname="HeadPitch"value="0"/>
<jointname="HeadRoll"value="0"/>
<jointname="LAnklePitch"value="-0.1"/>
<jointname="LAnkleRoll"value="0"/>
<jointname="LElbowRoll"value="0"/>
<jointname="LElbowYaw"value="0"/>
<jointname="LFinger12"value="0"/>
<jointname="LFinger13"value="0"/>
<jointname="LFinger21"value="0"/>
<jointname="LFinger22"value="0"/>
<jointname="LFinger23"value="0"/>
<jointname="LFinger31"value="0"/>
<jointname="LFinger32"value="0"/>
<jointname="LFinger33"value="0"/>
<jointname="LHand"value="0"/>
<jointname="LHipPitch"value="-0.2"/>
<jointname="LHipRoll"value="0"/>
<jointname="LHipYaw"value="0"/>
<jointname="LKneePitch"value="0.3"/>
<jointname="LShoulderPitch"value="0"/>
<jointname="LShoulderYaw"value="0"/>
<jointname="LThumb1"value="0"/>
<jointname="LThumb2"value="0"/>
<jointname="LThumb3"value="0"/>
<jointname="LWristPitch"value="0"/>
<jointname="LWristRoll"value="0"/>
<jointname="LWristYaw"value="0"/>
<jointname="NeckPitch"value="0"/>
<jointname="NeckYaw"value="0"/>
<jointname="RAnklePitch"value="-0.1"/>
<jointname="RAnkleRoll"value="0"/>
<jointname="RElbowRoll"value="0"/>
<jointname="RElbowYaw"value="0"/>
<jointname="RFinger12"value="0"/>
<jointname="RFinger13"value="0"/>
<jointname="RFinger21"value="0"/>
<jointname="RFinger22"value="0"/>
<jointname="RFinger23"value="0"/>
<jointname="RFinger31"value="0"/>
<jointname="RFinger32"value="0"/>
<jointname="RFinger33"value="0"/>
<jointname="RHand"value="0"/>
<jointname="RHipPitch"value="-0.2"/>
<jointname="RHipRoll"value="0"/>
<jointname="RHipYaw"value="0"/>
<jointname="RKneePitch"value="0.3"/>
<jointname="RShoulderPitch"value="0"/>
<jointname="RShoulderYaw"value="0"/>
<jointname="RThumb1"value="0"/>
<jointname="RThumb2"value="0"/>
<jointname="RThumb3"value="0"/>
<jointname="RWristPitch"value="0"/>
<jointname="RWristRoll"value="0"/>
<jointname="RWristYaw"value="0"/>
<jointname="TrunkYaw"value="0"/>
</group_state>
<!--DISABLE COLLISIONS: By default it is assumed that any link of the robot could potentially come into collision with any other link in the robot. This tag disables collision checking between a specified pair of links. -->