mirror of
https://github.com/westonrobot/scout_ros.git
synced 2026-01-12 11:20:02 +08:00
scout_description: add meshes and urdf for scout_mini
This commit is contained in:
144
scout_description/urdf/scout_mini.urdf
Normal file
144
scout_description/urdf/scout_mini.urdf
Normal file
@@ -0,0 +1,144 @@
|
||||
<?xml version="1.0" encoding="utf-8"?>
|
||||
<!-- =================================================================================== -->
|
||||
<!-- | This document was autogenerated by xacro from scout_mini_v2.xacro | -->
|
||||
<!-- | EDITING THIS FILE BY HAND IS NOT RECOMMENDED | -->
|
||||
<!-- =================================================================================== -->
|
||||
<robot name="scout_mini_v2">
|
||||
<!-- Base link -->
|
||||
<link name="base_link">
|
||||
<visual>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="package://scout_description/meshes/mini_base_link.dae"/>
|
||||
</geometry>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin rpy="0 0 0" xyz="0 0 0.008"/>
|
||||
<geometry>
|
||||
<box size="0.595 0.395 0.13"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
</link>
|
||||
<link name="base_footprint"/>
|
||||
<joint name="base_footprint_joint" type="fixed">
|
||||
<origin rpy="0 0 0" xyz="0 0 -0.178"/>
|
||||
<parent link="base_link"/>
|
||||
<child link="base_footprint"/>
|
||||
</joint>
|
||||
<link name="inertial_link">
|
||||
<inertial>
|
||||
<mass value="18"/>
|
||||
<origin xyz="0.0 0.0 0.0"/>
|
||||
<inertia ixx="2.288641" ixy="0" ixz="0" iyy="5.103976" iyz="0" izz="3.431465"/>
|
||||
</inertial>
|
||||
</link>
|
||||
<joint name="inertial_joint" type="fixed">
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<parent link="base_link"/>
|
||||
<child link="inertial_link"/>
|
||||
</joint>
|
||||
<link name="front_right_wheel_link">
|
||||
<inertial>
|
||||
<mass value="1"/>
|
||||
<origin xyz="0 0 0"/>
|
||||
<inertia ixx="0.7171" ixy="0" ixz="0" iyy="0.1361" iyz="0" izz="0.7171"/>
|
||||
</inertial>
|
||||
<visual>
|
||||
<!-- <origin xyz="0 0 0" rpy="0 0 0" /> -->
|
||||
<origin rpy="0 0 0" xyz="-0.221 -0.225 0.0925"/>
|
||||
<geometry>
|
||||
<mesh filename="package://scout_description/meshes/mini_wheel.dae"/>
|
||||
</geometry>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin rpy="1.570795 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<cylinder length="0.0852" radius="0.0875"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
</link>
|
||||
<joint name="front_right_wheel" type="continuous">
|
||||
<parent link="base_link"/>
|
||||
<child link="front_right_wheel_link"/>
|
||||
<origin rpy="3.14 0 0" xyz="0.226 -0.245 -0.0905"/>
|
||||
<axis rpy="0 0 0" xyz="0 -1 0"/>
|
||||
</joint>
|
||||
<link name="front_left_wheel_link">
|
||||
<inertial>
|
||||
<mass value="1"/>
|
||||
<origin xyz="0 0 0"/>
|
||||
<inertia ixx="0.7171" ixy="0" ixz="0" iyy="0.1361" iyz="0" izz="0.7171"/>
|
||||
</inertial>
|
||||
<visual>
|
||||
<!-- <origin xyz="0 0 0" rpy="0 0 0" /> -->
|
||||
<origin rpy="0 0 0" xyz="-0.221 -0.225 0.0925"/>
|
||||
<geometry>
|
||||
<mesh filename="package://scout_description/meshes/mini_wheel.dae"/>
|
||||
</geometry>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin rpy="1.570795 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<cylinder length="0.0852" radius="0.0875"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
</link>
|
||||
<joint name="front_left_wheel" type="continuous">
|
||||
<parent link="base_link"/>
|
||||
<child link="front_left_wheel_link"/>
|
||||
<origin rpy="0 0 0" xyz="0.226 0.245 -0.0905"/>
|
||||
<axis rpy="0 0 0" xyz="0 -1 0"/>
|
||||
</joint>
|
||||
<link name="rear_left_wheel_link">
|
||||
<inertial>
|
||||
<mass value="1"/>
|
||||
<origin xyz="0 0 0"/>
|
||||
<inertia ixx="0.7171" ixy="0" ixz="0" iyy="0.1361" iyz="0" izz="0.7171"/>
|
||||
</inertial>
|
||||
<visual>
|
||||
<!-- <origin xyz="0 0 0" rpy="0 0 0" /> -->
|
||||
<origin rpy="0 0 0" xyz="-0.221 -0.225 0.0925"/>
|
||||
<geometry>
|
||||
<mesh filename="package://scout_description/meshes/mini_wheel.dae"/>
|
||||
</geometry>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin rpy="1.570795 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<cylinder length="0.0852" radius="0.0875"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
</link>
|
||||
<joint name="rear_left_wheel" type="continuous">
|
||||
<parent link="base_link"/>
|
||||
<child link="rear_left_wheel_link"/>
|
||||
<origin rpy="0 0 0" xyz="-0.226 0.245 -0.0905"/>
|
||||
<axis rpy="0 0 0" xyz="0 -1 0"/>
|
||||
</joint>
|
||||
<link name="rear_right_wheel_link">
|
||||
<inertial>
|
||||
<mass value="1"/>
|
||||
<origin xyz="0 0 0"/>
|
||||
<inertia ixx="0.7171" ixy="0" ixz="0" iyy="0.1361" iyz="0" izz="0.7171"/>
|
||||
</inertial>
|
||||
<visual>
|
||||
<!-- <origin xyz="0 0 0" rpy="0 0 0" /> -->
|
||||
<origin rpy="0 0 0" xyz="-0.221 -0.225 0.0925"/>
|
||||
<geometry>
|
||||
<mesh filename="package://scout_description/meshes/mini_wheel.dae"/>
|
||||
</geometry>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin rpy="1.570795 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<cylinder length="0.0852" radius="0.0875"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
</link>
|
||||
<joint name="rear_right_wheel" type="continuous">
|
||||
<parent link="base_link"/>
|
||||
<child link="rear_right_wheel_link"/>
|
||||
<origin rpy="3.14 0 0" xyz="-0.226 -0.245 -0.0905"/>
|
||||
<axis rpy="0 0 0" xyz="0 -1 0"/>
|
||||
</joint>
|
||||
</robot>
|
||||
Reference in New Issue
Block a user