add husky, quadcopter and plane 100x100 meter urdf files,

to prepare for a bit of robotics, machine learning and VR fun
This commit is contained in:
Erwin Coumans
2016-07-16 23:14:16 -07:00
parent fcc9d4ebcb
commit 5cb97baba0
12 changed files with 2150 additions and 11 deletions

View File

@@ -0,0 +1,62 @@
<?xml version="1.0" ?>
<!-- adapted from Daniel Mellinger, Nathan Michael, Vijay Kumar, "Trajectory Generation and Control for Precise Aggressive Maneuvers with Quadrotors" -->
<robot xmlns="http://drake.mit.edu"
xmlns:xsi="http://www.w3.org/2001/XMLSchema-instance"
xsi:schemaLocation="http://drake.mit.edu ../../../../pods/drake/doc/drakeURDF.xsd" name="quadrotor">
<link name="base_link">
<inertial>
<mass value="0.5"/>
<origin xyz="0 0 0"/>
<inertia ixx="0.0023" ixy="0.0" ixz="0.0" iyy="0.0023" iyz="0.0" izz="0.004"/>
</inertial>
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="quadrotor_base.obj" scale=".1 .1 .1"/>
</geometry>
</visual>
<!-- note: the original hector quadrotor urdf had a (simplified, but still complex) collision mesh, too -->
<collision>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<cylinder radius=".3" length=".1"/>
</geometry>
</collision>
</link>
<frame link="base_link" name="body" rpy="0 0 0" xyz="0 0 0" />
<force_element name="prop1">
<propellor lower_limit="0" upper_limit="10" scale_factor_thrust="1.0" scale_factor_moment="0.0245">
<parent link="base_link"/>
<origin xyz=".1750 0 0"/>
<axis xyz="0 0 1"/>
</propellor>
</force_element>
<force_element name="prop2">
<propellor lower_limit="0" upper_limit="10" scale_factor_thrust="1.0" scale_factor_moment="-0.0245">
<parent link="base_link"/>
<origin xyz="0 .1750 0 "/>
<axis xyz="0 0 1"/>
</propellor>
</force_element>
<force_element name="prop3">
<propellor lower_limit="0" upper_limit="10" scale_factor_thrust="1.0" scale_factor_moment="0.0245">
<parent link="base_link"/>
<origin xyz="-.1750 0 0"/>
<axis xyz="0 0 1"/>
</propellor>
</force_element>
<force_element name="prop4">
<propellor lower_limit="0" upper_limit="10" scale_factor_thrust="1.0" scale_factor_moment="-0.0245">
<parent link="base_link"/>
<origin xyz="0 -.1750 0"/>
<axis xyz="0 0 1"/>
</propellor>
</force_element>
</robot>

File diff suppressed because it is too large Load Diff

BIN
data/checker_blue.png Normal file

Binary file not shown.

After

Width:  |  Height:  |  Size: 6.2 KiB

345
data/husky/husky.urdf Normal file
View File

@@ -0,0 +1,345 @@
<?xml version="1.0" ?>
<!-- =================================================================================== -->
<!-- | This document was autogenerated by xacro from ../urdf/husky.urdf.xacro | -->
<!-- | EDITING THIS FILE BY HAND IS NOT RECOMMENDED | -->
<!-- =================================================================================== -->
<!--
Software License Agreement (BSD)
\file husky.urdf.xacro
\authors Paul Bovbel <pbovbel@clearpathrobotics.com>
\copyright Copyright (c) 2015, Clearpath Robotics, Inc., 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 name="husky_robot" xmlns:xacro="http://ros.org/wiki/xacro">
<!-- Included URDF/XACRO Files -->
<material name="Black">
<color rgba="0.1 0.1 0.1 1.0"/>
</material>
<material name="Blue">
<color rgba="0.0 0.0 0.8 1.0"/>
</material>
<material name="Green">
<color rgba="0.0 0.8 0.0 1.0"/>
</material>
<material name="Grey">
<color rgba="0.7 0.7 0.7 1.0"/>
</material>
<material name="DarkGrey">
<color rgba="0.3 0.3 0.3 1.0"/>
</material>
<material name="Red">
<color rgba="0.8 0.0 0.0 1.0"/>
</material>
<material name="White">
<color rgba="1.0 1.0 1.0 1.0"/>
</material>
<material name="Yellow">
<color rgba="0.8 0.8 0.0 1.0"/>
</material>
<!-- Base Size -->
<!-- Wheel Mounting Positions -->
<!-- Wheel Properties -->
<!-- Base link is on the ground under the robot -->
<link name="base_footprint"/>
<gazebo reference="base_footprint">
<material>Gazebo/DarkGrey</material>
</gazebo>
<joint name="chassis_joint" type="fixed">
<origin rpy="0 0 0" xyz="0 0 0.14493"/>
<parent link="base_footprint"/>
<child link="base_link"/>
</joint>
<!-- Chassis link is the center of the robot's bottom plate -->
<link name="base_link">
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="meshes/base_link.stl"/>
</geometry>
<material name="Black"/>
</visual>
<collision>
<origin rpy="0 0 0" xyz="0 0 0.12498"/>
<geometry>
<!-- Make collision box slightly bigger in x and z directions. -->
<box size="1.0074 0.5709 0.2675"/>
</geometry>
</collision>
<inertial>
<mass value="33.455"/>
<origin xyz="-0.08748 -0.00085 0.09947"/>
<inertia ixx="0.6022" ixy="-0.02364" ixz="-0.1197" iyy="1.7386" iyz="-0.001544" izz="2.0296"/>
</inertial>
</link>
<gazebo reference="base_link">
</gazebo>
<!-- IMU Link is the standard mounting position for the UM6 IMU.-->
<!-- Can be modified with environment variables in /etc/ros/setup.bash -->
<link name="imu_link"/>
<joint name="imu_joint" type="fixed">
<origin rpy="$(optenv HUSKY_IMU_RPY 0 -1.5708 3.1416)" xyz="$(optenv HUSKY_IMU_XYZ 0.19 0 0.149)"/>
<parent link="base_link"/>
<child link="imu_link"/>
</joint>
<gazebo reference="imu_link">
</gazebo>
<!-- Husky wheel macros -->
<link name="front_left_wheel_link">
<inertial>
<mass value="2.637"/>
<origin xyz="0 0 0"/>
<inertia ixx="0.02467" ixy="0" ixz="0" iyy="0.02467" iyz="0" izz="0.04411"/>
</inertial>
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="meshes/wheel.stl"/>
</geometry>
<material name="DarkGrey"/>
</visual>
<collision>
<origin rpy="1.570795 0 0" xyz="0 0 0"/>
<geometry>
<cylinder length="0.1143" radius="0.17775"/>
</geometry>
</collision>
</link>
<gazebo reference="front_left_wheel_link">
<mu1 value="1.0"/>
<mu2 value="1.0"/>
<kp value="10000000.0"/>
<kd value="1.0"/>
<fdir1 value="1 0 0"/>
<material>Gazebo/Grey</material>
<turnGravityOff>false</turnGravityOff>
</gazebo>
<joint name="front_left_wheel" type="continuous">
<parent link="base_link"/>
<child link="front_left_wheel_link"/>
<origin rpy="0 0 0" xyz="0.256 0.2854 0.03282"/>
<axis rpy="0 0 0" xyz="0 1 0"/>
</joint>
<transmission name="front_left_wheel_trans" type="SimpleTransmission">
<type>transmission_interface/SimpleTransmission</type>
<actuator name="front_left_wheel_motor">
<mechanicalReduction>1</mechanicalReduction>
</actuator>
<joint name="front_left_wheel">
<hardwareInterface>VelocityJointInterface</hardwareInterface>
</joint>
</transmission>
<link name="front_right_wheel_link">
<inertial>
<mass value="2.637"/>
<origin xyz="0 0 0"/>
<inertia ixx="0.02467" ixy="0" ixz="0" iyy="0.02467" iyz="0" izz="0.04411"/>
</inertial>
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="meshes/wheel.stl"/>
</geometry>
<material name="DarkGrey"/>
</visual>
<collision>
<origin rpy="1.570795 0 0" xyz="0 0 0"/>
<geometry>
<cylinder length="0.1143" radius="0.17775"/>
</geometry>
</collision>
</link>
<gazebo reference="front_right_wheel_link">
<mu1 value="1.0"/>
<mu2 value="1.0"/>
<kp value="10000000.0"/>
<kd value="1.0"/>
<fdir1 value="1 0 0"/>
<material>Gazebo/Grey</material>
<turnGravityOff>false</turnGravityOff>
</gazebo>
<joint name="front_right_wheel" type="continuous">
<parent link="base_link"/>
<child link="front_right_wheel_link"/>
<origin rpy="0 0 0" xyz="0.256 -0.2854 0.03282"/>
<axis rpy="0 0 0" xyz="0 1 0"/>
</joint>
<transmission name="front_right_wheel_trans" type="SimpleTransmission">
<type>transmission_interface/SimpleTransmission</type>
<actuator name="front_right_wheel_motor">
<mechanicalReduction>1</mechanicalReduction>
</actuator>
<joint name="front_right_wheel">
<hardwareInterface>VelocityJointInterface</hardwareInterface>
</joint>
</transmission>
<link name="rear_left_wheel_link">
<inertial>
<mass value="2.637"/>
<origin xyz="0 0 0"/>
<inertia ixx="0.02467" ixy="0" ixz="0" iyy="0.02467" iyz="0" izz="0.04411"/>
</inertial>
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="meshes/wheel.stl"/>
</geometry>
<material name="DarkGrey"/>
</visual>
<collision>
<origin rpy="1.570795 0 0" xyz="0 0 0"/>
<geometry>
<cylinder length="0.1143" radius="0.17775"/>
</geometry>
</collision>
</link>
<gazebo reference="rear_left_wheel_link">
<mu1 value="1.0"/>
<mu2 value="1.0"/>
<kp value="10000000.0"/>
<kd value="1.0"/>
<fdir1 value="1 0 0"/>
<material>Gazebo/Grey</material>
<turnGravityOff>false</turnGravityOff>
</gazebo>
<joint name="rear_left_wheel" type="continuous">
<parent link="base_link"/>
<child link="rear_left_wheel_link"/>
<origin rpy="0 0 0" xyz="-0.256 0.2854 0.03282"/>
<axis rpy="0 0 0" xyz="0 1 0"/>
</joint>
<transmission name="rear_left_wheel_trans" type="SimpleTransmission">
<type>transmission_interface/SimpleTransmission</type>
<actuator name="rear_left_wheel_motor">
<mechanicalReduction>1</mechanicalReduction>
</actuator>
<joint name="rear_left_wheel">
<hardwareInterface>VelocityJointInterface</hardwareInterface>
</joint>
</transmission>
<link name="rear_right_wheel_link">
<inertial>
<mass value="2.637"/>
<origin xyz="0 0 0"/>
<inertia ixx="0.02467" ixy="0" ixz="0" iyy="0.02467" iyz="0" izz="0.04411"/>
</inertial>
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="meshes/wheel.stl"/>
</geometry>
<material name="DarkGrey"/>
</visual>
<collision>
<origin rpy="1.570795 0 0" xyz="0 0 0"/>
<geometry>
<cylinder length="0.1143" radius="0.17775"/>
</geometry>
</collision>
</link>
<gazebo reference="rear_right_wheel_link">
<mu1 value="1.0"/>
<mu2 value="1.0"/>
<kp value="10000000.0"/>
<kd value="1.0"/>
<fdir1 value="1 0 0"/>
<material>Gazebo/Grey</material>
<turnGravityOff>false</turnGravityOff>
</gazebo>
<joint name="rear_right_wheel" type="continuous">
<parent link="base_link"/>
<child link="rear_right_wheel_link"/>
<origin rpy="0 0 0" xyz="-0.256 -0.2854 0.03282"/>
<axis rpy="0 0 0" xyz="0 1 0"/>
</joint>
<transmission name="rear_right_wheel_trans" type="SimpleTransmission">
<type>transmission_interface/SimpleTransmission</type>
<actuator name="rear_right_wheel_motor">
<mechanicalReduction>1</mechanicalReduction>
</actuator>
<joint name="rear_right_wheel">
<hardwareInterface>VelocityJointInterface</hardwareInterface>
</joint>
</transmission>
<link name="top_plate_link">
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="meshes/top_plate.stl"/>
</geometry>
<material name="Yellow"/>
</visual>
</link>
<joint name="top_plate" type="fixed">
<parent link="base_link"/>
<child link="top_plate_link"/>
</joint>
<gazebo reference="top_plate_link">
<material>Gazebo/Yellow</material>
</gazebo>
<link name="user_rail_link">
<visual>
<geometry>
<mesh filename="meshes/user_rail.stl"/>
</geometry>
<material name="DarkGrey"/>
</visual>
</link>
<joint name="user_rail" type="fixed">
<origin rpy="0 0 0" xyz="0.272 0 0.245"/>
<parent link="base_link"/>
<child link="user_rail_link"/>
</joint>
<gazebo reference="user_rail_link">
<material>Gazebo/DarkGrey</material>
</gazebo>
<link name="front_bumper_link">
<visual>
<geometry>
<mesh filename="meshes/bumper.stl"/>
</geometry>
<material name="DarkGrey"/>
</visual>
</link>
<joint name="front_bumper" type="fixed">
<origin rpy="0 0 0" xyz="0.48 0 0.091"/>
<parent link="base_link"/>
<child link="front_bumper_link"/>
</joint>
<gazebo reference="front_bumper_link">
<material>Gazebo/DarkGrey</material>
</gazebo>
<link name="rear_bumper_link">
<visual>
<geometry>
<mesh filename="meshes/bumper.stl"/>
</geometry>
<material name="DarkGrey"/>
</visual>
</link>
<joint name="rear_bumper" type="fixed">
<origin rpy="0 0 3.14159" xyz="-0.48 0 0.091"/>
<parent link="base_link"/>
<child link="rear_bumper_link"/>
</joint>
<gazebo reference="rear_bumper_link">
<material>Gazebo/DarkGrey</material>
</gazebo>
</robot>

Binary file not shown.

Binary file not shown.

Binary file not shown.

BIN
data/husky/meshes/wheel.stl Normal file

Binary file not shown.

View File

@@ -10,6 +10,6 @@ newmtl Material
Ks 0.0000 0.0000 0.0000 Ks 0.0000 0.0000 0.0000
Ke 0.0000 0.0000 0.0000 Ke 0.0000 0.0000 0.0000
map_Ka cube.tga map_Ka cube.tga
map_Kd checker_grid.jpg map_Kd checker_blue.png

View File

@@ -7,9 +7,9 @@ v 5.000000 5.000000 0.000000
v -5.000000 5.000000 0.000000 v -5.000000 5.000000 0.000000
v -5.000000 -5.000000 0.000000 v -5.000000 -5.000000 0.000000
vt 1.000000 0.000000 vt 5.000000 0.000000
vt 1.000000 1.000000 vt 5.000000 5.000000
vt 0.000000 1.000000 vt 0.000000 5.000000
vt 0.000000 0.000000 vt 0.000000 0.000000
usemtl Material usemtl Material

View File

@@ -2,11 +2,21 @@
# www.blender.org # www.blender.org
mtllib plane.mtl mtllib plane.mtl
o Plane o Plane
v 100.000000 0.000000 -100.000000 v 100.000000 -100.000000 0.000000
v 100.000000 0.000000 100.000000 v 100.000000 100.000000 0.000000
v -100.000000 0.000000 100.000000 v -100.000000 100.000000 0.000000
v -100.000000 0.000000 -100.000000 v -100.000000 -100.000000 0.000000
vt 100.000000 0.000000
vt 100.000000 100.000000
vt 0.000000 100.000000
vt 0.000000 0.000000
usemtl Material usemtl Material
s off s off
f 3 2 1 f 1/1 2/2 3/3
f 4 3 1 f 1/1 3/3 4/4

26
data/plane100.urdf Normal file
View File

@@ -0,0 +1,26 @@
<?xml version="0.0" ?>
<robot name="cube.urdf">
<link name="baseLink">
<inertial>
<origin rpy="0 0 0" xyz="0 0 0"/>
<mass value=".0"/>
<inertia ixx="0" ixy="0" ixz="0" iyy="0" iyz="0" izz="0"/>
</inertial>
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="plane100.obj" scale="1 1 1"/>
</geometry>
<material name="white">
<color rgba="1 1 1 1"/>
</material>
</visual>
<collision>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<box size="10 10 0.001"/>
</geometry>
</collision>
</link>
</robot>