Create project file for BussIK inverse kinematics library (premake, cmake)
URDF/SDF: add a flag to force concave mesh collisiofor static objects. <collision concave="yes" name="pod_collision"> VR: support teleporting using buttong, allow multiple controllers to be used, fast wireframe rendering, Turn off warnings about deprecated C routine in btScalar.h/b3Scalar.h Add a dummy return to stop a warning Expose defaultContactERP in shared memory api/pybullet. First start to expose IK in shared memory api/pybullet (not working yet)
This commit is contained in:
@@ -5,6 +5,7 @@
|
||||
<lateral_friction value="1.0"/>
|
||||
<rolling_friction value="0.01"/>
|
||||
<inertia_scaling value="3.0"/>
|
||||
|
||||
</contact>
|
||||
<inertial>
|
||||
<origin rpy="0 0 0" xyz="0 0 0"/>
|
||||
|
||||
@@ -2,18 +2,18 @@
|
||||
<sdf version="1.4">
|
||||
<model name="Amazon Pod">
|
||||
<static>1</static>
|
||||
<pose>0 2 0 0 0 0</pose>
|
||||
<pose>0 1 0 0 0 0</pose>
|
||||
<link name="pod_link">
|
||||
<inertial>
|
||||
<pose>0.0 .0 1.2045 0 0 0</pose>
|
||||
<mass>76.26</mass>
|
||||
<mass>0</mass>
|
||||
<inertia>
|
||||
<ixx>47</ixx>
|
||||
<ixy>-0.003456</ixy>
|
||||
<ixz>0.001474</ixz>
|
||||
<izz>13.075</izz>
|
||||
<iyz>-0.014439</iyz>
|
||||
<iyy>47</iyy>
|
||||
<ixx>0</ixx>
|
||||
<ixy>0.0</ixy>
|
||||
<ixz>0.0</ixz>
|
||||
<izz>0.0</izz>
|
||||
<iyz>0.0</iyz>
|
||||
<iyy>0.0</iyy>
|
||||
</inertia>
|
||||
</inertial>
|
||||
|
||||
@@ -30,7 +30,7 @@
|
||||
</visual>
|
||||
|
||||
|
||||
<collision name="pod_collision">
|
||||
<collision concave="yes" name="pod_collision">
|
||||
<pose>0 0 0 1.5707 0 0</pose>
|
||||
<geometry>
|
||||
<mesh>
|
||||
|
||||
Binary file not shown.
29
data/samurai.urdf
Normal file
29
data/samurai.urdf
Normal file
@@ -0,0 +1,29 @@
|
||||
<?xml version="0.0" ?>
|
||||
<robot name="cube.urdf">
|
||||
<link concave="yes" name="baseLink">
|
||||
<contact>
|
||||
<rolling_friction value="0.3"/>
|
||||
</contact>
|
||||
<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="1.5707963 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="samurai_monastry.obj" scale="1 1 1"/>
|
||||
</geometry>
|
||||
<material name="white">
|
||||
<color rgba="1 1 1 1"/>
|
||||
</material>
|
||||
</visual>
|
||||
<collision concave="yes">
|
||||
<origin rpy="1.5707963 0 0" xyz="0 0 0"/>
|
||||
<geometry>
|
||||
<mesh filename="samurai_monastry.obj" scale="1 1 1"/>
|
||||
</geometry>
|
||||
</collision>
|
||||
</link>
|
||||
</robot>
|
||||
|
||||
Reference in New Issue
Block a user