Merge pull request #817 from erwincoumans/master

avoid wavefront obj texture index out-of-bounds (most obj out-of-boun…
This commit is contained in:
erwincoumans
2016-10-05 17:28:23 -07:00
committed by GitHub
9 changed files with 120 additions and 44 deletions

View File

@@ -2,18 +2,19 @@
[![Travis Build Status](https://api.travis-ci.org/bulletphysics/bullet3.png?branch=master)](https://travis-ci.org/bulletphysics/bullet3)
[![Appveyor Build status](https://ci.appveyor.com/api/projects/status/6sly9uxajr6xsstq)](https://ci.appveyor.com/project/erwincoumans/bullet3)
# Bullet 2.x including pybullet and experimental Bullet 3 OpenCL.
# Bullet 2.x including pybullet, Virtual Reality support
This is the official repository of Bullet 2.x, moved from http://bullet.googlecode.com
It includes the optional experimental Bullet 3 GPU pipeline.
The Bullet 2 API will stay default and up-to-date while slowly moving to Bullet 3.
The steps towards Bullet 3 are in a nutshell:
The Bullet 2 API will stay default and up-to-date while slowly moving to a new API.
The steps towards a new API is in a nutshell:
1. The old Bullet2 demos are being merged into the examples/ExampleBrowser
2. A new Bullet 3 API is created
3. All Bullet2 functionality is added to Bullet 3.
4. The OpenCL examples in the ExampleBrowser can be enabled using --enable_experimental_opencl
2. A new physics-engine agnostic C-API is created, see examples/SharedMemory/PhysicsClientC_API.h
3. Python bindings in pybullet are on top of this C-API, see examples/pybullet
4. A Virtual Reality sandbox using openvr for HTC Vive and Oculus Rift is available
5. The OpenCL examples in the ExampleBrowser can be enabled using --enable_experimental_opencl
You can still use svn or svn externals using the github git repository: use svn co https://github.com/bulletphysics/bullet3/trunk
@@ -49,6 +50,18 @@ All source code files are licensed under the permissive zlib license
Click on build_visual_studio.bat and open build3/vs2010/0MySolution.sln
**Windows Virtual Reality sandbox for HTC Vive and Oculus Rift**
Click on build_visual_studio_vr_pybullet_double.bat and open build3/vs2010/0MySolution.sln
Edit this batch file to choose where Python include/lib directories are located.
Build and run the App_SharedMemoryPhysics_VR project, preferably in Release/optimized build.
You can connect from Python pybullet to the sandbox using:
```
import pybullet as p
p.connect(p.SHARED_MEMORY)
```
**Linux and Mac OSX gnu make**
In a terminal type:
@@ -80,9 +93,6 @@ You can just run it though a terminal/command prompt, or by clicking it.
```
[--start_demo_name="Demo Name"] Start with a selected demo
[--enable_pybullet] Build with pybullet Python bindings. See also examples/pybullet
[--enable_openvr] Build with VR support for HTC Vive and Oculus Rift using OpenVR
[--enable_experimental_opencl] Enable some experimental OpenCL examples
[--mp4=moviename.mp4] Create a mp4 movie of the window, requires ffmpeg installed
[--mouse_move_multiplier=0.400000] Set the mouse move sensitivity
[--mouse_wheel_multiplier=0.01] Set the mouse wheel sensitivity

View File

@@ -1,9 +1,5 @@
IF NOT EXIST bin mkdir bin
IF NOT EXIST bin\openvr_api.dll copy examples\ThirdPartyLibs\openvr\bin\win32\openvr_api.dll bin
cd build3
premake4 --enable_openvr --targetdir="../bin" vs2010
rem premake4 --double --enable_pybullet --python_include_dir="C:/Python-3.5.2/include" --python_lib_dir="C:/Python-3.5.2/libs" --enable_openvr --targetdir="../bin" vs2010
pause
premake4 --targetdir="../bin" vs2010
start vs2010

View File

@@ -0,0 +1,8 @@
IF NOT EXIST bin mkdir bin
IF NOT EXIST bin\openvr_api.dll copy examples\ThirdPartyLibs\openvr\bin\win32\openvr_api.dll bin
cd build3
premake4 --double --enable_openvr --enable_pybullet --python_include_dir="C:/Python-3.5.2/include" --python_lib_dir="C:/Python-3.5.2/libs" --targetdir="../bin" vs2010
start vs2010

View File

@@ -174,7 +174,7 @@
<child link="lbr_iiwa_link_4"/>
<origin rpy="1.57079632679 0 0" xyz="0 0 0.2155"/>
<axis xyz="0 0 1"/>
<limit effort="300" lower=".29439510239" upper="2.09439510239" velocity="10"/>
<limit effort="300" lower="-2.09439510239" upper="2.09439510239" velocity="10"/>
<dynamics damping="0.5"/>
</joint>
<link name="lbr_iiwa_link_4">

View File

@@ -33,6 +33,10 @@ GLInstanceGraphicsShape* btgCreateGraphicsShapeFromWavefrontObj(std::vector<tiny
int vtxBaseIndex = vertices->size();
if (f<0 && f>=shape.mesh.indices.size())
{
continue;
}
GLInstanceVertex vtx0;
vtx0.xyzw[0] = shape.mesh.positions[shape.mesh.indices[f]*3+0];
@@ -40,10 +44,22 @@ GLInstanceGraphicsShape* btgCreateGraphicsShapeFromWavefrontObj(std::vector<tiny
vtx0.xyzw[2] = shape.mesh.positions[shape.mesh.indices[f]*3+2];
vtx0.xyzw[3] = 0.f;
if (shape.mesh.texcoords.size())
if (shape.mesh.texcoords.size() )
{
vtx0.uv[0] = shape.mesh.texcoords[shape.mesh.indices[f]*2+0];
vtx0.uv[1] = shape.mesh.texcoords[shape.mesh.indices[f]*2+1];
int uv0Index = shape.mesh.indices[f]*2+0;
int uv1Index = shape.mesh.indices[f]*2+1;
if (uv0Index>=0 && uv1Index>=0 && (uv0Index < shape.mesh.texcoords.size()) && (uv1Index < shape.mesh.texcoords.size()))
{
vtx0.uv[0] = shape.mesh.texcoords[uv0Index];
vtx0.uv[1] = shape.mesh.texcoords[uv1Index];
} else
{
b3Warning("obj texture coordinate out-of-range!");
vtx0.uv[0] = 0;
vtx0.uv[1] = 0;
}
} else
{
vtx0.uv[0] = 0.5;
@@ -58,8 +74,18 @@ GLInstanceGraphicsShape* btgCreateGraphicsShapeFromWavefrontObj(std::vector<tiny
if (shape.mesh.texcoords.size())
{
vtx1.uv[0] = shape.mesh.texcoords[shape.mesh.indices[f+1]*2+0];
vtx1.uv[1] = shape.mesh.texcoords[shape.mesh.indices[f+1]*2+1];
int uv0Index = shape.mesh.indices[f+1]*2+0;
int uv1Index = shape.mesh.indices[f+1]*2+1;
if (uv0Index>=0 && uv1Index>=0 && (uv0Index < shape.mesh.texcoords.size()) && (uv1Index < shape.mesh.texcoords.size()))
{
vtx1.uv[0] = shape.mesh.texcoords[uv0Index];
vtx1.uv[1] = shape.mesh.texcoords[uv1Index];
} else
{
b3Warning("obj texture coordinate out-of-range!");
vtx1.uv[0] = 0;
vtx1.uv[1] = 0;
}
} else
{
vtx1.uv[0] = 0.5f;
@@ -73,8 +99,18 @@ GLInstanceGraphicsShape* btgCreateGraphicsShapeFromWavefrontObj(std::vector<tiny
vtx2.xyzw[3] = 0.f;
if (shape.mesh.texcoords.size())
{
vtx2.uv[0] = shape.mesh.texcoords[shape.mesh.indices[f+2]*2+0];
vtx2.uv[1] = shape.mesh.texcoords[shape.mesh.indices[f+2]*2+1];
int uv0Index = shape.mesh.indices[f+2]*2+0;
int uv1Index = shape.mesh.indices[f+2]*2+1;
if (uv0Index>=0 && uv1Index>=0 && (uv0Index < shape.mesh.texcoords.size()) && (uv1Index < shape.mesh.texcoords.size()))
{
vtx2.uv[0] = shape.mesh.texcoords[uv0Index];
vtx2.uv[1] = shape.mesh.texcoords[uv1Index];
} else
{
b3Warning("obj texture coordinate out-of-range!");
vtx2.uv[0] = 0;
vtx2.uv[1] = 0;
}
} else
{
vtx2.uv[0] = 0.5;

View File

@@ -145,6 +145,15 @@ int b3PhysicsParamSetRealTimeSimulation(b3SharedMemoryCommandHandle commandH
return 0;
}
int b3PhysicsParamSetNumSolverIterations(b3SharedMemoryCommandHandle commandHandle, int numSolverIterations)
{
struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle;
b3Assert(command->m_type == CMD_SEND_PHYSICS_SIMULATION_PARAMETERS);
command->m_physSimParamArgs.m_numSolverIterations = numSolverIterations;
command->m_updateFlags |= SIM_PARAM_UPDATE_NUM_SOLVER_ITERATIONS;
return 0;
}
int b3PhysicsParamSetTimeStep(b3SharedMemoryCommandHandle commandHandle, double timeStep)
{
struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle;

View File

@@ -101,6 +101,9 @@ int b3PhysicsParamSetTimeStep(b3SharedMemoryCommandHandle commandHandle, double
int b3PhysicsParamSetDefaultContactERP(b3SharedMemoryCommandHandle commandHandle, double defaultContactERP);
int b3PhysicsParamSetNumSubSteps(b3SharedMemoryCommandHandle commandHandle, int numSubSteps);
int b3PhysicsParamSetRealTimeSimulation(b3SharedMemoryCommandHandle commandHandle, int enableRealTimeSimulation);
int b3PhysicsParamSetNumSolverIterations(b3SharedMemoryCommandHandle commandHandle, int numSolverIterations);
b3SharedMemoryCommandHandle b3InitStepSimulationCommand(b3PhysicsClientHandle physClient);

View File

@@ -27,7 +27,9 @@
#include "../CommonInterfaces/CommonGUIHelperInterface.h"
#include "SharedMemoryCommands.h"
//@todo(erwincoumans) those globals are hacks for a VR demo, move this to Python/pybullet!
btVector3 gLastPickPos(0, 0, 0);
bool gCloseToKuka=false;
bool gEnableRealTimeSimVR=false;
int gCreateObjectSimVR = -1;
btScalar simTimeScalingFactor = 1;
@@ -1488,7 +1490,7 @@ bool PhysicsServerCommandProcessor::processCommand(const struct SharedMemoryComm
break;
}
case CMD_SEND_DESIRED_STATE:
case CMD_SEND_DESIRED_STATE:
{
if (m_data->m_verboseOutput)
{
@@ -1668,18 +1670,18 @@ bool PhysicsServerCommandProcessor::processCommand(const struct SharedMemoryComm
break;
}
default:
{
b3Warning("m_controlMode not implemented yet");
break;
}
{
b3Warning("m_controlMode not implemented yet");
break;
}
}
}
}
}
serverStatusOut.m_type = CMD_DESIRED_STATE_RECEIVED_COMPLETED;
hasStatus = true;
break;
}
serverStatusOut.m_type = CMD_DESIRED_STATE_RECEIVED_COMPLETED;
hasStatus = true;
break;
}
case CMD_REQUEST_ACTUAL_STATE:
{
if (m_data->m_verboseOutput)
@@ -1942,6 +1944,10 @@ bool PhysicsServerCommandProcessor::processCommand(const struct SharedMemoryComm
}
}
if (clientCmd.m_updateFlags&SIM_PARAM_UPDATE_NUM_SOLVER_ITERATIONS)
{
m_data->m_dynamicsWorld->getSolverInfo().m_numIterations = clientCmd.m_physSimParamArgs.m_numSolverIterations;
}
if (clientCmd.m_updateFlags&SIM_PARAM_UPDATE_NUM_SIMULATION_SUB_STEPS)
{
m_data->m_numSimulationSubSteps = clientCmd.m_physSimParamArgs.m_numSimulationSubSteps;
@@ -2931,8 +2937,9 @@ btVector3 gVRGripperPos(0,0,0.2);
btQuaternion gVRGripperOrn(0,0,0,1);
btVector3 gVRController2Pos(0,0,0.2);
btQuaternion gVRController2Orn(0,0,0,1);
btScalar gVRGripper2Analog = 0;
btScalar gVRGripperAnalog = 0;
bool gVRGripperClosed = false;
@@ -3148,7 +3155,7 @@ void PhysicsServerCommandProcessor::stepSimulationRealTime(double dtInSec)
btMultiBodyJointMotor* motor = (btMultiBodyJointMotor*)childBody->m_multiBody->getLink(1).m_userPtr;
if (motor)
{
btScalar posTarget = (-0.048)*btMin(btScalar(0.75), gVRGripperAnalog) / 0.75;
btScalar posTarget = (-0.048)*btMin(btScalar(0.75), gVRGripper2Analog) / 0.75;
motor->setPositionTarget(posTarget, .2);
motor->setVelocityTarget(0.0, .5);
motor->setMaxAppliedImpulse(5.0);
@@ -3198,7 +3205,7 @@ void PhysicsServerCommandProcessor::stepSimulationRealTime(double dtInSec)
btMultiBody* mb = bodyHandle->m_multiBody;
btScalar sqLen = (mb->getBaseWorldTransform().getOrigin() - gVRController2Pos).length2();
btScalar distanceThreshold = 1.3;
bool closeToKuka=(sqLen<(distanceThreshold*distanceThreshold));
gCloseToKuka=(sqLen<(distanceThreshold*distanceThreshold));
int numDofs = bodyHandle->m_multiBody->getNumDofs();
btAlignedObjectArray<double> q_new;
@@ -3219,7 +3226,7 @@ void PhysicsServerCommandProcessor::stepSimulationRealTime(double dtInSec)
q_new[5] = -SIMD_HALF_PI*0.66;
q_new[6] = 0;
if (closeToKuka)
if (gCloseToKuka)
{
double dampIk[6] = {1.0, 1.0, 1.0, 1.0, 1.0, 0.0};
@@ -3390,7 +3397,7 @@ void PhysicsServerCommandProcessor::stepSimulationRealTime(double dtInSec)
{
btScalar desiredVelocity = 0.f;
btScalar desiredPosition = q_new[link];
motor->setRhsClamp(gRhsClamp);
//motor->setRhsClamp(gRhsClamp);
//printf("link %d: %f", link, q_new[link]);
motor->setVelocityTarget(desiredVelocity,1.0);
motor->setPositionTarget(desiredPosition,0.6);

View File

@@ -16,6 +16,7 @@
#define MAX_VR_CONTROLLERS 8
//@todo(erwincoumans) those globals are hacks for a VR demo, move this to Python/pybullet!
extern btVector3 gLastPickPos;
btVector3 gVRTeleportPos(0,0,0);
btQuaternion gVRTeleportOrn(0, 0, 0,1);
@@ -24,6 +25,8 @@ extern btQuaternion gVRGripperOrn;
extern btVector3 gVRController2Pos;
extern btQuaternion gVRController2Orn;
extern btScalar gVRGripperAnalog;
extern btScalar gVRGripper2Analog;
extern bool gCloseToKuka;
extern bool gEnableRealTimeSimVR;
extern int gCreateObjectSimVR;
static int gGraspingController = -1;
@@ -191,12 +194,15 @@ void MotionThreadFunc(void* userPtr,void* lsMemory)
args->m_physicsServerPtr->removePickingConstraint();
}
if (args->m_isVrControllerPicking[c])
if (!gCloseToKuka)
{
args->m_isVrControllerPicking[c] = false;
args->m_isVrControllerDragging[c] = true;
args->m_physicsServerPtr->pickBody(from,-toZ);
//printf("PICK!\n");
if (args->m_isVrControllerPicking[c])
{
args->m_isVrControllerPicking[c] = false;
args->m_isVrControllerDragging[c] = true;
args->m_physicsServerPtr->pickBody(from,-toZ);
//printf("PICK!\n");
}
}
if (args->m_isVrControllerDragging[c])
@@ -1254,6 +1260,7 @@ void PhysicsServerExample::vrControllerMoveCallback(int controllerId, float pos[
}
else
{
gVRGripper2Analog = analogAxis;
gVRController2Pos.setValue(pos[0] + gVRTeleportPos[0], pos[1] + gVRTeleportPos[1], pos[2] + gVRTeleportPos[2]);
btQuaternion orgOrn(orn[0], orn[1], orn[2], orn[3]);
gVRController2Orn = orgOrn*btQuaternion(btVector3(0, 0, 1), SIMD_HALF_PI)*btQuaternion(btVector3(0, 1, 0), SIMD_HALF_PI);