Merge remote-tracking branch 'bp/master'
This commit is contained in:
@@ -1,314 +0,0 @@
|
||||
<?xml version="1.0" encoding="utf-8"?>
|
||||
<!-- =================================================================================== -->
|
||||
<!-- | This document was autogenerated by xacro from src/xarm_ros/xarm_description/urdf/xarm6_robot.urdf.xacro | -->
|
||||
<!-- | EDITING THIS FILE BY HAND IS NOT RECOMMENDED | -->
|
||||
<!-- =================================================================================== -->
|
||||
<robot name="xarm6" xmlns:xacro="http://ros.org/wiki/xacro">
|
||||
<!--
|
||||
Author: Jason Peng <jason@ufactory.cc>
|
||||
Contributers:
|
||||
-->
|
||||
<gazebo>
|
||||
<plugin filename="libgazebo_ros_control.so" name="gazebo_ros_control">
|
||||
<robotNamespace>/xarm</robotNamespace>
|
||||
<!-- <controlPeriod>0.0001</controlPeriod> -->
|
||||
<robotSimType>gazebo_ros_control/DefaultRobotHWSim</robotSimType>
|
||||
<legacyModeNS>true</legacyModeNS>
|
||||
</plugin>
|
||||
</gazebo>
|
||||
<link name="base"/>
|
||||
<joint name="base_joint" type="fixed">
|
||||
<parent link="base"/>
|
||||
<child link="link_base"/>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
</joint>
|
||||
<!-- added tool0 to comply with ROS industrial-->
|
||||
<link name="tool0"/>
|
||||
<joint name="tool_joint" type="fixed">
|
||||
<parent link="link6"/>
|
||||
<child link="tool0"/>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
</joint>
|
||||
<material name="Black">
|
||||
<color rgba="0.0 0.0 0.0 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="Silver">
|
||||
<color rgba="0.753 0.753 0.753 1.0"/>
|
||||
</material>
|
||||
<link name="link_base">
|
||||
<visual>
|
||||
<geometry>
|
||||
<mesh filename="meshes/xarm6/visual/base.stl"/>
|
||||
</geometry>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<material name="White"/>
|
||||
</visual>
|
||||
<collision>
|
||||
<geometry>
|
||||
<mesh filename="meshes/xarm6/visual/base.stl"/>
|
||||
</geometry>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
</collision>
|
||||
<inertial>
|
||||
<origin rpy="0 0 0" xyz="0.0 0.0 0.09103"/>
|
||||
<mass value="2.7"/>
|
||||
<inertia ixx="0.00494875" ixy="-3.5E-06" ixz="1.25E-05" iyy="0.00494174" iyz="1.67E-06" izz="0.002219"/>
|
||||
</inertial>
|
||||
</link>
|
||||
<link name="link1">
|
||||
<visual>
|
||||
<geometry>
|
||||
<mesh filename="meshes/xarm6/visual/link1.stl"/>
|
||||
</geometry>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<material name="White"/>
|
||||
</visual>
|
||||
<collision>
|
||||
<geometry>
|
||||
<mesh filename="meshes/xarm6/visual/link1.stl"/>
|
||||
</geometry>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
</collision>
|
||||
<inertial>
|
||||
<origin rpy="0 0 0" xyz="-0.002 0.02692 -0.01332"/>
|
||||
<mass value="2.16"/>
|
||||
<inertia ixx="0.00539427" ixy="1.095E-05" ixz="1.635E-06" iyy="0.0048979" iyz="0.000793" izz="0.00311573"/>
|
||||
</inertial>
|
||||
</link>
|
||||
<joint name="joint1" type="revolute">
|
||||
<parent link="link_base"/>
|
||||
<child link="link1"/>
|
||||
<origin rpy="0 0 0" xyz="0 0 0.267"/>
|
||||
<axis xyz="0 0 1"/>
|
||||
<limit effort="50.0" lower="-6.28318530718" upper="6.28318530718" velocity="3.14"/>
|
||||
<dynamics damping="1.0" friction="1.0"/>
|
||||
</joint>
|
||||
<link name="link2">
|
||||
<visual>
|
||||
<geometry>
|
||||
<mesh filename="meshes/xarm6/visual/link2.stl"/>
|
||||
</geometry>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<material name="White"/>
|
||||
</visual>
|
||||
<collision>
|
||||
<geometry>
|
||||
<mesh filename="meshes/xarm6/visual/link2.stl"/>
|
||||
</geometry>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
</collision>
|
||||
<inertial>
|
||||
<origin rpy="0 0 0" xyz="0.03531 -0.21398 0.03386"/>
|
||||
<mass value="1.71"/>
|
||||
<inertia ixx="0.0248674" ixy="-0.00430651" ixz="-0.00067797" iyy="0.00485548" iyz="0.00457245" izz="0.02387827"/>
|
||||
</inertial>
|
||||
</link>
|
||||
<joint name="joint2" type="revolute">
|
||||
<parent link="link1"/>
|
||||
<child link="link2"/>
|
||||
<origin rpy="-1.5708 0 0" xyz="0 0 0"/>
|
||||
<axis xyz="0 0 1"/>
|
||||
<limit effort="50.0" lower="-2.18" upper="2.18" velocity="3.14"/>
|
||||
<dynamics damping="1.0" friction="1.0"/>
|
||||
</joint>
|
||||
<link name="link3">
|
||||
<visual>
|
||||
<geometry>
|
||||
<mesh filename="meshes/xarm6/visual/link3.stl"/>
|
||||
</geometry>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<material name="White"/>
|
||||
</visual>
|
||||
<collision>
|
||||
<geometry>
|
||||
<mesh filename="meshes/xarm6/visual/link3.stl"/>
|
||||
</geometry>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
</collision>
|
||||
<inertial>
|
||||
<origin rpy="0 0 0" xyz="0.06781 0.10749 0.01457"/>
|
||||
<mass value="1.384"/>
|
||||
<inertia ixx="0.0053694" ixy="0.0014185" ixz="-0.00092094" iyy="0.0032423" iyz="-0.00169178" izz="0.00501731"/>
|
||||
</inertial>
|
||||
</link>
|
||||
<joint name="joint3" type="revolute">
|
||||
<parent link="link2"/>
|
||||
<child link="link3"/>
|
||||
<origin rpy="0 0 0" xyz="0.0535 -0.2845 0"/>
|
||||
<axis xyz="0 0 1"/>
|
||||
<limit effort="32.0" lower="-4.01" upper="0.11" velocity="3.14"/>
|
||||
<dynamics damping="1.0" friction="1.0"/>
|
||||
</joint>
|
||||
<link name="link4">
|
||||
<visual>
|
||||
<geometry>
|
||||
<mesh filename="meshes/xarm6/visual/link4.stl"/>
|
||||
</geometry>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<material name="White"/>
|
||||
</visual>
|
||||
<collision>
|
||||
<geometry>
|
||||
<mesh filename="meshes/xarm6/visual/link4.stl"/>
|
||||
</geometry>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
</collision>
|
||||
<inertial>
|
||||
<origin rpy="0 0 0" xyz="-0.00021 0.02578 -0.02538"/>
|
||||
<mass value="1.115"/>
|
||||
<inertia ixx="0.00439263" ixy="5.028E-05" ixz="1.374E-05" iyy="0.0040077" iyz="0.00045338" izz="0.00110321"/>
|
||||
</inertial>
|
||||
</link>
|
||||
<joint name="joint4" type="revolute">
|
||||
<parent link="link3"/>
|
||||
<child link="link4"/>
|
||||
<origin rpy="-1.5708 0 0" xyz="0.0775 0.3425 0"/>
|
||||
<axis xyz="0 0 1"/>
|
||||
<limit effort="32.0" lower="-6.28318530718" upper="6.28318530718" velocity="3.14"/>
|
||||
<dynamics damping="1.0" friction="1.0"/>
|
||||
</joint>
|
||||
<link name="link5">
|
||||
<visual>
|
||||
<geometry>
|
||||
<mesh filename="meshes/xarm6/visual/link5.stl"/>
|
||||
</geometry>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<material name="White"/>
|
||||
</visual>
|
||||
<collision>
|
||||
<geometry>
|
||||
<mesh filename="meshes/xarm6/visual/link5.stl"/>
|
||||
</geometry>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
</collision>
|
||||
<inertial>
|
||||
<origin rpy="0 0 0" xyz="0.05428 0.01781 0.00543"/>
|
||||
<mass value="1.275"/>
|
||||
<inertia ixx="0.001202758" ixy="0.000492428" ixz="-0.00039147" iyy="0.0022876" iyz="-1.235E-04" izz="0.0026866"/>
|
||||
</inertial>
|
||||
</link>
|
||||
<joint name="joint5" type="revolute">
|
||||
<parent link="link4"/>
|
||||
<child link="link5"/>
|
||||
<origin rpy="1.5708 0 0" xyz="0 0 0"/>
|
||||
<axis xyz="0 0 1"/>
|
||||
<limit effort="32.0" lower="-1.75" upper="3.14159265359" velocity="3.14"/>
|
||||
<dynamics damping="1.0" friction="1.0"/>
|
||||
</joint>
|
||||
<link name="link6">
|
||||
<visual>
|
||||
<geometry>
|
||||
<mesh filename="meshes/xarm6/visual/link6.stl"/>
|
||||
</geometry>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<material name="Silver"/>
|
||||
</visual>
|
||||
<collision>
|
||||
<geometry>
|
||||
<mesh filename="meshes/xarm6/visual/link6.stl"/>
|
||||
</geometry>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
</collision>
|
||||
<inertial>
|
||||
<origin rpy="0 0 0" xyz="0 0.00064 -0.00952"/>
|
||||
<mass value="0.1096"/>
|
||||
<inertia ixx="4.5293E-05" ixy="0" ixz="0" iyy="4.8111E-05" iyz="0" izz="7.9715E-05"/>
|
||||
</inertial>
|
||||
</link>
|
||||
<joint name="joint6" type="revolute">
|
||||
<parent link="link5"/>
|
||||
<child link="link6"/>
|
||||
<origin rpy="-1.5708 0 0" xyz="0.076 0.097 0"/>
|
||||
<axis xyz="0 0 1"/>
|
||||
<limit effort="20.0" lower="-6.28318530718" upper="6.28318530718" velocity="3.14"/>
|
||||
<dynamics damping="1.0" friction="1.0"/>
|
||||
</joint>
|
||||
<transmission name="tran1">
|
||||
<type>transmission_interface/SimpleTransmission</type>
|
||||
<joint name="joint1">
|
||||
<hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
|
||||
</joint>
|
||||
<actuator name="motor1">
|
||||
<hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
|
||||
<mechanicalReduction>100</mechanicalReduction>
|
||||
</actuator>
|
||||
</transmission>
|
||||
<transmission name="tran2">
|
||||
<type>transmission_interface/SimpleTransmission</type>
|
||||
<joint name="joint2">
|
||||
<hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
|
||||
</joint>
|
||||
<actuator name="motor2">
|
||||
<hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
|
||||
<mechanicalReduction>reduction</mechanicalReduction>
|
||||
</actuator>
|
||||
</transmission>
|
||||
<transmission name="tran3">
|
||||
<type>transmission_interface/SimpleTransmission</type>
|
||||
<joint name="joint3">
|
||||
<hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
|
||||
</joint>
|
||||
<actuator name="motor3">
|
||||
<hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
|
||||
<mechanicalReduction>reduction</mechanicalReduction>
|
||||
</actuator>
|
||||
</transmission>
|
||||
<transmission name="tran4">
|
||||
<type>transmission_interface/SimpleTransmission</type>
|
||||
<joint name="joint4">
|
||||
<hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
|
||||
</joint>
|
||||
<actuator name="motor3">
|
||||
<hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
|
||||
<mechanicalReduction>reduction</mechanicalReduction>
|
||||
</actuator>
|
||||
</transmission>
|
||||
<transmission name="tran5">
|
||||
<type>transmission_interface/SimpleTransmission</type>
|
||||
<joint name="joint5">
|
||||
<hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
|
||||
</joint>
|
||||
<actuator name="motor5">
|
||||
<hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
|
||||
<mechanicalReduction>reduction</mechanicalReduction>
|
||||
</actuator>
|
||||
</transmission>
|
||||
<transmission name="tran6">
|
||||
<type>transmission_interface/SimpleTransmission</type>
|
||||
<joint name="joint6">
|
||||
<hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
|
||||
</joint>
|
||||
<actuator name="motor6">
|
||||
<hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
|
||||
<mechanicalReduction>reduction</mechanicalReduction>
|
||||
</actuator>
|
||||
</transmission>
|
||||
<gazebo reference="link_base">
|
||||
<selfCollide>true</selfCollide>
|
||||
</gazebo>
|
||||
<gazebo reference="link1">
|
||||
<selfCollide>true</selfCollide>
|
||||
</gazebo>
|
||||
<gazebo reference="link2">
|
||||
<selfCollide>true</selfCollide>
|
||||
</gazebo>
|
||||
<gazebo reference="link3">
|
||||
<selfCollide>true</selfCollide>
|
||||
</gazebo>
|
||||
<gazebo reference="link4">
|
||||
<selfCollide>true</selfCollide>
|
||||
</gazebo>
|
||||
<gazebo reference="link5">
|
||||
<selfCollide>true</selfCollide>
|
||||
</gazebo>
|
||||
<gazebo reference="link6">
|
||||
<selfCollide>true</selfCollide>
|
||||
</gazebo>
|
||||
</robot>
|
||||
|
||||
@@ -27,7 +27,16 @@
|
||||
<color rgba="0.0 0.0 0.0 1.0"/>
|
||||
</material>
|
||||
<material name="Red">
|
||||
<color rgba="0.8 0.0 0.0 1.0"/>
|
||||
<color rgba="0.85 0.19 0.21 1.0"/>
|
||||
</material>
|
||||
<material name="Blue">
|
||||
<color rgba="0.28 0.52 0.92 1.0"/>
|
||||
</material>
|
||||
<material name="Green">
|
||||
<color rgba="0.23 0.72 0.32 1.0"/>
|
||||
</material>
|
||||
<material name="Yellow">
|
||||
<color rgba="0.95 0.76 0.05 1.0"/>
|
||||
</material>
|
||||
<material name="White">
|
||||
<color rgba="1.0 1.0 1.0 1.0"/>
|
||||
@@ -41,11 +50,11 @@
|
||||
<mesh filename="package://xarm_description/meshes/xarm6/visual/base.stl"/>
|
||||
</geometry>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<material name="White"/>
|
||||
<material name="Blue"/>
|
||||
</visual>
|
||||
<collision>
|
||||
<geometry>
|
||||
<mesh filename="package://xarm_description/meshes/xarm6/visual/base.stl"/>
|
||||
<mesh filename="package://xarm_description/meshes/xarm6/collision/base_vhacd.obj"/>
|
||||
</geometry>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
</collision>
|
||||
@@ -61,11 +70,11 @@
|
||||
<mesh filename="package://xarm_description/meshes/xarm6/visual/link1.stl"/>
|
||||
</geometry>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<material name="White"/>
|
||||
<material name="Red"/>
|
||||
</visual>
|
||||
<collision>
|
||||
<geometry>
|
||||
<mesh filename="package://xarm_description/meshes/xarm6/visual/link1.stl"/>
|
||||
<mesh filename="package://xarm_description/meshes/xarm6/collision/link1_vhacd.obj"/>
|
||||
</geometry>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
</collision>
|
||||
@@ -89,11 +98,11 @@
|
||||
<mesh filename="package://xarm_description/meshes/xarm6/visual/link2.stl"/>
|
||||
</geometry>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<material name="White"/>
|
||||
<material name="Yellow"/>
|
||||
</visual>
|
||||
<collision>
|
||||
<geometry>
|
||||
<mesh filename="package://xarm_description/meshes/xarm6/visual/link2.stl"/>
|
||||
<mesh filename="package://xarm_description/meshes/xarm6/collision/link2_vhacd.obj"/>
|
||||
</geometry>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
</collision>
|
||||
@@ -117,11 +126,11 @@
|
||||
<mesh filename="package://xarm_description/meshes/xarm6/visual/link3.stl"/>
|
||||
</geometry>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<material name="White"/>
|
||||
<material name="Blue"/>
|
||||
</visual>
|
||||
<collision>
|
||||
<geometry>
|
||||
<mesh filename="package://xarm_description/meshes/xarm6/visual/link3.stl"/>
|
||||
<mesh filename="package://xarm_description/meshes/xarm6/collision/link3_vhacd.obj"/>
|
||||
</geometry>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
</collision>
|
||||
@@ -145,11 +154,11 @@
|
||||
<mesh filename="package://xarm_description/meshes/xarm6/visual/link4.stl"/>
|
||||
</geometry>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<material name="White"/>
|
||||
<material name="Green"/>
|
||||
</visual>
|
||||
<collision>
|
||||
<geometry>
|
||||
<mesh filename="package://xarm_description/meshes/xarm6/visual/link4.stl"/>
|
||||
<mesh filename="package://xarm_description/meshes/xarm6/collision/link4_vhacd.obj"/>
|
||||
</geometry>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
</collision>
|
||||
@@ -173,11 +182,11 @@
|
||||
<mesh filename="package://xarm_description/meshes/xarm6/visual/link5.stl"/>
|
||||
</geometry>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
<material name="White"/>
|
||||
<material name="Red"/>
|
||||
</visual>
|
||||
<collision>
|
||||
<geometry>
|
||||
<mesh filename="package://xarm_description/meshes/xarm6/visual/link5.stl"/>
|
||||
<mesh filename="package://xarm_description/meshes/xarm6/collision/link5_vhacd.obj"/>
|
||||
</geometry>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
</collision>
|
||||
@@ -205,7 +214,7 @@
|
||||
</visual>
|
||||
<collision>
|
||||
<geometry>
|
||||
<mesh filename="package://xarm_description/meshes/xarm6/visual/link6.stl"/>
|
||||
<mesh filename="package://xarm_description/meshes/xarm6/collision/link6_vhacd.obj"/>
|
||||
</geometry>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
</collision>
|
||||
|
||||
@@ -0,0 +1,10 @@
|
||||
# Blender MTL File: 'None'
|
||||
# Material Count: 1
|
||||
|
||||
newmtl None
|
||||
Ns 500
|
||||
Ka 0.8 0.8 0.8
|
||||
Kd 0.8 0.8 0.8
|
||||
Ks 0.8 0.8 0.8
|
||||
d 1
|
||||
illum 2
|
||||
@@ -0,0 +1,189 @@
|
||||
o convex_0
|
||||
v 0.033187 0.018503 -0.027247
|
||||
v -0.037691 -0.004112 -0.027247
|
||||
v -0.036680 -0.006625 -0.028254
|
||||
v 0.013576 -0.034758 0.000399
|
||||
v -0.012050 0.035092 0.000399
|
||||
v 0.001516 -0.051863 -0.020710
|
||||
v -0.035174 -0.014657 -0.000608
|
||||
v 0.037202 0.000916 0.000399
|
||||
v -0.009541 0.036598 -0.027749
|
||||
v 0.032685 -0.018178 -0.028254
|
||||
v 0.016093 0.034593 -0.000608
|
||||
v -0.032658 0.019510 -0.000608
|
||||
v -0.005016 -0.051863 -0.008652
|
||||
v -0.024620 -0.028233 -0.028254
|
||||
v 0.028153 -0.025719 -0.000608
|
||||
v -0.028642 0.025037 -0.027247
|
||||
v 0.013074 0.035092 -0.028254
|
||||
v 0.006542 -0.051863 -0.011667
|
||||
v -0.029646 -0.022706 0.000399
|
||||
v 0.028662 0.025046 -0.000608
|
||||
v 0.013576 -0.034758 -0.028254
|
||||
v 0.037711 -0.000091 -0.027749
|
||||
v -0.037691 0.004927 -0.000608
|
||||
v -0.034673 0.013984 -0.028254
|
||||
v 0.005029 0.037614 -0.000608
|
||||
v 0.036700 -0.009629 -0.000608
|
||||
v -0.031654 -0.021191 -0.027247
|
||||
v -0.007024 -0.051855 -0.014175
|
||||
v -0.022103 0.031072 -0.000608
|
||||
v -0.013054 -0.034767 0.000399
|
||||
v 0.022123 0.031072 -0.027247
|
||||
v 0.036700 0.009963 -0.000608
|
||||
v 0.028153 -0.025719 -0.027247
|
||||
v 0.001014 -0.051863 -0.007143
|
||||
v -0.014058 -0.034767 -0.028254
|
||||
v 0.005029 0.037614 -0.027247
|
||||
v -0.034171 0.014982 0.000399
|
||||
v 0.021119 0.030572 0.000399
|
||||
v -0.016073 0.034593 -0.027247
|
||||
v -0.028133 -0.025719 -0.000608
|
||||
v -0.008028 0.037098 -0.000608
|
||||
v 0.034692 -0.015664 -0.027247
|
||||
v 0.035194 0.012477 -0.028254
|
||||
v -0.005016 -0.051863 -0.019201
|
||||
v -0.036680 0.009955 -0.027247
|
||||
v 0.006542 -0.051863 -0.017193
|
||||
v -0.037691 -0.004112 -0.000608
|
||||
v 0.031674 -0.021191 -0.000608
|
||||
v -0.035174 -0.014657 -0.027247
|
||||
v -0.023616 0.029066 -0.028254
|
||||
v 0.033187 0.018503 -0.000608
|
||||
v 0.023636 -0.028732 0.000399
|
||||
v 0.028662 0.025046 -0.027247
|
||||
v 0.036700 0.009963 -0.027247
|
||||
v -0.005016 0.037614 -0.027247
|
||||
v 0.037711 0.004936 -0.000608
|
||||
v 0.037711 -0.004112 -0.027247
|
||||
v -0.032658 0.019510 -0.027247
|
||||
v -0.035676 0.012976 -0.000608
|
||||
v 0.022123 0.031072 -0.000608
|
||||
v -0.016073 0.034593 -0.000608
|
||||
v 0.020617 -0.031246 -0.028254
|
||||
v -0.028642 0.025037 -0.000608
|
||||
v 0.016093 0.034593 -0.027247
|
||||
f 36 11 64
|
||||
f 5 4 8
|
||||
f 3 10 14
|
||||
f 10 3 17
|
||||
f 13 6 18
|
||||
f 4 5 19
|
||||
f 14 10 21
|
||||
f 17 3 24
|
||||
f 3 14 27
|
||||
f 27 14 28
|
||||
f 4 19 30
|
||||
f 15 18 33
|
||||
f 13 18 34
|
||||
f 4 30 34
|
||||
f 30 13 34
|
||||
f 21 6 35
|
||||
f 14 21 35
|
||||
f 17 9 36
|
||||
f 25 11 36
|
||||
f 19 5 37
|
||||
f 5 29 37
|
||||
f 5 8 38
|
||||
f 25 5 38
|
||||
f 11 25 38
|
||||
f 19 7 40
|
||||
f 7 27 40
|
||||
f 27 28 40
|
||||
f 28 13 40
|
||||
f 13 30 40
|
||||
f 30 19 40
|
||||
f 5 25 41
|
||||
f 9 39 41
|
||||
f 33 10 42
|
||||
f 10 17 43
|
||||
f 22 10 43
|
||||
f 6 13 44
|
||||
f 13 28 44
|
||||
f 28 14 44
|
||||
f 35 6 44
|
||||
f 14 35 44
|
||||
f 3 2 45
|
||||
f 2 23 45
|
||||
f 24 3 45
|
||||
f 18 6 46
|
||||
f 33 18 46
|
||||
f 2 7 47
|
||||
f 7 19 47
|
||||
f 23 2 47
|
||||
f 19 37 47
|
||||
f 37 23 47
|
||||
f 26 8 48
|
||||
f 15 33 48
|
||||
f 42 26 48
|
||||
f 33 42 48
|
||||
f 2 3 49
|
||||
f 7 2 49
|
||||
f 3 27 49
|
||||
f 27 7 49
|
||||
f 9 17 50
|
||||
f 24 16 50
|
||||
f 17 24 50
|
||||
f 16 29 50
|
||||
f 39 9 50
|
||||
f 29 39 50
|
||||
f 1 20 51
|
||||
f 32 1 51
|
||||
f 8 32 51
|
||||
f 38 8 51
|
||||
f 20 38 51
|
||||
f 8 4 52
|
||||
f 18 15 52
|
||||
f 4 34 52
|
||||
f 34 18 52
|
||||
f 48 8 52
|
||||
f 15 48 52
|
||||
f 20 1 53
|
||||
f 17 31 53
|
||||
f 31 20 53
|
||||
f 43 17 53
|
||||
f 1 43 53
|
||||
f 1 32 54
|
||||
f 22 43 54
|
||||
f 43 1 54
|
||||
f 36 9 55
|
||||
f 25 36 55
|
||||
f 41 25 55
|
||||
f 9 41 55
|
||||
f 8 26 56
|
||||
f 32 8 56
|
||||
f 54 32 56
|
||||
f 22 54 56
|
||||
f 10 22 57
|
||||
f 42 10 57
|
||||
f 26 42 57
|
||||
f 56 26 57
|
||||
f 22 56 57
|
||||
f 12 16 58
|
||||
f 16 24 58
|
||||
f 24 45 58
|
||||
f 58 45 59
|
||||
f 37 12 59
|
||||
f 23 37 59
|
||||
f 45 23 59
|
||||
f 12 58 59
|
||||
f 31 11 60
|
||||
f 20 31 60
|
||||
f 38 20 60
|
||||
f 11 38 60
|
||||
f 29 5 61
|
||||
f 39 29 61
|
||||
f 5 41 61
|
||||
f 41 39 61
|
||||
f 6 21 62
|
||||
f 21 10 62
|
||||
f 10 33 62
|
||||
f 46 6 62
|
||||
f 33 46 62
|
||||
f 16 12 63
|
||||
f 29 16 63
|
||||
f 12 37 63
|
||||
f 37 29 63
|
||||
f 31 17 64
|
||||
f 11 31 64
|
||||
f 17 36 64
|
||||
@@ -1,29 +0,0 @@
|
||||
import functools
|
||||
import inspect
|
||||
import pybullet
|
||||
|
||||
|
||||
class BulletClient(object):
|
||||
"""A wrapper for pybullet to manage different clients."""
|
||||
|
||||
def __init__(self, connection_mode=pybullet.DIRECT, options=""):
|
||||
"""Create a simulation and connect to it."""
|
||||
self._client = pybullet.connect(pybullet.SHARED_MEMORY)
|
||||
if (self._client < 0):
|
||||
print("options=", options)
|
||||
self._client = pybullet.connect(connection_mode, options=options)
|
||||
self._shapes = {}
|
||||
|
||||
def __del__(self):
|
||||
"""Clean up connection if not already done."""
|
||||
try:
|
||||
pybullet.disconnect(physicsClientId=self._client)
|
||||
except pybullet.error:
|
||||
pass
|
||||
|
||||
def __getattr__(self, name):
|
||||
"""Inject the client id into Bullet functions."""
|
||||
attribute = getattr(pybullet, name)
|
||||
if inspect.isbuiltin(attribute):
|
||||
attribute = functools.partial(attribute, physicsClientId=self._client)
|
||||
return attribute
|
||||
@@ -17,7 +17,7 @@ from gym import spaces
|
||||
from gym.utils import seeding
|
||||
import numpy as np
|
||||
import pybullet
|
||||
from . import bullet_client
|
||||
import pybullet_utils.bullet_client as bc
|
||||
from . import minitaur
|
||||
import pybullet_data
|
||||
from . import minitaur_env_randomizer
|
||||
@@ -150,9 +150,9 @@ class MinitaurBulletDuckEnv(gym.Env):
|
||||
self._action_repeat *= NUM_SUBSTEPS
|
||||
|
||||
if self._is_render:
|
||||
self._pybullet_client = bullet_client.BulletClient(connection_mode=pybullet.GUI)
|
||||
self._pybullet_client = bc.BulletClient(connection_mode=pybullet.GUI)
|
||||
else:
|
||||
self._pybullet_client = bullet_client.BulletClient()
|
||||
self._pybullet_client = bc.BulletClient()
|
||||
|
||||
self.seed()
|
||||
self.reset()
|
||||
|
||||
@@ -14,7 +14,7 @@ from gym import spaces
|
||||
from gym.utils import seeding
|
||||
import numpy as np
|
||||
import pybullet
|
||||
from . import bullet_client
|
||||
import pybullet_utils.bullet_client as bc
|
||||
from . import minitaur
|
||||
import os
|
||||
import pybullet_data
|
||||
@@ -145,9 +145,9 @@ class MinitaurBulletEnv(gym.Env):
|
||||
self._action_repeat *= NUM_SUBSTEPS
|
||||
|
||||
if self._is_render:
|
||||
self._pybullet_client = bullet_client.BulletClient(connection_mode=pybullet.GUI)
|
||||
self._pybullet_client = bc.BulletClient(connection_mode=pybullet.GUI)
|
||||
else:
|
||||
self._pybullet_client = bullet_client.BulletClient()
|
||||
self._pybullet_client = bc.BulletClient()
|
||||
|
||||
self.seed()
|
||||
self.reset()
|
||||
|
||||
@@ -12,7 +12,7 @@ import numpy as np
|
||||
import pybullet
|
||||
from . import racecar
|
||||
import random
|
||||
from . import bullet_client
|
||||
import pybullet_utils.bullet_client as bc
|
||||
import pybullet_data
|
||||
from pkg_resources import parse_version
|
||||
|
||||
@@ -40,9 +40,9 @@ class RacecarGymEnv(gym.Env):
|
||||
self._renders = renders
|
||||
self._isDiscrete = isDiscrete
|
||||
if self._renders:
|
||||
self._p = bullet_client.BulletClient(connection_mode=pybullet.GUI)
|
||||
self._p = bc.BulletClient(connection_mode=pybullet.GUI)
|
||||
else:
|
||||
self._p = bullet_client.BulletClient()
|
||||
self._p = bc.BulletClient()
|
||||
|
||||
self.seed()
|
||||
#self.reset()
|
||||
|
||||
@@ -10,7 +10,7 @@ from gym.utils import seeding
|
||||
import numpy as np
|
||||
import time
|
||||
import pybullet
|
||||
from . import bullet_client
|
||||
import pybullet_utils.bullet_client as bc
|
||||
from . import racecar
|
||||
import random
|
||||
import pybullet_data
|
||||
@@ -42,9 +42,9 @@ class RacecarZEDGymEnv(gym.Env):
|
||||
|
||||
self._isDiscrete = isDiscrete
|
||||
if self._renders:
|
||||
self._p = bullet_client.BulletClient(connection_mode=pybullet.GUI)
|
||||
self._p = bc.BulletClient(connection_mode=pybullet.GUI)
|
||||
else:
|
||||
self._p = bullet_client.BulletClient()
|
||||
self._p = bc.BulletClient()
|
||||
|
||||
self.seed()
|
||||
self.reset()
|
||||
|
||||
@@ -7,7 +7,12 @@ p.setAdditionalSearchPath(pd.getDataPath())
|
||||
|
||||
useFixedBase = True
|
||||
flags = p.URDF_INITIALIZE_SAT_FEATURES#0#p.URDF_USE_SELF_COLLISION
|
||||
xarm = p.loadURDF("xarm/xarm6_with_gripper.urdf", flags = flags, useFixedBase=useFixedBase)
|
||||
|
||||
#plane_pos = [0,0,0]
|
||||
#plane = p.loadURDF("plane.urdf", plane_pos, flags = flags, useFixedBase=useFixedBase)
|
||||
table_pos = [0,0,-0.625]
|
||||
table = p.loadURDF("table/table.urdf", table_pos, flags = flags, useFixedBase=useFixedBase)
|
||||
xarm = p.loadURDF("xarm/xarm6_robot.urdf", flags = flags, useFixedBase=useFixedBase)
|
||||
|
||||
while (1):
|
||||
p.stepSimulation()
|
||||
|
||||
@@ -1,54 +0,0 @@
|
||||
"""A wrapper for pybullet to manage different clients."""
|
||||
from __future__ import absolute_import
|
||||
from __future__ import division
|
||||
import functools
|
||||
import inspect
|
||||
import pybullet
|
||||
|
||||
|
||||
class BulletClient(object):
|
||||
"""A wrapper for pybullet to manage different clients."""
|
||||
|
||||
def __init__(self, connection_mode=None):
|
||||
"""Creates a Bullet client and connects to a simulation.
|
||||
|
||||
Args:
|
||||
connection_mode:
|
||||
`None` connects to an existing simulation or, if fails, creates a
|
||||
new headless simulation,
|
||||
`pybullet.GUI` creates a new simulation with a GUI,
|
||||
`pybullet.DIRECT` creates a headless simulation,
|
||||
`pybullet.SHARED_MEMORY` connects to an existing simulation.
|
||||
"""
|
||||
self._shapes = {}
|
||||
|
||||
if connection_mode is None:
|
||||
self._client = pybullet.connect(pybullet.SHARED_MEMORY)
|
||||
if self._client >= 0:
|
||||
return
|
||||
else:
|
||||
connection_mode = pybullet.DIRECT
|
||||
self._client = pybullet.connect(connection_mode)
|
||||
|
||||
def __del__(self):
|
||||
"""Clean up connection if not already done."""
|
||||
try:
|
||||
pybullet.disconnect(physicsClientId=self._client)
|
||||
except pybullet.error:
|
||||
pass
|
||||
|
||||
def __getattr__(self, name):
|
||||
"""Inject the client id into Bullet functions."""
|
||||
attribute = getattr(pybullet, name)
|
||||
if inspect.isbuiltin(attribute):
|
||||
if name not in [
|
||||
"invertTransform",
|
||||
"multiplyTransforms",
|
||||
"getMatrixFromQuaternion",
|
||||
"getEulerFromQuaternion",
|
||||
"computeViewMatrixFromYawPitchRoll",
|
||||
"computeProjectionMatrixFOV",
|
||||
"getQuaternionFromEuler",
|
||||
]: # A temporary hack for now.
|
||||
attribute = functools.partial(attribute, physicsClientId=self._client)
|
||||
return attribute
|
||||
@@ -14,7 +14,7 @@ from gym import spaces
|
||||
from gym.utils import seeding
|
||||
import numpy as np
|
||||
import pybullet
|
||||
from pybullet_envs.minitaur.envs import bullet_client
|
||||
import pybullet_utils.bullet_client as bc
|
||||
import pybullet_data
|
||||
from pybullet_envs.minitaur.envs import minitaur
|
||||
from pybullet_envs.minitaur.envs import minitaur_derpy
|
||||
@@ -223,9 +223,9 @@ class MinitaurGymEnv(gym.Env):
|
||||
self._env_randomizers = convert_to_list(env_randomizer) if env_randomizer else []
|
||||
self._episode_proto = minitaur_logging_pb2.MinitaurEpisode()
|
||||
if self._is_render:
|
||||
self._pybullet_client = bullet_client.BulletClient(connection_mode=pybullet.GUI)
|
||||
self._pybullet_client = bc.BulletClient(connection_mode=pybullet.GUI)
|
||||
else:
|
||||
self._pybullet_client = bullet_client.BulletClient()
|
||||
self._pybullet_client = bc.BulletClient()
|
||||
if self._urdf_version is None:
|
||||
self._urdf_version = DEFAULT_URDF_VERSION
|
||||
self._pybullet_client.setPhysicsEngineParameter(enableConeFriction=0)
|
||||
|
||||
@@ -14,7 +14,7 @@ from gym import spaces
|
||||
from gym.utils import seeding
|
||||
import numpy as np
|
||||
import pybullet
|
||||
from pybullet_envs.bullet import bullet_client
|
||||
import pybullet_utils.bullet_client as bc
|
||||
|
||||
from pybullet_envs.prediction import boxstack_pybullet_sim
|
||||
|
||||
@@ -71,10 +71,10 @@ class PyBulletSimGymEnv(gym.Env):
|
||||
print("urdf_root=" + self._urdf_root)
|
||||
|
||||
if self._is_render:
|
||||
self._pybullet_client = bullet_client.BulletClient(connection_mode=pybullet.GUI,
|
||||
self._pybullet_client = bc.BulletClient(connection_mode=pybullet.GUI,
|
||||
options=optionstring)
|
||||
else:
|
||||
self._pybullet_client = bullet_client.BulletClient()
|
||||
self._pybullet_client = bc.BulletClient()
|
||||
|
||||
if (debug_visualization == False):
|
||||
self._pybullet_client.configureDebugVisualizer(flag=self._pybullet_client.COV_ENABLE_GUI,
|
||||
|
||||
Reference in New Issue
Block a user