scout_description: add meshes and urdf for scout_mini

This commit is contained in:
Pin Loon Lee
2021-10-21 16:18:57 +08:00
parent 71bd7eab20
commit b53042be5d
7 changed files with 3982 additions and 0 deletions

File diff suppressed because one or more lines are too long

File diff suppressed because one or more lines are too long

File diff suppressed because one or more lines are too long

File diff suppressed because one or more lines are too long

View 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>

View File

@@ -0,0 +1,80 @@
<?xml version="1.0"?>
<robot name="scout_mini_v2"
xmlns:xacro="http://ros.org/wiki/xacro">
<xacro:arg name="robot_namespace" default="/" />
<xacro:include filename="$(find scout_description)/urdf/scout_mini_wheel.xacro" />
<!-- Variables -->
<xacro:property name="M_PI" value="3.14159"/>
<!-- Vehicle Geometries -->
<xacro:property name="base_x_size" value="0.595000" />
<!-- <xacro:property name="base_y_size" value="0.335000" /> -->
<xacro:property name="base_y_size" value="0.395000" />
<xacro:property name="base_z_size" value="0.130000" />
<xacro:property name="wheelbase" value="0.452" />
<xacro:property name="track" value="0.49" />
<xacro:property name="wheel_vertical_offset" value="-0.0905" />
<xacro:property name="wheel_length" value="0.8520e-01" />
<xacro:property name="wheel_radius" value="0.8750e-01" />
<!-- Base link -->
<link name="base_link">
<visual>
<origin xyz="0 0 0" rpy="0 0 0" />
<geometry>
<mesh filename="package://scout_description/meshes/mini_base_link.dae" />
</geometry>
</visual>
<collision>
<origin xyz="0 0 0.008" rpy="0 0 0" />
<geometry>
<box size="${base_x_size} ${base_y_size} ${base_z_size}"/>
</geometry>
</collision>
</link>
<link name="base_footprint"/>
<joint name="base_footprint_joint" type="fixed">
<origin xyz="0 0 ${wheel_vertical_offset - wheel_radius}" rpy="0 0 0" />
<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 xyz="0 0 0" rpy="0 0 0" />
<parent link="base_link" />
<child link="inertial_link" />
</joint>
<!-- Scout wheel macros -->
<!-- wheel labeled from 0 to 3, conter-clockwise, starting from front right wheel -->
<!-- motor 1 and 2 (left side) are mechanically installed in a reversed direction -->
<xacro:scout_mini_wheel wheel_prefix="front_right">
<origin xyz="${wheelbase/2} ${-track/2} ${wheel_vertical_offset}" rpy="3.14 0 0" />
</xacro:scout_mini_wheel>
<xacro:scout_mini_wheel wheel_prefix="front_left">
<origin xyz="${wheelbase/2} ${track/2} ${wheel_vertical_offset}" rpy="0 0 0" />
</xacro:scout_mini_wheel>
<xacro:scout_mini_wheel wheel_prefix="rear_left">
<origin xyz="${-wheelbase/2} ${track/2} ${wheel_vertical_offset}" rpy="0 0 0" />
</xacro:scout_mini_wheel>
<xacro:scout_mini_wheel wheel_prefix="rear_right">
<origin xyz="${-wheelbase/2} ${-track/2} ${wheel_vertical_offset}" rpy="3.14 0 0" />
</xacro:scout_mini_wheel>
</robot>

View File

@@ -0,0 +1,60 @@
<?xml version="1.0"?>
<!--
Software License Agreement (BSD)
\file scout_wheel.xacro (adapted from wheel.urdf.xacro in husky_description)
\authors Paul Bovbel <pbovbel@clearpathrobotics.com>
Ruixiang Du <ruixiang.du@westonrobot.com>
\copyright Copyright (c) 2015, Clearpath Robotics, Inc., All rights reserved.
\copyright Copyright (c) 2020, Weston Robot Pte. Ltd., All rights reserved.
Redistribution and use in source and binary forms, with or without modification, are permitted provided that
the following conditions are met:
* Redistributions of source code must retain the above copyright notice, this list of conditions and the
following disclaimer.
* Redistributions in binary form must reproduce the above copyright notice, this list of conditions and the
following disclaimer in the documentation and/or other materials provided with the distribution.
* Neither the name of Clearpath Robotics nor the names of its contributors may be used to endorse or promote
products derived from this software without specific prior written permission.
THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND ANY EXPRESS OR IMPLIED WAR-
RANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR
PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, IN-
DIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT
OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
-->
<robot xmlns:xacro="http://ros.org/wiki/xacro" name="scout_mini_wheel">
<xacro:macro name="scout_mini_wheel" params="wheel_prefix *joint_pose">
<link name="${wheel_prefix}_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 xyz="${-0.452/2 + 0.005} ${-0.49/2 + 0.02} 0.0925" rpy="0 0 0" />
<geometry>
<mesh filename="package://scout_description/meshes/mini_wheel.dae" />
</geometry>
</visual>
<collision>
<origin xyz="0 0 0" rpy="${M_PI/2} 0 0" />
<geometry>
<cylinder length="${wheel_length}" radius="${wheel_radius}" />
</geometry>
</collision>
</link>
<joint name="${wheel_prefix}_wheel" type="continuous">
<parent link="base_link"/>
<child link="${wheel_prefix}_wheel_link"/>
<xacro:insert_block name="joint_pose"/>
<axis xyz="0 -1 0" rpy="0 0 0" />
</joint>
</xacro:macro>
</robot>