mirror of
https://github.com/bulletphysics/bullet3
synced 2024-12-15 22:20:12 +00:00
Merge pull request #1214 from erwincoumans/master
Added manually converted widowx.urdf from https://github.com/Robotnik…
This commit is contained in:
commit
6dfb320b8f
22
data/widowx/bsd_license.txt
Normal file
22
data/widowx/bsd_license.txt
Normal file
@ -0,0 +1,22 @@
|
||||
Converted from https://github.com/RobotnikAutomation/widowx_arm/blob/master/widowx_arm_description/package.xml
|
||||
|
||||
Copyright 2017 robotnik
|
||||
|
||||
Redistribution and use in source and binary forms, with or without modification, are permitted provided that the following conditions are met:
|
||||
|
||||
1. Redistributions of source code must retain the above copyright notice, this list of conditions and the following disclaimer.
|
||||
2. 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.
|
||||
3. Neither the name of the copyright holder 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 WARRANTIES, 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, INDIRECT, 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.
|
||||
|
||||
<package>
|
||||
<name>widowx_arm_description</name>
|
||||
<version>0.0.2</version>
|
||||
<description>The widowx_arm_description package</description>
|
||||
|
||||
<maintainer email="jmrapado@robotnik.es">Jose Rapado García</maintainer>
|
||||
<maintainer email="rnavarro@robotnik.es">Román Navarro</maintainer>
|
||||
<maintainer email="cvillar@robotnik.es">Carlos Villar</maintainer>
|
||||
|
||||
|
BIN
data/widowx/meshes/base_link.stl
Normal file
BIN
data/widowx/meshes/base_link.stl
Normal file
Binary file not shown.
BIN
data/widowx/meshes/biceps_link.stl
Normal file
BIN
data/widowx/meshes/biceps_link.stl
Normal file
Binary file not shown.
BIN
data/widowx/meshes/forearm_link.stl
Normal file
BIN
data/widowx/meshes/forearm_link.stl
Normal file
Binary file not shown.
BIN
data/widowx/meshes/gripper_hand_fixed_link.stl
Normal file
BIN
data/widowx/meshes/gripper_hand_fixed_link.stl
Normal file
Binary file not shown.
BIN
data/widowx/meshes/gripper_rail_link.stl
Normal file
BIN
data/widowx/meshes/gripper_rail_link.stl
Normal file
Binary file not shown.
BIN
data/widowx/meshes/shoulder_link.stl
Normal file
BIN
data/widowx/meshes/shoulder_link.stl
Normal file
Binary file not shown.
BIN
data/widowx/meshes/wrist_1_link.stl
Normal file
BIN
data/widowx/meshes/wrist_1_link.stl
Normal file
Binary file not shown.
BIN
data/widowx/meshes/wrist_2_link.stl
Normal file
BIN
data/widowx/meshes/wrist_2_link.stl
Normal file
Binary file not shown.
279
data/widowx/widowx.urdf
Normal file
279
data/widowx/widowx.urdf
Normal file
@ -0,0 +1,279 @@
|
||||
<?xml version="1.0" encoding="UTF-8"?>
|
||||
<robot name="widowx" xmlns:xacro="http://ros.org/wiki/xacro">
|
||||
|
||||
<material name="yellow">
|
||||
<color rgba="0.15 0.15 0.15 1.0"/>
|
||||
</material>
|
||||
|
||||
<material name="white">
|
||||
<color rgba="0.86 0.85 0.81 1.0"/>
|
||||
</material>
|
||||
|
||||
<material name="black">
|
||||
<color rgba="0.15 0.15 0.15 1.0"/>
|
||||
</material>
|
||||
|
||||
<material name="grey">
|
||||
<color rgba="0.34 0.35 0.36 1.0"/>
|
||||
</material>
|
||||
|
||||
|
||||
<material name="greyish">
|
||||
<color rgba="0.75 0.75 0.75 1.0"/>
|
||||
</material>
|
||||
|
||||
|
||||
|
||||
<link name="arm_base_link">
|
||||
<visual>
|
||||
<origin xyz="0 0 0" rpy="0 0 0" />
|
||||
<geometry>
|
||||
<mesh filename="meshes/base_link.stl"/>
|
||||
</geometry>
|
||||
<material name="black"/>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin xyz="0 0 0" rpy="0 0 0" />
|
||||
<geometry>
|
||||
<mesh filename="meshes/base_link.stl"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
<inertial>
|
||||
<origin xyz="0 0 0" rpy="0 0 0" />
|
||||
<mass value="13" />
|
||||
<inertia ixx="1.0" ixy="0.0" ixz="0.0" iyy="1.0" iyz="0.0" izz="1.0" />
|
||||
</inertial>
|
||||
</link>
|
||||
<link name="shoulder_link">
|
||||
<visual>
|
||||
<origin xyz="0 0 0" rpy="0 0 0" />
|
||||
<geometry>
|
||||
<mesh filename="meshes/shoulder_link.stl" />
|
||||
</geometry>
|
||||
<material name="greyish"/>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin xyz="0 0 0" rpy="0 0 0" />
|
||||
<geometry>
|
||||
<mesh filename="meshes/shoulder_link.stl"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
<inertial>
|
||||
<origin xyz="0 0 0" rpy="0 0 0" />
|
||||
<mass value=".1" />
|
||||
<inertia ixx="1.0" ixy="0.0" ixz="0.0" iyy="1.0" iyz="0.0" izz="1.0" />
|
||||
</inertial>
|
||||
</link>
|
||||
<link name="biceps_link">
|
||||
<visual>
|
||||
<origin xyz="0.04825 0 0.140" rpy="0 0 0" />
|
||||
<!--origin xyz="0 0 0" rpy="0 0 0" /-->
|
||||
<geometry>
|
||||
<mesh filename="meshes/biceps_link.stl" />
|
||||
</geometry>
|
||||
<material name="black"/>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin xyz="0.04825 0 0.140" rpy="0 0 0" />
|
||||
<geometry>
|
||||
<mesh filename="meshes/biceps_link.stl" />
|
||||
</geometry>
|
||||
</collision>
|
||||
<inertial>
|
||||
<origin xyz="0 0 0" rpy="0 0 0" />
|
||||
<mass value=".1" />
|
||||
<inertia ixx="1.0" ixy="0.0" ixz="0.0" iyy="1.0" iyz="0.0" izz="1.0" />
|
||||
</inertial>
|
||||
</link>
|
||||
<link name="forearm_link">
|
||||
<visual>
|
||||
<origin xyz="0 0 0.14203" rpy="0 0 0" />
|
||||
<!--origin xyz="0 0 0" rpy="0 0 0" /-->
|
||||
<geometry>
|
||||
<mesh filename="meshes/forearm_link.stl"/>
|
||||
</geometry>
|
||||
<material name="greyish"/>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin xyz="0 0 0.14203" rpy="0 0 0" />
|
||||
<geometry>
|
||||
<mesh filename="meshes/forearm_link.stl"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
<inertial>
|
||||
<origin xyz="0 0 0" rpy="0 0 0" />
|
||||
<mass value=".1" />
|
||||
<inertia ixx="1.0" ixy="0.0" ixz="0.0" iyy="1.0" iyz="0.0" izz="1.0"/>
|
||||
</inertial>
|
||||
</link>
|
||||
<link name="wrist_1_link">
|
||||
<visual>
|
||||
<origin xyz="0 0 0" rpy="0 0 0" />
|
||||
<geometry>
|
||||
<mesh filename="meshes/wrist_1_link.stl"/>
|
||||
</geometry>
|
||||
<material name="greyish"/>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin xyz="0 0 0" rpy="0 0 0" />
|
||||
<geometry>
|
||||
<mesh filename="meshes/wrist_1_link.stl"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
<inertial>
|
||||
<origin xyz="0 0 0" rpy="0 0 0" />
|
||||
<mass value=".1" />
|
||||
<inertia ixx="1.0" ixy="0.0" ixz="0.0" iyy="1.0" iyz="0.0" izz="1.0" />
|
||||
</inertial>
|
||||
</link>
|
||||
<link name="wrist_2_link">
|
||||
<visual>
|
||||
<origin xyz="0 0 0.043" rpy="0 0 0" />
|
||||
<geometry>
|
||||
<mesh filename="meshes/wrist_2_link.stl"/>
|
||||
</geometry>
|
||||
<material name="black"/>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin xyz="0 0 0.043" rpy="0 0 0" />
|
||||
<geometry>
|
||||
<mesh filename="meshes/wrist_2_link.stl"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
<inertial>
|
||||
<origin xyz="0 0 0" rpy="0 0 0" />
|
||||
<mass value=".1" />
|
||||
<inertia ixx="1.0" ixy="0.0" ixz="0.0" iyy="1.0" iyz="0.0" izz="1.0" />
|
||||
</inertial>
|
||||
</link>
|
||||
<link name="gripper_rail_link">
|
||||
<visual>
|
||||
<origin xyz="0 0 0" rpy="0 0 1.57" />
|
||||
<geometry>
|
||||
<mesh filename="meshes/gripper_rail_link.stl"/>
|
||||
</geometry>
|
||||
<material name="greyish"/>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin xyz="0 0 0" rpy="0 0 1.57" />
|
||||
<geometry>
|
||||
<mesh filename="meshes/gripper_rail_link.stl"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
<inertial>
|
||||
<origin xyz="0 0 0" rpy="0 0 0" />
|
||||
<mass value=".1" />
|
||||
<inertia ixx="1.0" ixy="0.0" ixz="0.0" iyy="1.0" iyz="0.0" izz="1.0" />
|
||||
</inertial>
|
||||
</link>
|
||||
<link name="gripper_aux_link">
|
||||
</link>
|
||||
<link name="gripper_1_link">
|
||||
<visual>
|
||||
<origin xyz="0 -0.0007 0" rpy="0 0 1.57" />
|
||||
<geometry>
|
||||
<mesh filename="meshes/gripper_hand_fixed_link.stl"/>
|
||||
</geometry>
|
||||
<material name="black"/>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin xyz="0 -0.0007 0" rpy="0 0 1.57" />
|
||||
<geometry>
|
||||
<mesh filename="meshes/gripper_hand_fixed_link.stl"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
<inertial>
|
||||
<origin xyz="0 0 0" rpy="0 0 0" />
|
||||
<mass value=".1" />
|
||||
<inertia ixx="1.0" ixy="0.0" ixz="0.0" iyy="1.0" iyz="0.0" izz="1.0" />
|
||||
</inertial>
|
||||
</link>
|
||||
<link name="gripper_2_link">
|
||||
<visual>
|
||||
<origin xyz="0 0.0007 0" rpy="0 0 -1.57" />
|
||||
<geometry>
|
||||
<mesh filename="meshes/gripper_hand_fixed_link.stl"/>
|
||||
</geometry>
|
||||
<material name="greyish"/>
|
||||
</visual>
|
||||
<collision>
|
||||
<origin xyz="0 0.0007 0" rpy="0 0 -1.57" />
|
||||
<geometry>
|
||||
<mesh filename="meshes/gripper_hand_fixed_link.stl"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
<inertial>
|
||||
<origin xyz="0 0 0" rpy="0 0 0" />
|
||||
<mass value=".1" />
|
||||
<inertia ixx="1.0" ixy="0.0" ixz="0.0" iyy="1.0" iyz="0.0" izz="1.0" />
|
||||
</inertial>
|
||||
</link>
|
||||
<!-- joints -->
|
||||
|
||||
<joint name="joint_1" type="revolute">
|
||||
<origin xyz="0 0 0.125" rpy="0 0 0" />
|
||||
<parent link="arm_base_link" />
|
||||
<child link="shoulder_link" />
|
||||
<axis xyz="0 0 1" />
|
||||
<limit lower="-2.617" upper="2.617" effort="0" velocity="0.785" />
|
||||
</joint>
|
||||
<joint name="joint_2" type="revolute">
|
||||
<!--origin xyz="0.04825 0 0.14203" rpy="0 0 0" /-->
|
||||
<origin xyz="0 0 0" rpy="0 0 0" />
|
||||
<parent link="shoulder_link" />
|
||||
<child link="biceps_link" />
|
||||
<axis xyz="0 1 0" />
|
||||
<limit lower="-1.571" upper="1.571" effort="0" velocity="1.571" />
|
||||
</joint>
|
||||
<joint name="joint_3" type="revolute">
|
||||
<origin xyz="0.04825 0 0.14203" rpy="0 1.5707963268 0" />
|
||||
<parent link="biceps_link" />
|
||||
<child link="forearm_link" />
|
||||
<axis xyz="0 1 0" />
|
||||
<limit lower="-1.571" upper="1.571" effort="0" velocity="1.571" />
|
||||
</joint>
|
||||
<joint name="joint_4" type="revolute">
|
||||
<origin xyz="0 0 0.14203" rpy="0 0 0" />
|
||||
<parent link="forearm_link" />
|
||||
<child link="wrist_1_link" />
|
||||
<axis xyz="0 1 0" />
|
||||
<limit lower="-1.745" upper="1.745" effort="0" velocity="1.571" />
|
||||
</joint>
|
||||
<joint name="joint_5" type="revolute">
|
||||
<origin xyz="0 0 0.0715" rpy="0 0 0" />
|
||||
<parent link="wrist_1_link" />
|
||||
<child link="wrist_2_link" />
|
||||
<axis xyz="0 0 1" />
|
||||
<limit lower="-2.617" upper="2.617" effort="0" velocity="1.571" />
|
||||
</joint>
|
||||
<joint name="joint_6" type="fixed">
|
||||
<origin xyz = "0 0 0.043" rpy="0 0 0" />
|
||||
<parent link="wrist_2_link" />
|
||||
<child link="gripper_rail_link" />
|
||||
<axis xyz="0 0 1" />
|
||||
<limit lower="-0.31" upper="0.1" effort="0" velocity="0.5" />
|
||||
</joint>
|
||||
<joint name="gripper_revolute_joint" type="revolute">
|
||||
<origin xyz = "0 0 0" rpy="0 0 0" />
|
||||
<parent link="gripper_rail_link" />
|
||||
<child link="gripper_aux_link" />
|
||||
<axis xyz="0 0 1" />
|
||||
<limit lower="0" upper="2.6" effort="0" velocity="0.5" />
|
||||
</joint>
|
||||
<joint name="gripper_prismatic_joint_1" type="prismatic">
|
||||
<origin xyz="0 0 0" rpy="0 0 0" />
|
||||
<parent link="gripper_rail_link" />
|
||||
<child link="gripper_1_link" />
|
||||
<axis xyz="0 -1 0" />
|
||||
<limit lower="0" upper="0.027" effort="0" velocity="0.5" />
|
||||
</joint>
|
||||
<joint name="gripper_prismatic_joint_2" type="prismatic">
|
||||
<origin xyz="0 0 0" rpy="0 0 0" />
|
||||
<parent link="gripper_rail_link" />
|
||||
<child link="gripper_2_link" />
|
||||
<mimic joint="gripper_prismatic_joint_1" />
|
||||
<axis xyz="0 1 0" />
|
||||
<limit lower="0" upper="0.027" effort="0" velocity="0.5" />
|
||||
</joint>
|
||||
|
||||
</robot>
|
21
examples/pybullet/examples/widows.py
Normal file
21
examples/pybullet/examples/widows.py
Normal file
@ -0,0 +1,21 @@
|
||||
import pybullet as p
|
||||
import time
|
||||
|
||||
p.connect(p.GUI)
|
||||
p.loadURDF("table/table.urdf", 0.5000000,0.00000,-.820000,0.000000,0.000000,0.0,1.0)
|
||||
p.setGravity(0,0,-10)
|
||||
arm = p.loadURDF("widowx/widowx.urdf",useFixedBase=True)
|
||||
|
||||
p.resetBasePositionAndOrientation(arm,[-0.098612,-0.000726,-0.194018],[0.000000,0.000000,0.000000,1.000000])
|
||||
|
||||
|
||||
while (1):
|
||||
p.stepSimulation()
|
||||
time.sleep(0.01)
|
||||
#p.saveWorld("test.py")
|
||||
viewMat = p.getDebugVisualizerCamera()[2]
|
||||
#projMatrix = [0.7499999403953552, 0.0, 0.0, 0.0, 0.0, 1.0, 0.0, 0.0, 0.0, 0.0, -1.0000200271606445, -1.0, 0.0, 0.0, -0.02000020071864128, 0.0]
|
||||
projMatrix = p.getDebugVisualizerCamera()[3]
|
||||
width=640
|
||||
height=480
|
||||
img_arr = p.getCameraImage(width=width,height=height,viewMatrix=viewMat,projectionMatrix=projMatrix)
|
Loading…
Reference in New Issue
Block a user