| @@ -0,0 +1,663 @@ | |||
| <?xml version="1.0"?> | |||
| <robot name="hexapod"> | |||
| <material name="black"> | |||
| <color rgba="0 0 0 1"/> | |||
| </material> | |||
| <material name="blue"> | |||
| <color rgba="0 0 1 1"/> | |||
| </material> | |||
| <material name="green"> | |||
| <color rgba="0 1 0 1"/> | |||
| </material> | |||
| <material name="red"> | |||
| <color rgba="1 0 0 1"/> | |||
| </material> | |||
| <link name="base_link"> | |||
| <!-- top and bottom plate --> | |||
| <visual> | |||
| <origin xyz="0 0 -0.034"/> | |||
| <geometry> | |||
| <box size="0.100 0.180 0.003"/> | |||
| </geometry> | |||
| <material name="black"/> | |||
| </visual> | |||
| <visual> | |||
| <origin xyz="0 0 0.034"/> | |||
| <geometry> | |||
| <box size="0.100 0.180 0.003"/> | |||
| </geometry> | |||
| <material name="black"/> | |||
| </visual> | |||
| <!-- c1 link base --> | |||
| <visual> | |||
| <origin xyz="-0.040 0.080 -0.0325"/> | |||
| <geometry> | |||
| <cylinder radius="0.0125" length="0.006"/> | |||
| </geometry> | |||
| <material name="black"/> | |||
| </visual> | |||
| <visual> | |||
| <origin xyz="-0.040 0.080 0.0325"/> | |||
| <geometry> | |||
| <cylinder radius="0.0125" length="0.006"/> | |||
| </geometry> | |||
| <material name="black"/> | |||
| </visual> | |||
| <!-- c2 link base --> | |||
| <visual> | |||
| <origin xyz="-0.060 0.000 -0.0325"/> | |||
| <geometry> | |||
| <cylinder radius="0.0125" length="0.006"/> | |||
| </geometry> | |||
| </visual> | |||
| <visual> | |||
| <origin xyz="-0.060 0.000 0.0325"/> | |||
| <geometry> | |||
| <cylinder radius="0.0125" length="0.006"/> | |||
| </geometry> | |||
| <material name="black"/> | |||
| </visual> | |||
| <!-- c3 link base --> | |||
| <visual> | |||
| <origin xyz="-0.040 -0.080 -0.0325"/> | |||
| <geometry> | |||
| <cylinder radius="0.0125" length="0.006"/> | |||
| </geometry> | |||
| </visual> | |||
| <visual> | |||
| <origin xyz="-0.040 -0.080 0.0325"/> | |||
| <geometry> | |||
| <cylinder radius="0.0125" length="0.006"/> | |||
| </geometry> | |||
| <material name="black"/> | |||
| </visual> | |||
| <!-- c4 link base --> | |||
| <visual> | |||
| <origin xyz=" 0.040 -0.080 -0.0325"/> | |||
| <geometry> | |||
| <cylinder radius="0.0125" length="0.006"/> | |||
| </geometry> | |||
| </visual> | |||
| <visual> | |||
| <origin xyz=" 0.040 -0.080 0.0325"/> | |||
| <geometry> | |||
| <cylinder radius="0.0125" length="0.006"/> | |||
| </geometry> | |||
| <material name="black"/> | |||
| </visual> | |||
| <!-- c5 link base --> | |||
| <visual> | |||
| <origin xyz=" 0.060 0.000 -0.0325"/> | |||
| <geometry> | |||
| <cylinder radius="0.0125" length="0.006"/> | |||
| </geometry> | |||
| </visual> | |||
| <visual> | |||
| <origin xyz=" 0.060 0.000 0.0325"/> | |||
| <geometry> | |||
| <cylinder radius="0.0125" length="0.006"/> | |||
| </geometry> | |||
| <material name="black"/> | |||
| </visual> | |||
| <!-- c6 link base --> | |||
| <visual> | |||
| <origin xyz=" 0.040 0.080 -0.0325"/> | |||
| <geometry> | |||
| <cylinder radius="0.0125" length="0.006"/> | |||
| </geometry> | |||
| </visual> | |||
| <visual> | |||
| <origin xyz="0.040 0.080 0.0325"/> | |||
| <geometry> | |||
| <cylinder radius="0.0125" length="0.006"/> | |||
| </geometry> | |||
| <material name="black"/> | |||
| </visual> | |||
| </link> | |||
| <!-- leg 1 --> | |||
| <link name="c1"> | |||
| <visual> | |||
| <geometry> | |||
| <box size="0.045 0.045 0.045"/> | |||
| </geometry> | |||
| <origin xyz="-0.015 0 0"/> | |||
| <material name="blue"/> | |||
| </visual> | |||
| <visual> | |||
| <geometry> | |||
| <cylinder radius="0.005" length="0.065"/> | |||
| </geometry> | |||
| <material name="blue"/> | |||
| </visual> | |||
| <visual> | |||
| <origin xyz="-0.020 0 -0.0075" rpy="-1.57 0 0"/> | |||
| <geometry> | |||
| <cylinder radius="0.005" length="0.065"/> | |||
| </geometry> | |||
| <material name="blue"/> | |||
| </visual> | |||
| </link> | |||
| <link name="f1"> | |||
| <visual> | |||
| <origin xyz="-0.040 -0.0015 0"/> | |||
| <geometry> | |||
| <box size="0.100 0.003 0.010"/> | |||
| </geometry> | |||
| <material name="green"/> | |||
| </visual> | |||
| <visual> | |||
| <origin xyz="0 -0.003 0" rpy="-1.57 0 0"/> | |||
| <geometry> | |||
| <cylinder radius="0.0125" length="0.006"/> | |||
| </geometry> | |||
| <material name="green"/> | |||
| </visual> | |||
| <visual> | |||
| <origin xyz="-0.080 -0.003 0" rpy="-1.57 0 0"/> | |||
| <geometry> | |||
| <cylinder radius="0.0125" length="0.006"/> | |||
| </geometry> | |||
| <material name="green"/> | |||
| </visual> | |||
| </link> | |||
| <link name="t1"> | |||
| <!-- servo --> | |||
| <visual> | |||
| <origin xyz="0 -0.005 0.010"/> | |||
| <geometry> | |||
| <box size="0.020 0.035 0.040"/> | |||
| </geometry> | |||
| <material name="red"/> | |||
| </visual> | |||
| <!-- tibia --> | |||
| <visual> | |||
| <origin xyz="-0.010 0 -0.0425"/> | |||
| <geometry> | |||
| <box size="0.040 0.003 0.175"/> | |||
| </geometry> | |||
| <material name="red"/> | |||
| </visual> | |||
| </link> | |||
| <joint name="base_to_c1" type="continuous"> | |||
| <parent link="base_link"/> | |||
| <child link="c1"/> | |||
| <origin xyz="-0.040 0.080 0"/> | |||
| <axis xyz="0 0 1"/> | |||
| </joint> | |||
| <joint name="c1_to_f1" type="continuous"> | |||
| <parent link="c1"/> | |||
| <child link="f1"/> | |||
| <origin xyz="-0.020 0.03 -0.0075"/> | |||
| <axis xyz="0 1 0"/> | |||
| </joint> | |||
| <joint name="f1_to_t1" type="continuous"> | |||
| <parent link="f1"/> | |||
| <child link="t1"/> | |||
| <origin xyz="-0.080 -0.025 0"/> | |||
| <axis xyz="0 1 0"/> | |||
| </joint> | |||
| <!-- leg 2 --> | |||
| <link name="c2"> | |||
| <visual> | |||
| <geometry> | |||
| <box size="0.045 0.045 0.045"/> | |||
| </geometry> | |||
| <origin xyz="-0.015 0 0"/> | |||
| <material name="blue"/> | |||
| </visual> | |||
| <visual> | |||
| <geometry> | |||
| <cylinder radius="0.005" length="0.065"/> | |||
| </geometry> | |||
| <material name="blue"/> | |||
| </visual> | |||
| <visual> | |||
| <origin xyz="-0.020 0 -0.0075" rpy="-1.57 0 0"/> | |||
| <geometry> | |||
| <cylinder radius="0.005" length="0.065"/> | |||
| </geometry> | |||
| <material name="blue"/> | |||
| </visual> | |||
| </link> | |||
| <link name="f2"> | |||
| <visual> | |||
| <origin xyz="-0.040 -0.0015 0"/> | |||
| <geometry> | |||
| <box size="0.100 0.003 0.010"/> | |||
| </geometry> | |||
| <material name="green"/> | |||
| </visual> | |||
| <visual> | |||
| <origin xyz="0 -0.003 0" rpy="-1.57 0 0"/> | |||
| <geometry> | |||
| <cylinder radius="0.0125" length="0.006"/> | |||
| </geometry> | |||
| <material name="green"/> | |||
| </visual> | |||
| <visual> | |||
| <origin xyz="-0.080 -0.003 0" rpy="-1.57 0 0"/> | |||
| <geometry> | |||
| <cylinder radius="0.0125" length="0.006"/> | |||
| </geometry> | |||
| <material name="green"/> | |||
| </visual> | |||
| </link> | |||
| <link name="t2"> | |||
| <!-- servo --> | |||
| <visual> | |||
| <origin xyz="0 -0.005 0.010"/> | |||
| <geometry> | |||
| <box size="0.020 0.035 0.040"/> | |||
| </geometry> | |||
| <material name="red"/> | |||
| </visual> | |||
| <!-- tibia --> | |||
| <visual> | |||
| <origin xyz="-0.010 0 -0.0425"/> | |||
| <geometry> | |||
| <box size="0.040 0.003 0.175"/> | |||
| </geometry> | |||
| <material name="red"/> | |||
| </visual> | |||
| </link> | |||
| <joint name="base_to_c2" type="continuous"> | |||
| <parent link="base_link"/> | |||
| <child link="c2"/> | |||
| <origin xyz="-0.060 0 0"/> | |||
| <axis xyz="0 0 1"/> | |||
| </joint> | |||
| <joint name="c2_to_f2" type="continuous"> | |||
| <parent link="c2"/> | |||
| <child link="f2"/> | |||
| <origin xyz="-0.020 0.03 -0.0075"/> | |||
| <axis xyz="0 1 0"/> | |||
| </joint> | |||
| <joint name="f2_to_t2" type="continuous"> | |||
| <parent link="f2"/> | |||
| <child link="t2"/> | |||
| <origin xyz="-0.080 -0.025 0"/> | |||
| <axis xyz="0 1 0"/> | |||
| </joint> | |||
| <!-- leg 3 --> | |||
| <link name="c3"> | |||
| <visual> | |||
| <geometry> | |||
| <box size="0.045 0.045 0.045"/> | |||
| </geometry> | |||
| <origin xyz="-0.015 0 0"/> | |||
| <material name="blue"/> | |||
| </visual> | |||
| <visual> | |||
| <geometry> | |||
| <cylinder radius="0.005" length="0.065"/> | |||
| </geometry> | |||
| <material name="blue"/> | |||
| </visual> | |||
| <visual> | |||
| <origin xyz="-0.020 0 -0.0075" rpy="-1.57 0 0"/> | |||
| <geometry> | |||
| <cylinder radius="0.005" length="0.065"/> | |||
| </geometry> | |||
| <material name="blue"/> | |||
| </visual> | |||
| </link> | |||
| <link name="f3"> | |||
| <visual> | |||
| <origin xyz="-0.040 -0.0015 0"/> | |||
| <geometry> | |||
| <box size="0.100 0.003 0.010"/> | |||
| </geometry> | |||
| <material name="green"/> | |||
| </visual> | |||
| <visual> | |||
| <origin xyz="0 -0.003 0" rpy="-1.57 0 0"/> | |||
| <geometry> | |||
| <cylinder radius="0.0125" length="0.006"/> | |||
| </geometry> | |||
| <material name="green"/> | |||
| </visual> | |||
| <visual> | |||
| <origin xyz="-0.080 -0.003 0" rpy="-1.57 0 0"/> | |||
| <geometry> | |||
| <cylinder radius="0.0125" length="0.006"/> | |||
| </geometry> | |||
| <material name="green"/> | |||
| </visual> | |||
| </link> | |||
| <link name="t3"> | |||
| <!-- servo --> | |||
| <visual> | |||
| <origin xyz="0 -0.005 0.010"/> | |||
| <geometry> | |||
| <box size="0.020 0.035 0.040"/> | |||
| </geometry> | |||
| <material name="red"/> | |||
| </visual> | |||
| <!-- tibia --> | |||
| <visual> | |||
| <origin xyz="-0.010 0 -0.0425"/> | |||
| <geometry> | |||
| <box size="0.040 0.003 0.175"/> | |||
| </geometry> | |||
| <material name="red"/> | |||
| </visual> | |||
| </link> | |||
| <joint name="base_to_c3" type="continuous"> | |||
| <parent link="base_link"/> | |||
| <child link="c3"/> | |||
| <origin xyz="-0.040 -0.080 0"/> | |||
| <axis xyz="0 0 1"/> | |||
| </joint> | |||
| <joint name="c3_to_f3" type="continuous"> | |||
| <parent link="c3"/> | |||
| <child link="f3"/> | |||
| <origin xyz="-0.020 0.03 -0.0075"/> | |||
| <axis xyz="0 1 0"/> | |||
| </joint> | |||
| <joint name="f3_to_t3" type="continuous"> | |||
| <parent link="f3"/> | |||
| <child link="t3"/> | |||
| <origin xyz="-0.080 -0.025 0"/> | |||
| <axis xyz="0 1 0"/> | |||
| </joint> | |||
| <!-- leg 4 --> | |||
| <link name="c4"> | |||
| <visual> | |||
| <geometry> | |||
| <box size="0.045 0.045 0.045"/> | |||
| </geometry> | |||
| <origin xyz="0.015 0 0"/> | |||
| <material name="blue"/> | |||
| </visual> | |||
| <visual> | |||
| <geometry> | |||
| <cylinder radius="0.005" length="0.065"/> | |||
| </geometry> | |||
| <material name="blue"/> | |||
| </visual> | |||
| <visual> | |||
| <origin xyz="0.020 0 -0.0075" rpy="-1.57 0 0"/> | |||
| <geometry> | |||
| <cylinder radius="0.005" length="0.065"/> | |||
| </geometry> | |||
| <material name="blue"/> | |||
| </visual> | |||
| </link> | |||
| <link name="f4"> | |||
| <visual> | |||
| <origin xyz="0.040 -0.0015 0"/> | |||
| <geometry> | |||
| <box size="0.100 0.003 0.010"/> | |||
| </geometry> | |||
| <material name="green"/> | |||
| </visual> | |||
| <visual> | |||
| <origin xyz="0 -0.003 0" rpy="-1.57 0 0"/> | |||
| <geometry> | |||
| <cylinder radius="0.0125" length="0.006"/> | |||
| </geometry> | |||
| <material name="green"/> | |||
| </visual> | |||
| <visual> | |||
| <origin xyz="0.080 -0.003 0" rpy="-1.57 0 0"/> | |||
| <geometry> | |||
| <cylinder radius="0.0125" length="0.006"/> | |||
| </geometry> | |||
| <material name="green"/> | |||
| </visual> | |||
| </link> | |||
| <link name="t4"> | |||
| <!-- servo --> | |||
| <visual> | |||
| <origin xyz="0 -0.005 0.010"/> | |||
| <geometry> | |||
| <box size="0.020 0.035 0.040"/> | |||
| </geometry> | |||
| <material name="red"/> | |||
| </visual> | |||
| <!-- tibia --> | |||
| <visual> | |||
| <origin xyz="0.010 0 -0.0425"/> | |||
| <geometry> | |||
| <box size="0.040 0.003 0.175"/> | |||
| </geometry> | |||
| <material name="red"/> | |||
| </visual> | |||
| </link> | |||
| <joint name="base_to_c4" type="continuous"> | |||
| <parent link="base_link"/> | |||
| <child link="c4"/> | |||
| <origin xyz="0.040 -0.080 0"/> | |||
| <axis xyz="0 0 1"/> | |||
| </joint> | |||
| <joint name="c4_to_f4" type="continuous"> | |||
| <parent link="c4"/> | |||
| <child link="f4"/> | |||
| <origin xyz="0.020 0.03 -0.0075"/> | |||
| <axis xyz="0 1 0"/> | |||
| </joint> | |||
| <joint name="f4_to_t4" type="continuous"> | |||
| <parent link="f4"/> | |||
| <child link="t4"/> | |||
| <origin xyz="0.080 -0.025 0"/> | |||
| <axis xyz="0 1 0"/> | |||
| </joint> | |||
| <!-- leg 5 --> | |||
| <link name="c5"> | |||
| <visual> | |||
| <geometry> | |||
| <box size="0.045 0.045 0.045"/> | |||
| </geometry> | |||
| <origin xyz="0.015 0 0"/> | |||
| <material name="blue"/> | |||
| </visual> | |||
| <visual> | |||
| <geometry> | |||
| <cylinder radius="0.005" length="0.065"/> | |||
| </geometry> | |||
| <material name="blue"/> | |||
| </visual> | |||
| <visual> | |||
| <origin xyz="0.020 0 -0.0075" rpy="-1.57 0 0"/> | |||
| <geometry> | |||
| <cylinder radius="0.005" length="0.065"/> | |||
| </geometry> | |||
| <material name="blue"/> | |||
| </visual> | |||
| </link> | |||
| <link name="f5"> | |||
| <visual> | |||
| <origin xyz="0.040 -0.0015 0"/> | |||
| <geometry> | |||
| <box size="0.100 0.003 0.010"/> | |||
| </geometry> | |||
| <material name="green"/> | |||
| </visual> | |||
| <visual> | |||
| <origin xyz="0 -0.003 0" rpy="-1.57 0 0"/> | |||
| <geometry> | |||
| <cylinder radius="0.0125" length="0.006"/> | |||
| </geometry> | |||
| <material name="green"/> | |||
| </visual> | |||
| <visual> | |||
| <origin xyz="0.080 -0.003 0" rpy="-1.57 0 0"/> | |||
| <geometry> | |||
| <cylinder radius="0.0125" length="0.006"/> | |||
| </geometry> | |||
| <material name="green"/> | |||
| </visual> | |||
| </link> | |||
| <link name="t5"> | |||
| <!-- servo --> | |||
| <visual> | |||
| <origin xyz="0 -0.005 0.010"/> | |||
| <geometry> | |||
| <box size="0.020 0.035 0.040"/> | |||
| </geometry> | |||
| <material name="red"/> | |||
| </visual> | |||
| <!-- tibia --> | |||
| <visual> | |||
| <origin xyz="0.010 0 -0.0425"/> | |||
| <geometry> | |||
| <box size="0.040 0.003 0.175"/> | |||
| </geometry> | |||
| <material name="red"/> | |||
| </visual> | |||
| </link> | |||
| <joint name="base_to_c5" type="continuous"> | |||
| <parent link="base_link"/> | |||
| <child link="c5"/> | |||
| <origin xyz="0.060 0 0"/> | |||
| <axis xyz="0 0 1"/> | |||
| </joint> | |||
| <joint name="c5_to_f5" type="continuous"> | |||
| <parent link="c5"/> | |||
| <child link="f5"/> | |||
| <origin xyz="0.020 0.03 -0.0075"/> | |||
| <axis xyz="0 1 0"/> | |||
| </joint> | |||
| <joint name="f5_to_t5" type="continuous"> | |||
| <parent link="f5"/> | |||
| <child link="t5"/> | |||
| <origin xyz="0.080 -0.025 0"/> | |||
| <axis xyz="0 1 0"/> | |||
| </joint> | |||
| <!-- leg 6 --> | |||
| <link name="c6"> | |||
| <visual> | |||
| <geometry> | |||
| <box size="0.045 0.045 0.045"/> | |||
| </geometry> | |||
| <origin xyz="0.015 0 0"/> | |||
| <material name="blue"/> | |||
| </visual> | |||
| <visual> | |||
| <geometry> | |||
| <cylinder radius="0.005" length="0.065"/> | |||
| </geometry> | |||
| <material name="blue"/> | |||
| </visual> | |||
| <visual> | |||
| <origin xyz="0.020 0 -0.0075" rpy="-1.57 0 0"/> | |||
| <geometry> | |||
| <cylinder radius="0.005" length="0.065"/> | |||
| </geometry> | |||
| <material name="blue"/> | |||
| </visual> | |||
| </link> | |||
| <link name="f6"> | |||
| <visual> | |||
| <origin xyz="0.040 -0.0015 0"/> | |||
| <geometry> | |||
| <box size="0.100 0.003 0.010"/> | |||
| </geometry> | |||
| <material name="green"/> | |||
| </visual> | |||
| <visual> | |||
| <origin xyz="0 -0.003 0" rpy="-1.57 0 0"/> | |||
| <geometry> | |||
| <cylinder radius="0.0125" length="0.006"/> | |||
| </geometry> | |||
| <material name="green"/> | |||
| </visual> | |||
| <visual> | |||
| <origin xyz="0.080 -0.003 0" rpy="-1.57 0 0"/> | |||
| <geometry> | |||
| <cylinder radius="0.0125" length="0.006"/> | |||
| </geometry> | |||
| <material name="green"/> | |||
| </visual> | |||
| </link> | |||
| <link name="t6"> | |||
| <!-- servo --> | |||
| <visual> | |||
| <origin xyz="0 -0.005 0.010"/> | |||
| <geometry> | |||
| <box size="0.020 0.035 0.040"/> | |||
| </geometry> | |||
| <material name="red"/> | |||
| </visual> | |||
| <!-- tibia --> | |||
| <visual> | |||
| <origin xyz="0.010 0 -0.0425"/> | |||
| <geometry> | |||
| <box size="0.040 0.003 0.175"/> | |||
| </geometry> | |||
| <material name="red"/> | |||
| </visual> | |||
| </link> | |||
| <joint name="base_to_c6" type="continuous"> | |||
| <parent link="base_link"/> | |||
| <child link="c6"/> | |||
| <origin xyz="0.040 0.080 0"/> | |||
| <axis xyz="0 0 1"/> | |||
| </joint> | |||
| <joint name="c6_to_f6" type="continuous"> | |||
| <parent link="c6"/> | |||
| <child link="f6"/> | |||
| <origin xyz="0.020 0.03 -0.0075"/> | |||
| <axis xyz="0 1 0"/> | |||
| </joint> | |||
| <joint name="f6_to_t6" type="continuous"> | |||
| <parent link="f6"/> | |||
| <child link="t6"/> | |||
| <origin xyz="0.080 -0.025 0"/> | |||
| <axis xyz="0 1 0"/> | |||
| </joint> | |||
| </robot> | |||