<?xml version="1.0"?> <robot name="Olympian" xmlns:xacro="http://ros.org/wiki/xacro"> <link name="base_link"> </link> <joint name="Rev20" type="revolute"> <parent link="base_link"/> <child link="Leg_Pitch_v5_2"/> <axis xyz="1 0 0"/> <limit effort="10000" velocity="10"/> <origin xyz="0.2 0.812 0.1" rpy="0 0 0"/> </joint> <link name="Leg_Pitch_v5_2"> </link> <joint name="Rev21" type="revolute"> <parent link="Leg_Pitch_v5_2"/> <child link="Leg_Roll_v4_2"/> <axis xyz="0 0 -1"/> <limit effort="10000" velocity="10"/> <origin xyz="0.05 0 -0.075" rpy="0 0 0"/> </joint> <link name="Leg_Roll_v4_2"> </link> <joint name="Rev22" type="revolute"> <parent link="Leg_Roll_v4_2"/> <child link="Upper_Leg_v4_2"/> <axis xyz="0 -1 0"/> <limit effort="10000" velocity="10"/> <origin xyz="0 -0.075 0.075" rpy="0 0 0"/> </joint> <link name="Upper_Leg_v4_2"> </link> <joint name="Rev23" type="revolute"> <parent link="Upper_Leg_v4_2"/> <child link="Lower_Leg_v6_2"/> <axis xyz="-1 0 0"/> <limit effort="10000" velocity="10"/> <origin xyz="0.05 -0.2982 0" rpy="0 0 0"/> </joint> <link name="Lower_Leg_v6_2"> </link> <joint name="Rev24" type="revolute"> <parent link="Lower_Leg_v6_2"/> <child link="Ankle_Link_v5_2"/> <axis xyz="0 0 1"/> <limit effort="10000" velocity="10"/> <origin xyz="-0.05 -0.3532 -0.03" rpy="0 0 0"/> </joint> <link name="Ankle_Link_v5_2"> </link> <joint name="Rev25" type="revolute"> <parent link="Ankle_Link_v5_2"/> <child link="Foot_v4_2"/> <axis xyz="1 0 0"/> <limit effort="10000" velocity="10"/> <origin xyz="0.02 -0.035 0.03" rpy="0 0 0"/> </joint> <link name="Foot_v4_2"> </link> <joint name="Rev12" type="revolute"> <parent link="base_link"/> <child link="Leg_Pitch_v5_1"/> <axis xyz="-1 0 0"/> <limit effort="10000" velocity="10"/> <origin xyz="0 0.812 0.1" rpy="0 0 0"/> </joint> <link name="Leg_Pitch_v5_1"> </link> <joint name="Rev13" type="revolute"> <parent link="Leg_Pitch_v5_1"/> <child link="Leg_Roll_v4_1"/> <axis xyz="0 0 -1"/> <limit effort="10000" velocity="10"/> <origin xyz="-0.05 0 -0.075" rpy="0 0 0"/> </joint> <link name="Leg_Roll_v4_1"> </link> <joint name="Rev14" type="revolute"> <parent link="Leg_Roll_v4_1"/> <child link="Upper_Leg_v4_1"/> <axis xyz="0 -1 0"/> <limit effort="10000" velocity="10"/> <origin xyz="0 -0.075 0.075" rpy="0 0 0"/> </joint> <link name="Upper_Leg_v4_1"> </link> <joint name="Rev15" type="revolute"> <parent link="Upper_Leg_v4_1"/> <child link="Lower_Leg_v6_1"/> <axis xyz="1 0 0"/> <limit effort="10000" velocity="10"/> <origin xyz="-0.05 -0.2982 0" rpy="0 0 0"/> </joint> <link name="Lower_Leg_v6_1"> </link> <joint name="Rev16" type="revolute"> <parent link="Lower_Leg_v6_1"/> <child link="Ankle_Link_v5_1"/> <axis xyz="0 0 1"/> <limit effort="10000" velocity="10"/> <origin xyz="0.05 -0.3532 -0.03" rpy="0 0 0"/> </joint> <link name="Ankle_Link_v5_1"> </link> <joint name="Rev19" type="revolute"> <parent link="Ankle_Link_v5_1"/> <child link="Foot_v4_1"/> <axis xyz="-1 0 0"/> <limit effort="10000" velocity="10"/> <origin xyz="-0.02 -0.035 0.03" rpy="0 0 0"/> </joint> <link name="Foot_v4_1"> </link> <joint name="Rev1" type="revolute"> <parent link="base_link"/> <child link="Pelvis_v7_1"/> <axis xyz="1 0 0"/> <limit effort="10000" velocity="10"/> <origin xyz="0.05 0.912 0.1" rpy="0 0 0"/> </joint> <link name="Pelvis_v7_1"> </link> <joint name="Rev2" type="revolute"> <parent link="Pelvis_v7_1"/> <child link="Chest_v13_1"/> <axis xyz="0 0 -1"/> <limit effort="10000" velocity="10"/> <origin xyz="0.05 0.075 -0.0375" rpy="0 0 0"/> </joint> <link name="Chest_v13_1"> </link> <joint name="Rev7" type="revolute"> <parent link="Chest_v13_1"/> <child link="Upper_Arm_Link_type_b_v9_2"/> <axis xyz="1 0 0"/> <limit effort="10000" velocity="10"/> <origin xyz="0.275 0.5164 0.0375" rpy="0 0 0"/> </joint> <link name="Upper_Arm_Link_type_b_v9_2"> </link> <joint name="Rev8" type="revolute"> <parent link="Upper_Arm_Link_type_b_v9_2"/> <child link="Upper_Arm_Roll_Link_v5_2"/> <axis xyz="0 0 -1"/> <limit effort="10000" velocity="10"/> <origin xyz="0.075 -0.0125 -0.05" rpy="0 0 0"/> </joint> <link name="Upper_Arm_Roll_Link_v5_2"> </link> <joint name="Rev9" type="revolute"> <parent link="Upper_Arm_Roll_Link_v5_2"/> <child link="Upper_Arm_v10_3"/> <axis xyz="0 -1 0"/> <limit effort="10000" velocity="10"/> <origin xyz="0 -0.05635 0.05" rpy="0 0 0"/> </joint> <link name="Upper_Arm_v10_3"> </link> <joint name="Rev10" type="revolute"> <parent link="Upper_Arm_v10_3"/> <child link="Lower_Arm_v8_2"/> <axis xyz="0 0 1"/> <limit effort="10000" velocity="10"/> <origin xyz="0 -0.3675 -0.05" rpy="0 0 0"/> </joint> <link name="Lower_Arm_v8_2"> </link> <joint name="Rev3" type="revolute"> <parent link="Chest_v13_1"/> <child link="Upper_Arm_Link_type_b_v9_1"/> <axis xyz="-1 0 0"/> <limit effort="10000" velocity="10"/> <origin xyz="-0.275 0.5164 0.0375" rpy="0 0 0"/> </joint> <link name="Upper_Arm_Link_type_b_v9_1"> </link> <joint name="Rev4" type="revolute"> <parent link="Upper_Arm_Link_type_b_v9_1"/> <child link="Upper_Arm_Roll_Link_v5_1"/> <axis xyz="0 0 -1"/> <limit effort="10000" velocity="10"/> <origin xyz="-0.075 -0.0125 -0.05" rpy="0 0 0"/> </joint> <link name="Upper_Arm_Roll_Link_v5_1"> </link> <joint name="Rev5" type="revolute"> <parent link="Upper_Arm_Roll_Link_v5_1"/> <child link="Upper_Arm_v10_1"/> <axis xyz="0 -1 0"/> <limit effort="10000" velocity="10"/> <origin xyz="0 -0.05635 0.05" rpy="0 0 0"/> </joint> <link name="Upper_Arm_v10_1"> </link> <joint name="Rev6" type="revolute"> <parent link="Upper_Arm_v10_1"/> <child link="Lower_Arm_v8_1"/> <axis xyz="0 0 -1"/> <limit effort="10000" velocity="10"/> <origin xyz="0 -0.3675 0.05" rpy="0 0 0"/> </joint> <link name="Lower_Arm_v8_1"> </link> <joint name="Rev11" type="revolute"> <parent link="Chest_v13_1"/> <child link="Box_Head_v5_1"/> <axis xyz="0 1 0"/> <limit effort="10000" velocity="10"/> <origin xyz="0 0.5664 0.0375" rpy="0 0 0"/> </joint> <link name="Box_Head_v5_1"> </link> </robot>