diff options
-rw-r--r-- | examples/ExampleBrowser/CMakeLists.txt | 1 | ||||
-rw-r--r-- | examples/ExampleBrowser/premake4.lua | 5 | ||||
-rw-r--r-- | examples/pybullet/gym/pybullet_data/quadruped/vision60.urdf | 568 | ||||
-rw-r--r-- | examples/pybullet/gym/pybullet_data/random_urdfs.zip | bin | 0 -> 5413261 bytes |
4 files changed, 572 insertions, 2 deletions
diff --git a/examples/ExampleBrowser/CMakeLists.txt b/examples/ExampleBrowser/CMakeLists.txt index 0b76fdead..a0dcfe57e 100644 --- a/examples/ExampleBrowser/CMakeLists.txt +++ b/examples/ExampleBrowser/CMakeLists.txt @@ -149,7 +149,6 @@ SET(BulletExampleBrowser_SRCS ../BulletRobotics/BoxStack.cpp ../BulletRobotics/JointLimit.cpp # ../BulletRobotics/GraspBox.cpp - ../BulletRobotics/FixJointBoxes.cpp ../TinyRenderer/geometry.cpp ../TinyRenderer/model.cpp diff --git a/examples/ExampleBrowser/premake4.lua b/examples/ExampleBrowser/premake4.lua index 222ad911e..067eb2c64 100644 --- a/examples/ExampleBrowser/premake4.lua +++ b/examples/ExampleBrowser/premake4.lua @@ -89,7 +89,10 @@ project "App_BulletExampleBrowser" "main.cpp", "ExampleEntries.cpp", "../InverseKinematics/*", - "../TinyRenderer/geometry.cpp", + "../BulletRobotics/FixJointBoxes.cpp", + "../BulletRobotics/BoxStack.cpp", + "../BulletRobotics/JointLimit.cpp", + "../TinyRenderer/geometry.cpp", "../TinyRenderer/model.cpp", "../TinyRenderer/tgaimage.cpp", "../TinyRenderer/our_gl.cpp", diff --git a/examples/pybullet/gym/pybullet_data/quadruped/vision60.urdf b/examples/pybullet/gym/pybullet_data/quadruped/vision60.urdf new file mode 100644 index 000000000..31ebe9e78 --- /dev/null +++ b/examples/pybullet/gym/pybullet_data/quadruped/vision60.urdf @@ -0,0 +1,568 @@ +<?xml version="1.0" ?> +<!-- =================================================================================== --> +<!-- | This document was autogenerated by xacro from vision60.urdf.xacro | --> +<!-- | EDITING THIS FILE BY HAND IS NOT RECOMMENDED | --> +<!-- =================================================================================== --> +<!-- +MIT License (modified) + +Copyright (c) 2018 Ghost Robotics +Authors: +Avik De <avik@ghostrobotics.io> +Tom Jacobs <tom.jacobs@ghostrobotics.io> + +Permission is hereby granted, free of charge, to any person obtaining a copy +of this **file** (the "Software"), to deal +in the Software without restriction, including without limitation the rights +to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +copies of the Software, and to permit persons to whom the Software is +furnished to do so, subject to the following conditions: + +The above copyright notice and this permission notice shall be included in all +copies or substantial portions of the Software. + +THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +SOFTWARE. +--> +<robot name="ngr" xmlns:xacro="http://www.ros.org/wiki/xacro"> + <!-- Define parameters --> + <!-- Define materials --> + <material name="gray"> + <color rgba="0.5 0.5 0.5 0.7"/> + </material> + <material name="darkgray"> + <color rgba="0.3 0.3 0.3 1.0"/> + </material> + <material name="blue"> + <color rgba="0 0 0.8 1"/> + </material> + <material name="black"> + <color rgba="0 0 0 1"/> + </material> + <material name="purple"> + <color rgba="0.5 0.0 0.5 1.0"/> + </material> + <material name="red"> + <color rgba="0.8 0.0 0.2 1.0"/> + </material> + <!-- Body --> + <link name="body"> + <visual> + <origin rpy="0 0 0" xyz="0 0 0"/> + <geometry> + <box size="0.88 0.25 0.19"/> + </geometry> + <material name="gray"/> + </visual> + <inertial> + <mass value="12"/> + <!-- Uniform box --> + <inertia ixx="0.0986" ixy="0" ixz="0" iyy="0.8105" iyz="0" izz="0.8369"/> + </inertial> + <!-- Just copy geometry for collision --> + <collision> + <geometry> + <box size="0.05 0.25 0.19"/> + </geometry> + </collision> + </link> + <!-- Define our leg macro --> + <!-- red new legs --> + <!-- TODO: clean this, it should be part of main leg macro --> + <!-- Define our leg macro --> + <!-- Our four legs --> + <!-- Hip motor --> + <link name="hip0"> + <visual> + <origin rpy="1.5707963268 0 0" xyz="0.0 -0.039 0"/> + <geometry> + <box size="0.195 0.1 0.17"/> + </geometry> + <material name="red"/> + </visual> + <collision> + <origin rpy="1.5707963268 0 0" xyz="0.0 -0.039 0"/> + <geometry> + <box size="0.195 0.1 0.17"/> + </geometry> + </collision> + <inertial> + <mass value="2.75"/> + <inertia ixx="0.00891458" ixy="0" ixz="0" iyy="0.0100573" iyz="0" izz="0.01533698"/> + </inertial> + </link> + <!-- Abduction joint. Joint names are: 8 9 10 11 --> + <joint name="8" type="revolute"> + <parent link="body"/> + <child link="hip0"/> + <axis xyz="1 0 0"/> + <origin xyz="0.325 0.1575 0"/> + <limit effort="375" lower="-0.43" upper="0.43" velocity="8.6"/> + <dynamics damping="0.0" friction="0.0"/> + </joint> + <!-- Upper leg --> + <link name="upper0"> + <visual> + <origin rpy="0 0 0" xyz="-0.125 0.0 0"/> + <geometry> + <box size="0.25 0.044 0.06"/> + </geometry> + <material name="blue"/> + </visual> + <collision> + <origin rpy="0 0 0" xyz="-0.125 0 0"/> + <geometry> + <box size="0.25 0.044 0.06"/> + </geometry> + </collision> + <inertial> + <mass value="0.625"/> + <inertia ixx="0.0003125" ixy="0" ixz="0" iyy="0.0040625" iyz="0" izz="0.0040625"/> + </inertial> + </link> + <!-- Hip joint. (Motor to upper leg). Joint names are: 0 2 4 6 --> + <joint name="0" type="revolute"> + <parent link="hip0"/> + <child link="upper0"/> + <axis xyz="0 -1 0"/> + <origin xyz="0 0.068 0"/> + <!-- rpy="0 -0.3 0" --> + <limit effort="87.5" lower="-3.14159265359" upper="3.14159265359" velocity="30"/> + <dynamics damping="0.0" friction="0.0"/> + </joint> + <!-- Lower leg --> + <link name="lower0"> + <visual> + <origin rpy="0 1.5707963268 0" xyz="0.14 0 -0.0355"/> + <geometry> + <cylinder length="0.28" radius="0.011"/> + </geometry> + <material name="black"/> + </visual> + <collision> + <origin rpy="0 1.5707963268 0" xyz="0.14 0 -0.0355"/> + <geometry> + <cylinder length="0.28" radius="0.011"/> + </geometry> + </collision> + <inertial> + <mass value="0.2"/> + <inertia ixx="0.00131075" ixy="0" ixz="0" iyy="0.00131075" iyz="0" izz="0.0001"/> + </inertial> + </link> + <!-- Knee joint. Joint names are: 1 3 5 7 --> + <joint name="1" type="revolute"> + <parent link="upper0"/> + <child link="lower0"/> + <axis xyz="0 1 0"/> + <origin xyz="-0.25 0 0"/> + <!--rpy="0 0.5 0"--> + <limit effort="87.5" lower="0" upper="3.14159265359" velocity="30"/> + <dynamics damping="0.0" friction="0.0"/> + </joint> + <!-- Toe --> + <link name="toe0"> + <contact> + <friction_anchor/> + <stiffness value="30000.0"/> + <damping value="1000.0"/> + <spinning_friction value="0.3"/> + <lateral_friction value="3.0"/> + </contact> + <visual> + <origin rpy="0 0 0" xyz="0 0 0"/> + <geometry> + <sphere radius="0.03"/> + </geometry> + <material name="darkgray"/> + </visual> + <collision> + <origin rpy="0 0 0" xyz="0 0 0"/> + <geometry> + <sphere radius="0.03"/> + </geometry> + </collision> + <inertial> + <mass value="0.15"/> + <inertia ixx="0.000025" ixy="0" ixz="0" iyy="0.000025" iyz="0" izz="0.000025"/> + </inertial> + </link> + <joint name="jtoe0" type="fixed"> + <parent link="lower0"/> + <child link="toe0"/> + <origin xyz="0.28 0 -0.0461"/> + <dynamics damping="0.0" friction="0.0"/> + </joint> + <!-- Hip motor --> + <link name="hip1"> + <visual> + <origin rpy="1.5707963268 0 0" xyz="0.0 -0.039 0"/> + <geometry> + <box size="0.195 0.1 0.17"/> + </geometry> + <material name="purple"/> + </visual> + <collision> + <origin rpy="1.5707963268 0 0" xyz="0.0 -0.039 0"/> + <geometry> + <box size="0.195 0.1 0.17"/> + </geometry> + </collision> + <inertial> + <mass value="2.75"/> + <inertia ixx="0.00891458" ixy="0" ixz="0" iyy="0.0100573" iyz="0" izz="0.01533698"/> + </inertial> + </link> + <!-- Abduction joint. Joint names are: 8 9 10 11 --> + <joint name="9" type="revolute"> + <parent link="body"/> + <child link="hip1"/> + <axis xyz="1 0 0"/> + <origin xyz="-0.325 0.1575 0"/> + <limit effort="375" lower="-0.43" upper="0.43" velocity="8.6"/> + <dynamics damping="0.0" friction="0.0"/> + </joint> + <!-- Upper leg --> + <link name="upper1"> + <visual> + <origin rpy="0 0 0" xyz="-0.125 0.0 0"/> + <geometry> + <box size="0.25 0.044 0.06"/> + </geometry> + <material name="blue"/> + </visual> + <collision> + <origin rpy="0 0 0" xyz="-0.125 0 0"/> + <geometry> + <box size="0.25 0.044 0.06"/> + </geometry> + </collision> + <inertial> + <mass value="0.625"/> + <inertia ixx="0.0003125" ixy="0" ixz="0" iyy="0.0040625" iyz="0" izz="0.0040625"/> + </inertial> + </link> + <!-- Hip joint. (Motor to upper leg). Joint names are: 0 2 4 6 --> + <joint name="2" type="revolute"> + <parent link="hip1"/> + <child link="upper1"/> + <axis xyz="0 -1 0"/> + <origin xyz="0 0.068 0"/> + <!-- rpy="0 -0.3 0" --> + <limit effort="87.5" lower="-3.14159265359" upper="3.14159265359" velocity="30"/> + <dynamics damping="0.0" friction="0.0"/> + </joint> + <!-- Lower leg --> + <link name="lower1"> + <visual> + <origin rpy="0 1.5707963268 0" xyz="0.14 0 -0.0355"/> + <geometry> + <cylinder length="0.28" radius="0.011"/> + </geometry> + <material name="black"/> + </visual> + <collision> + <origin rpy="0 1.5707963268 0" xyz="0.14 0 -0.0355"/> + <geometry> + <cylinder length="0.28" radius="0.011"/> + </geometry> + </collision> + <inertial> + <mass value="0.2"/> + <inertia ixx="0.00131075" ixy="0" ixz="0" iyy="0.00131075" iyz="0" izz="0.0001"/> + </inertial> + </link> + <!-- Knee joint. Joint names are: 1 3 5 7 --> + <joint name="3" type="revolute"> + <parent link="upper1"/> + <child link="lower1"/> + <axis xyz="0 1 0"/> + <origin xyz="-0.25 0 0"/> + <!--rpy="0 0.5 0"--> + <limit effort="87.5" lower="0" upper="3.14159265359" velocity="30"/> + <dynamics damping="0.0" friction="0.0"/> + </joint> + <!-- Toe --> + <link name="toe1"> + <contact> + <friction_anchor/> + <stiffness value="30000.0"/> + <damping value="1000.0"/> + <spinning_friction value="0.3"/> + <lateral_friction value="3.0"/> + </contact> + <visual> + <origin rpy="0 0 0" xyz="0 0 0"/> + <geometry> + <sphere radius="0.03"/> + </geometry> + <material name="darkgray"/> + </visual> + <collision> + <origin rpy="0 0 0" xyz="0 0 0"/> + <geometry> + <sphere radius="0.03"/> + </geometry> + </collision> + <inertial> + <mass value="0.15"/> + <inertia ixx="0.000025" ixy="0" ixz="0" iyy="0.000025" iyz="0" izz="0.000025"/> + </inertial> + </link> + <joint name="jtoe1" type="fixed"> + <parent link="lower1"/> + <child link="toe1"/> + <origin xyz="0.28 0 -0.0461"/> + <dynamics damping="0.0" friction="0.0"/> + </joint> + <!-- Hip motor --> + <link name="hip2"> + <visual> + <origin rpy="1.5707963268 0 0" xyz="0.0 0.039 0"/> + <geometry> + <box size="0.195 0.1 0.17"/> + </geometry> + <material name="red"/> + </visual> + <collision> + <origin rpy="1.5707963268 0 0" xyz="0.0 0.039 0"/> + <geometry> + <box size="0.195 0.1 0.17"/> + </geometry> + </collision> + <inertial> + <mass value="2.75"/> + <inertia ixx="0.00891458" ixy="0" ixz="0" iyy="0.0100573" iyz="0" izz="0.01533698"/> + </inertial> + </link> + <!-- Abduction joint. Joint names are: 8 9 10 11 --> + <joint name="10" type="revolute"> + <parent link="body"/> + <child link="hip2"/> + <axis xyz="1 0 0"/> + <origin xyz="0.325 -0.1575 0"/> + <limit effort="375" lower="-0.43" upper="0.43" velocity="8.6"/> + <dynamics damping="0.0" friction="0.0"/> + </joint> + <!-- Upper leg --> + <link name="upper2"> + <visual> + <origin rpy="0 0 0" xyz="-0.125 -0.0 0"/> + <geometry> + <box size="0.25 0.044 0.06"/> + </geometry> + <material name="blue"/> + </visual> + <collision> + <origin rpy="0 0 0" xyz="-0.125 0 0"/> + <geometry> + <box size="0.25 0.044 0.06"/> + </geometry> + </collision> + <inertial> + <mass value="0.625"/> + <inertia ixx="0.0003125" ixy="0" ixz="0" iyy="0.0040625" iyz="0" izz="0.0040625"/> + </inertial> + </link> + <!-- Hip joint. (Motor to upper leg). Joint names are: 0 2 4 6 --> + <joint name="4" type="revolute"> + <parent link="hip2"/> + <child link="upper2"/> + <axis xyz="0 -1 0"/> + <origin xyz="0 -0.068 0"/> + <!-- rpy="0 -0.3 0" --> + <limit effort="87.5" lower="-3.14159265359" upper="3.14159265359" velocity="30"/> + <dynamics damping="0.0" friction="0.0"/> + </joint> + <!-- Lower leg --> + <link name="lower2"> + <visual> + <origin rpy="0 1.5707963268 0" xyz="0.14 0 -0.0355"/> + <geometry> + <cylinder length="0.28" radius="0.011"/> + </geometry> + <material name="black"/> + </visual> + <collision> + <origin rpy="0 1.5707963268 0" xyz="0.14 0 -0.0355"/> + <geometry> + <cylinder length="0.28" radius="0.011"/> + </geometry> + </collision> + <inertial> + <mass value="0.2"/> + <inertia ixx="0.00131075" ixy="0" ixz="0" iyy="0.00131075" iyz="0" izz="0.0001"/> + </inertial> + </link> + <!-- Knee joint. Joint names are: 1 3 5 7 --> + <joint name="5" type="revolute"> + <parent link="upper2"/> + <child link="lower2"/> + <axis xyz="0 1 0"/> + <origin xyz="-0.25 0 0"/> + <!--rpy="0 0.5 0"--> + <limit effort="87.5" lower="0" upper="3.14159265359" velocity="30"/> + <dynamics damping="0.0" friction="0.0"/> + </joint> + <!-- Toe --> + <link name="toe2"> + <contact> + <friction_anchor/> + <stiffness value="30000.0"/> + <damping value="1000.0"/> + <spinning_friction value="0.3"/> + <lateral_friction value="3.0"/> + </contact> + <visual> + <origin rpy="0 0 0" xyz="0 0 0"/> + <geometry> + <sphere radius="0.03"/> + </geometry> + <material name="darkgray"/> + </visual> + <collision> + <origin rpy="0 0 0" xyz="0 0 0"/> + <geometry> + <sphere radius="0.03"/> + </geometry> + </collision> + <inertial> + <mass value="0.15"/> + <inertia ixx="0.000025" ixy="0" ixz="0" iyy="0.000025" iyz="0" izz="0.000025"/> + </inertial> + </link> + <joint name="jtoe2" type="fixed"> + <parent link="lower2"/> + <child link="toe2"/> + <origin xyz="0.28 0 -0.0461"/> + <dynamics damping="0.0" friction="0.0"/> + </joint> + <!-- Hip motor --> + <link name="hip3"> + <visual> + <origin rpy="1.5707963268 0 0" xyz="0.0 0.039 0"/> + <geometry> + <box size="0.195 0.1 0.17"/> + </geometry> + <material name="purple"/> + </visual> + <collision> + <origin rpy="1.5707963268 0 0" xyz="0.0 0.039 0"/> + <geometry> + <box size="0.195 0.1 0.17"/> + </geometry> + </collision> + <inertial> + <mass value="2.75"/> + <inertia ixx="0.00891458" ixy="0" ixz="0" iyy="0.0100573" iyz="0" izz="0.01533698"/> + </inertial> + </link> + <!-- Abduction joint. Joint names are: 8 9 10 11 --> + <joint name="11" type="revolute"> + <parent link="body"/> + <child link="hip3"/> + <axis xyz="1 0 0"/> + <origin xyz="-0.325 -0.1575 0"/> + <limit effort="375" lower="-0.43" upper="0.43" velocity="8.6"/> + <dynamics damping="0.0" friction="0.0"/> + </joint> + <!-- Upper leg --> + <link name="upper3"> + <visual> + <origin rpy="0 0 0" xyz="-0.125 -0.0 0"/> + <geometry> + <box size="0.25 0.044 0.06"/> + </geometry> + <material name="blue"/> + </visual> + <collision> + <origin rpy="0 0 0" xyz="-0.125 0 0"/> + <geometry> + <box size="0.25 0.044 0.06"/> + </geometry> + </collision> + <inertial> + <mass value="0.625"/> + <inertia ixx="0.0003125" ixy="0" ixz="0" iyy="0.0040625" iyz="0" izz="0.0040625"/> + </inertial> + </link> + <!-- Hip joint. (Motor to upper leg). Joint names are: 0 2 4 6 --> + <joint name="6" type="revolute"> + <parent link="hip3"/> + <child link="upper3"/> + <axis xyz="0 -1 0"/> + <origin xyz="0 -0.068 0"/> + <!-- rpy="0 -0.3 0" --> + <limit effort="87.5" lower="-3.14159265359" upper="3.14159265359" velocity="30"/> + <dynamics damping="0.0" friction="0.0"/> + </joint> + <!-- Lower leg --> + <link name="lower3"> + <visual> + <origin rpy="0 1.5707963268 0" xyz="0.14 0 -0.0355"/> + <geometry> + <cylinder length="0.28" radius="0.011"/> + </geometry> + <material name="black"/> + </visual> + <collision> + <origin rpy="0 1.5707963268 0" xyz="0.14 0 -0.0355"/> + <geometry> + <cylinder length="0.28" radius="0.011"/> + </geometry> + </collision> + <inertial> + <mass value="0.2"/> + <inertia ixx="0.00131075" ixy="0" ixz="0" iyy="0.00131075" iyz="0" izz="0.0001"/> + </inertial> + </link> + <!-- Knee joint. Joint names are: 1 3 5 7 --> + <joint name="7" type="revolute"> + <parent link="upper3"/> + <child link="lower3"/> + <axis xyz="0 1 0"/> + <origin xyz="-0.25 0 0"/> + <!--rpy="0 0.5 0"--> + <limit effort="87.5" lower="0" upper="3.14159265359" velocity="30"/> + <dynamics damping="0.0" friction="0.0"/> + </joint> + <!-- Toe --> + <link name="toe3"> + <contact> + <friction_anchor/> + <stiffness value="30000.0"/> + <damping value="1000.0"/> + <spinning_friction value="0.3"/> + <lateral_friction value="3.0"/> + </contact> + <visual> + <origin rpy="0 0 0" xyz="0 0 0"/> + <geometry> + <sphere radius="0.03"/> + </geometry> + <material name="darkgray"/> + </visual> + <collision> + <origin rpy="0 0 0" xyz="0 0 0"/> + <geometry> + <sphere radius="0.03"/> + </geometry> + </collision> + <inertial> + <mass value="0.15"/> + <inertia ixx="0.000025" ixy="0" ixz="0" iyy="0.000025" iyz="0" izz="0.000025"/> + </inertial> + </link> + <joint name="jtoe3" type="fixed"> + <parent link="lower3"/> + <child link="toe3"/> + <origin xyz="0.28 0 -0.0461"/> + <dynamics damping="0.0" friction="0.0"/> + </joint> +</robot> + diff --git a/examples/pybullet/gym/pybullet_data/random_urdfs.zip b/examples/pybullet/gym/pybullet_data/random_urdfs.zip Binary files differnew file mode 100644 index 000000000..6f100bde0 --- /dev/null +++ b/examples/pybullet/gym/pybullet_data/random_urdfs.zip |