Merge pull request #839 from erwincoumans/master
fix r2d2.urdf and avoid self-penetrating limbs
This commit is contained in:
@@ -11,7 +11,7 @@
|
|||||||
</visual>
|
</visual>
|
||||||
<collision>
|
<collision>
|
||||||
<geometry>
|
<geometry>
|
||||||
<cylinder length="0.6" radius="0.2"/>
|
<cylinder length="0.6" radius="0.17"/>
|
||||||
</geometry>
|
</geometry>
|
||||||
</collision>
|
</collision>
|
||||||
<inertial>
|
<inertial>
|
||||||
@@ -266,7 +266,7 @@
|
|||||||
<joint name="left_gripper_joint" type="revolute">
|
<joint name="left_gripper_joint" type="revolute">
|
||||||
<axis xyz="0 0 1"/>
|
<axis xyz="0 0 1"/>
|
||||||
<limit effort="1000.0" lower="0.0" upper="0.548" velocity="0.5"/>
|
<limit effort="1000.0" lower="0.0" upper="0.548" velocity="0.5"/>
|
||||||
<origin rpy="0 0 0" xyz="0.2 0.01 0"/>
|
<origin rpy="0 0 0" xyz="0.2 0.02 0"/>
|
||||||
<parent link="gripper_pole"/>
|
<parent link="gripper_pole"/>
|
||||||
<child link="left_gripper"/>
|
<child link="left_gripper"/>
|
||||||
</joint>
|
</joint>
|
||||||
@@ -317,7 +317,7 @@
|
|||||||
<joint name="right_gripper_joint" type="revolute">
|
<joint name="right_gripper_joint" type="revolute">
|
||||||
<axis xyz="0 0 -1"/>
|
<axis xyz="0 0 -1"/>
|
||||||
<limit effort="1000.0" lower="0.0" upper="0.548" velocity="0.5"/>
|
<limit effort="1000.0" lower="0.0" upper="0.548" velocity="0.5"/>
|
||||||
<origin rpy="0 0 0" xyz="0.2 -0.01 0"/>
|
<origin rpy="0 0 0" xyz="0.2 -0.02 0"/>
|
||||||
<parent link="gripper_pole"/>
|
<parent link="gripper_pole"/>
|
||||||
<child link="right_gripper"/>
|
<child link="right_gripper"/>
|
||||||
</joint>
|
</joint>
|
||||||
@@ -368,13 +368,13 @@
|
|||||||
<link name="head">
|
<link name="head">
|
||||||
<visual>
|
<visual>
|
||||||
<geometry>
|
<geometry>
|
||||||
<sphere radius="0.2"/>
|
<sphere radius="0.16"/>
|
||||||
</geometry>
|
</geometry>
|
||||||
<material name="white"/>
|
<material name="white"/>
|
||||||
</visual>
|
</visual>
|
||||||
<collision>
|
<collision>
|
||||||
<geometry>
|
<geometry>
|
||||||
<sphere radius="0.2"/>
|
<sphere radius="0.16"/>
|
||||||
</geometry>
|
</geometry>
|
||||||
</collision>
|
</collision>
|
||||||
<inertial>
|
<inertial>
|
||||||
@@ -412,7 +412,7 @@
|
|||||||
<joint name="tobox" type="fixed">
|
<joint name="tobox" type="fixed">
|
||||||
<parent link="head"/>
|
<parent link="head"/>
|
||||||
<child link="box"/>
|
<child link="box"/>
|
||||||
<origin xyz="0 0.1414 0.1414"/>
|
<origin xyz="0 0.1214 0.1214"/>
|
||||||
</joint>
|
</joint>
|
||||||
|
|
||||||
</robot>
|
</robot>
|
||||||
|
|||||||
@@ -3,6 +3,7 @@
|
|||||||
|
|
||||||
struct CommonCameraInterface
|
struct CommonCameraInterface
|
||||||
{
|
{
|
||||||
|
virtual ~CommonCameraInterface(){}
|
||||||
virtual void getCameraProjectionMatrix(float m[16])const = 0;
|
virtual void getCameraProjectionMatrix(float m[16])const = 0;
|
||||||
virtual void getCameraViewMatrix(float m[16]) const = 0;
|
virtual void getCameraViewMatrix(float m[16]) const = 0;
|
||||||
|
|
||||||
|
|||||||
@@ -19,6 +19,7 @@ enum
|
|||||||
|
|
||||||
struct CommonRenderInterface
|
struct CommonRenderInterface
|
||||||
{
|
{
|
||||||
|
virtual ~CommonRenderInterface() {}
|
||||||
virtual void init()=0;
|
virtual void init()=0;
|
||||||
virtual void updateCamera(int upAxis)=0;
|
virtual void updateCamera(int upAxis)=0;
|
||||||
virtual void removeAllInstances() = 0;
|
virtual void removeAllInstances() = 0;
|
||||||
|
|||||||
@@ -15,7 +15,7 @@ subject to the following restrictions:
|
|||||||
|
|
||||||
|
|
||||||
#include "PhysicsServerExample.h"
|
#include "PhysicsServerExample.h"
|
||||||
#include "PhysicsClientExample.h"
|
|
||||||
#include "Bullet3Common/b3CommandLineArgs.h"
|
#include "Bullet3Common/b3CommandLineArgs.h"
|
||||||
|
|
||||||
#include "../CommonInterfaces/CommonExampleInterface.h"
|
#include "../CommonInterfaces/CommonExampleInterface.h"
|
||||||
@@ -73,16 +73,10 @@ int main(int argc, char* argv[])
|
|||||||
|
|
||||||
args.GetCmdLineArgument("shared_memory_key", gSharedMemoryKey);
|
args.GetCmdLineArgument("shared_memory_key", gSharedMemoryKey);
|
||||||
|
|
||||||
if (args.CheckCmdLineFlag("client"))
|
// options.m_option |= PHYSICS_SERVER_ENABLE_COMMAND_LOGGING;
|
||||||
{
|
// options.m_option |= PHYSICS_SERVER_REPLAY_FROM_COMMAND_LOG;
|
||||||
example = (SharedMemoryCommon*)PhysicsClientCreateFunc(options);
|
|
||||||
}else
|
|
||||||
{
|
|
||||||
// options.m_option |= PHYSICS_SERVER_ENABLE_COMMAND_LOGGING;
|
|
||||||
// options.m_option |= PHYSICS_SERVER_REPLAY_FROM_COMMAND_LOG;
|
|
||||||
|
|
||||||
example = (SharedMemoryCommon*)PhysicsServerCreateFunc(options);
|
example = (SharedMemoryCommon*)PhysicsServerCreateFunc(options);
|
||||||
}
|
|
||||||
|
|
||||||
|
|
||||||
example->initPhysics();
|
example->initPhysics();
|
||||||
|
|||||||
Reference in New Issue
Block a user