diff options
| author | Sébastien Crozet <developer@crozet.re> | 2024-05-25 23:17:15 +0200 |
|---|---|---|
| committer | Sébastien Crozet <sebastien@crozet.re> | 2024-06-09 12:09:58 +0200 |
| commit | 5c44d936f7449e7925b124681cfbfd64cb031123 (patch) | |
| tree | c78b64c703f5d9cf26230015eee85b316b706ba7 /assets | |
| parent | 0446d4457fae2021de6f18207825374dfa0ceb8d (diff) | |
| download | rapier-5c44d936f7449e7925b124681cfbfd64cb031123.tar.gz rapier-5c44d936f7449e7925b124681cfbfd64cb031123.tar.bz2 rapier-5c44d936f7449e7925b124681cfbfd64cb031123.zip | |
feat: add urdf example
Diffstat (limited to 'assets')
| -rw-r--r-- | assets/3d/sample.urdf | 132 |
1 files changed, 132 insertions, 0 deletions
diff --git a/assets/3d/sample.urdf b/assets/3d/sample.urdf new file mode 100644 index 0000000..c07d330 --- /dev/null +++ b/assets/3d/sample.urdf @@ -0,0 +1,132 @@ +<robot name="robot"> + <link name="root"> + <inertial> + <origin xyz="0 0 0.5" rpy="0 0 0"/> + <mass value="1"/> + <inertia ixx="100" ixy="0" ixz="0" iyy="100" iyz="0" izz="100" /> + </inertial> + <visual> + <origin xyz="0.0 0.0 0.0" rpy="0.0 0.0 0.0" /> + <geometry> + <box size="0.2 0.2 0.4" /> + </geometry> + <material name="Cyan"> + <color rgba="1.0 1.0 1.0 1.0"/> + </material> + </visual> + <collision> + <origin xyz="0 0 0" rpy="0 0 0"/> + <geometry> + <cylinder radius="1" length="0.5"/> + </geometry> + </collision> + </link> + <link name="shoulder1"> + <visual> + <origin xyz="0.0 0.0 0.0" rpy="0.0 0.0 0.0" /> + <geometry> + <box size="0.1 0.1 0.1" /> + </geometry> + <material name="Cyan"> + <color rgba="0 1.0 1.0 1.0"/> + </material> + </visual> + </link> + <link name="shoulder2"> + <visual> + <origin xyz="0.0 0.0 0.0" rpy="0.0 0.0 0.0" /> + <geometry> + <box size="0.1 0.1 0.1" /> + </geometry> + <material name="Cyan"> + <color rgba="1.0 1.0 0.0 1.0"/> + </material> + </visual> + </link> + <link name="shoulder3"> + <visual> + <origin xyz="0.0 0.0 0.0" rpy="0.0 0.0 0.0" /> + <geometry> + <box size="0.1 0.1 0.2" /> + </geometry> + <material name="Cyan"> + <color rgba="0.5 0.5 0.2 1.0"/> + </material> + </visual> + </link> + <link name="elbow1"> + <visual> + <origin xyz="0.0 0.0 0.0" rpy="0.0 0.0 0.0" /> + <geometry> + <box size="0.1 0.1 0.2" /> + </geometry> + <material name="Cyan"> + <color rgba="0.8 0.2 0.2 1.0"/> + </material> + </visual> + </link> + <link name="wrist1"> + <visual> + <origin xyz="0.0 0.0 0.0" rpy="0.0 0.0 0.0" /> + <geometry> + <box size="0.1 0.15 0.1" /> + </geometry> + <material name="Cyan"> + <color rgba="1.0 0.0 0.0 1.0"/> + </material> + </visual> + </link> + <joint name="shoulder_yaw" type="revolute"> + <origin xyz="0.0 0.2 0.2" /> + <parent link="root" /> + <child link="shoulder1" /> + <axis xyz="0 0 1" /> + <limit lower="-1" upper="1.0" effort="0" velocity="1.0"/> + </joint> + <link name="wrist2"> + <visual> + <origin xyz="0.0 0.0 0.0" rpy="0.0 0.0 0.0" /> + <geometry> + <box size="0.05 0.08 0.15" /> + </geometry> + <material name="Cyan"> + <color rgba="0.0 0.0 1.0 1.0"/> + </material> + </visual> + </link> + <joint name="shoulder_pitch" type="revolute"> + <origin xyz="0.0 0.1 0.0" /> + <parent link="shoulder1" /> + <child link="shoulder2" /> + <axis xyz="0 1 0" /> + <limit lower="-1" upper="1.0" effort="0" velocity="1.0"/> + </joint> + <joint name="shoulder_roll" type="revolute"> + <origin xyz="0.0 0.1 0.0" /> + <parent link="shoulder2" /> + <child link="shoulder3" /> + <axis xyz="1 0 0" /> + <limit lower="-2" upper="1.0" effort="0" velocity="1.0"/> + </joint> + <joint name="elbow_pitch" type="revolute"> + <origin xyz="0.0 0.0 -0.2" /> + <parent link="shoulder3" /> + <child link="elbow1" /> + <axis xyz="0 1 0" /> + <limit lower="-2" upper="1.0" effort="0" velocity="1.0"/> + </joint> + <joint name="wrist_yaw" type="revolute"> + <origin xyz="0.0 0.0 -0.2" /> + <parent link="elbow1" /> + <child link="wrist1" /> + <axis xyz="0 0 1" /> + <limit lower="-2" upper="1.0" effort="0" velocity="1.0"/> + </joint> + <joint name="wrist_pitch" type="revolute"> + <origin xyz="0.0 0.0 -0.2" /> + <parent link="wrist1" /> + <child link="wrist2" /> + <axis xyz="0 1 0" /> + <limit lower="-2" upper="1.0" effort="0" velocity="1.0"/> + </joint> +</robot> |
