summaryrefslogtreecommitdiff
diff options
context:
space:
mode:
authorErwin Coumans <erwin.coumans@gmail.com>2017-04-29 10:32:30 -0700
committerErwin Coumans <erwin.coumans@gmail.com>2017-04-29 10:32:30 -0700
commit2a2c18e959d293ce2367947e6027121683d281b8 (patch)
tree3cdc19fe3ccd561cf6896c3ddd6df52ee8ab4b40
parentc95a1c9c339b92c3201271e5d04242608e50d329 (diff)
downloadbullet3-2a2c18e959d293ce2367947e6027121683d281b8.tar.gz
add more tinyaudio preparation, some test wav files, play sound on collision events. Will expose this in the C-API to pick wav files and collision threshold levels etc. Use the premake --audio flag to try it out. The TinyAudio example in the ExampleBrowser works on Mac, Linux and Windows, you can play notes by pressing keys.
-rw-r--r--build_visual_studio_vr_pybullet_double.bat2
-rw-r--r--data/wav/cardboardbox0.wavbin0 -> 36836 bytes
-rw-r--r--data/wav/cardboardbox1.wavbin0 -> 41876 bytes
-rw-r--r--data/wav/cardboardbox2.wavbin0 -> 38852 bytes
-rw-r--r--examples/RobotSimulator/RobotSimulatorMain.cpp18
-rw-r--r--examples/RobotSimulator/premake4.lua29
-rw-r--r--examples/SharedMemory/PhysicsServerCommandProcessor.cpp120
-rw-r--r--examples/SharedMemory/PhysicsServerCommandProcessor.h1
-rw-r--r--examples/SharedMemory/premake4.lua31
-rw-r--r--examples/TinyAudio/b3ADSR.cpp4
10 files changed, 196 insertions, 9 deletions
diff --git a/build_visual_studio_vr_pybullet_double.bat b/build_visual_studio_vr_pybullet_double.bat
index 3fadb9253..db2765f42 100644
--- a/build_visual_studio_vr_pybullet_double.bat
+++ b/build_visual_studio_vr_pybullet_double.bat
@@ -17,6 +17,6 @@ del tmp1234.txt
cd build3
-premake4 --double --midi --enable_openvr --enable_pybullet --python_include_dir="%myvar%/include" --python_lib_dir="%myvar%/libs" --targetdir="../bin" vs2010
+premake4 --audio --double --midi --enable_openvr --enable_pybullet --python_include_dir="%myvar%/include" --python_lib_dir="%myvar%/libs" --targetdir="../bin" vs2010
start vs2010
diff --git a/data/wav/cardboardbox0.wav b/data/wav/cardboardbox0.wav
new file mode 100644
index 000000000..fe63ce886
--- /dev/null
+++ b/data/wav/cardboardbox0.wav
Binary files differ
diff --git a/data/wav/cardboardbox1.wav b/data/wav/cardboardbox1.wav
new file mode 100644
index 000000000..7806f4620
--- /dev/null
+++ b/data/wav/cardboardbox1.wav
Binary files differ
diff --git a/data/wav/cardboardbox2.wav b/data/wav/cardboardbox2.wav
new file mode 100644
index 000000000..328b98f3d
--- /dev/null
+++ b/data/wav/cardboardbox2.wav
Binary files differ
diff --git a/examples/RobotSimulator/RobotSimulatorMain.cpp b/examples/RobotSimulator/RobotSimulatorMain.cpp
index 558c5e9de..3fafac9e8 100644
--- a/examples/RobotSimulator/RobotSimulatorMain.cpp
+++ b/examples/RobotSimulator/RobotSimulatorMain.cpp
@@ -35,12 +35,16 @@ int main(int argc, char* argv[])
sim->loadURDF("plane.urdf");
- MinitaurSetup minitaur;
- int minitaurUid = minitaur.setupMinitaur(sim, b3MakeVector3(0,0,.3));
+ b3RobotSimulatorLoadUrdfFileArgs args;
+ args.m_startPosition.setValue(0,0,2);
+ for (int i=0;i<10;i++)
+ {
+ args.m_startPosition[0] = 0.5*i;
+ args.m_startPosition[1] = 0.5*i;
+ args.m_startPosition[2] = 2+i*2;
+ int r2d2 = sim->loadURDF("cube.urdf",args);
+ }
-
- //b3RobotSimulatorLoadUrdfFileArgs args;
- //args.m_startPosition.setValue(2,0,1);
//int r2d2 = sim->loadURDF("r2d2.urdf",args);
//b3RobotSimulatorLoadFileResults sdfResults;
@@ -123,8 +127,8 @@ int main(int argc, char* argv[])
yaw+=0.1;
b3Vector3 basePos;
b3Quaternion baseOrn;
- sim->getBasePositionAndOrientation(minitaurUid,basePos,baseOrn);
- sim->resetDebugVisualizerCamera(distance,yaw,20,basePos);
+// sim->getBasePositionAndOrientation(minitaurUid,basePos,baseOrn);
+ // sim->resetDebugVisualizerCamera(distance,yaw,20,basePos);
}
b3Clock::usleep(1000.*1000.*fixedTimeStep);
}
diff --git a/examples/RobotSimulator/premake4.lua b/examples/RobotSimulator/premake4.lua
index 7eb0e1b55..0d73ffd05 100644
--- a/examples/RobotSimulator/premake4.lua
+++ b/examples/RobotSimulator/premake4.lua
@@ -87,6 +87,35 @@ if not _OPTIONS["no-enet"] then
defines {"BT_ENABLE_CLSOCKET"}
end
+ if _OPTIONS["audio"] then
+ files {
+ "../TinyAudio/b3ADSR.cpp",
+ "../TinyAudio/b3AudioListener.cpp",
+ "../TinyAudio/b3ReadWavFile.cpp",
+ "../TinyAudio/b3SoundEngine.cpp",
+ "../TinyAudio/b3SoundSource.cpp",
+ "../TinyAudio/b3WriteWavFile.cpp",
+ "../TinyAudio/RtAudio.cpp",
+ }
+ defines {"B3_ENABLE_TINY_AUDIO"}
+
+ if os.is("Windows") then
+ links {"winmm","Wsock32","dsound"}
+ defines {"WIN32","__WINDOWS_MM__","__WINDOWS_DS__"}
+ end
+
+ if os.is("Linux") then initX11()
+ defines {"__OS_LINUX__","__LINUX_ALSA__"}
+ links {"asound","pthread"}
+ end
+
+
+ if os.is("MacOSX") then
+ links{"Cocoa.framework"}
+ links{"CoreAudio.framework", "coreMIDI.framework", "Cocoa.framework"}
+ defines {"__OS_MACOSX__","__MACOSX_CORE__"}
+ end
+ end
files {
"RobotSimulatorMain.cpp",
"b3RobotSimulatorClientAPI.cpp",
diff --git a/examples/SharedMemory/PhysicsServerCommandProcessor.cpp b/examples/SharedMemory/PhysicsServerCommandProcessor.cpp
index 625c99d33..2d58ccb1e 100644
--- a/examples/SharedMemory/PhysicsServerCommandProcessor.cpp
+++ b/examples/SharedMemory/PhysicsServerCommandProcessor.cpp
@@ -26,6 +26,10 @@
#include "Bullet3Common/b3Logging.h"
#include "../CommonInterfaces/CommonGUIHelperInterface.h"
#include "SharedMemoryCommands.h"
+#include "LinearMath/btRandom.h"
+#ifdef B3_ENABLE_TINY_AUDIO
+#include "../TinyAudio/b3SoundEngine.h"
+#endif
#ifdef USE_SOFT_BODY_MULTI_BODY_DYNAMICS_WORLD
#include "BulletSoftBody/btSoftBodyRigidBodyCollisionConfiguration.h"
@@ -1297,6 +1301,10 @@ struct PhysicsServerCommandProcessorInternalData
btScalar m_oldPickingDist;
bool m_prevCanSleep;
TinyRendererVisualShapeConverter m_visualConverter;
+#ifdef B3_ENABLE_TINY_AUDIO
+ b3SoundEngine m_soundEngine;
+ int m_wavIds[3];
+#endif
PhysicsServerCommandProcessorInternalData()
:
@@ -1456,11 +1464,101 @@ PhysicsServerCommandProcessor::~PhysicsServerCommandProcessor()
void logCallback(btDynamicsWorld *world, btScalar timeStep)
{
+ //handle the logging and playing sounds
PhysicsServerCommandProcessor* proc = (PhysicsServerCommandProcessor*) world->getWorldUserInfo();
+ proc->processCollisionForces(timeStep);
+
proc->logObjectStates(timeStep);
}
+bool MyContactAddedCallback(btManifoldPoint& cp, const btCollisionObjectWrapper* colObj0Wrap,int partId0,int index0,const btCollisionObjectWrapper* colObj1Wrap,int partId1,int index1)
+{
+ return true;
+}
+
+
+
+
+bool MyContactDestroyedCallback(void* userPersistentData)
+{
+ //printf("destroyed\n");
+ return false;
+}
+
+bool MyContactProcessedCallback(btManifoldPoint& cp,void* body0,void* body1)
+{
+ //printf("processed\n");
+ return false;
+
+}
+void MyContactStartedCallback(btPersistentManifold* const &manifold)
+{
+ //printf("started\n");
+}
+void MyContactEndedCallback(btPersistentManifold* const &manifold)
+{
+// printf("ended\n");
+}
+
+
+
+void PhysicsServerCommandProcessor::processCollisionForces(btScalar timeStep)
+{
+#ifdef B3_ENABLE_TINY_AUDIO
+ //this is experimental at the moment: impulse thresholds, sound parameters will be exposed in C-API/pybullet.
+ //audio will go into a wav file, as well as real-time output to speakers/headphones using RtAudio/DAC.
+
+ int numContactManifolds = m_data->m_dynamicsWorld->getDispatcher()->getNumManifolds();
+ for (int i = 0; i < numContactManifolds; i++)
+ {
+ const btPersistentManifold* manifold = m_data->m_dynamicsWorld->getDispatcher()->getInternalManifoldPointer()[i];
+ for (int p=0;p<manifold->getNumContacts();p++)
+ {
+ double imp = manifold->getContactPoint(p).getAppliedImpulse();
+ //printf ("manifold %d, contact %d, lifeTime:%d, appliedImpulse:%f\n",i,p, manifold->getContactPoint(p).getLifeTime(),imp);
+
+ if (imp>0.4 && manifold->getContactPoint(p).getLifeTime()==1)
+ {
+ int soundSourceIndex = m_data->m_soundEngine.getAvailableSoundSource();
+ if (soundSourceIndex>=0)
+ {
+ b3SoundMessage msg;
+ msg.m_releaseRate = 0.0001;
+ msg.m_attackRate = 1.;
+ msg.m_type = B3_SOUND_SOURCE_WAV_FILE;
+
+ int cardboardIndex = float(rand())/float(RAND_MAX)*2.9;
+
+ msg.m_wavId = m_data->m_wavIds[cardboardIndex];
+
+ float rnd = rand()% 2;
+
+ msg.m_frequency = 100+rnd*10.;
+
+ m_data->m_soundEngine.startSound(soundSourceIndex,msg);
+ m_data->m_soundEngine.releaseSound(soundSourceIndex);
+
+ }
+ }
+ }
+ int linkIndexA = -1;
+ int linkIndexB = -1;
+
+ int objectIndexB = -1;
+
+ const btRigidBody* bodyB = btRigidBody::upcast(manifold->getBody1());
+ if (bodyB)
+ {
+ objectIndexB = bodyB->getUserIndex2();
+ }
+ const btMultiBodyLinkCollider* mblB = btMultiBodyLinkCollider::upcast(manifold->getBody1());
+ if (mblB && mblB->m_multiBody)
+ {
+ }
+ }
+#endif//B3_ENABLE_TINY_AUDIO
+}
void PhysicsServerCommandProcessor::logObjectStates(btScalar timeStep)
{
@@ -1522,6 +1620,20 @@ void PhysicsServerCommandProcessor::createEmptyDynamicsWorld()
m_data->m_guiHelper->createPhysicsDebugDrawer(m_data->m_dynamicsWorld);
}
m_data->m_dynamicsWorld->setInternalTickCallback(logCallback,this);
+
+#ifdef B3_ENABLE_TINY_AUDIO
+ m_data->m_soundEngine.init(16,true);
+ m_data->m_wavIds[0] = m_data->m_soundEngine.loadWavFile("wav/cardboardbox0.wav");
+ m_data->m_wavIds[1] = m_data->m_soundEngine.loadWavFile("wav/cardboardbox1.wav");
+ m_data->m_wavIds[2] = m_data->m_soundEngine.loadWavFile("wav/cardboardbox2.wav");
+
+//we don't use those callbacks (yet), experimental
+// gContactAddedCallback = MyContactAddedCallback;
+// gContactDestroyedCallback = MyContactDestroyedCallback;
+// gContactProcessedCallback = MyContactProcessedCallback;
+// gContactStartedCallback = MyContactStartedCallback;
+// gContactEndedCallback = MyContactEndedCallback;
+#endif
}
void PhysicsServerCommandProcessor::deleteStateLoggers()
@@ -1565,6 +1677,14 @@ void PhysicsServerCommandProcessor::deleteCachedInverseDynamicsBodies()
void PhysicsServerCommandProcessor::deleteDynamicsWorld()
{
+#ifdef B3_ENABLE_TINY_AUDIO
+ m_data->m_soundEngine.exit();
+ //gContactDestroyedCallback = 0;
+ //gContactProcessedCallback = 0;
+ //gContactStartedCallback = 0;
+ //gContactEndedCallback = 0;
+#endif
+
deleteCachedInverseDynamicsBodies();
deleteCachedInverseKinematicsBodies();
deleteStateLoggers();
diff --git a/examples/SharedMemory/PhysicsServerCommandProcessor.h b/examples/SharedMemory/PhysicsServerCommandProcessor.h
index 180db5c58..5dc0d0e64 100644
--- a/examples/SharedMemory/PhysicsServerCommandProcessor.h
+++ b/examples/SharedMemory/PhysicsServerCommandProcessor.h
@@ -95,6 +95,7 @@ public:
//logging of object states (position etc)
void logObjectStates(btScalar timeStep);
+ void processCollisionForces(btScalar timeStep);
void stepSimulationRealTime(double dtInSec, const struct b3VRControllerEvent* vrEvents, int numVREvents, const struct b3KeyboardEvent* keyEvents, int numKeyEvents);
void enableRealTimeSimulation(bool enableRealTimeSim);
diff --git a/examples/SharedMemory/premake4.lua b/examples/SharedMemory/premake4.lua
index e410dbf9c..20d97c36b 100644
--- a/examples/SharedMemory/premake4.lua
+++ b/examples/SharedMemory/premake4.lua
@@ -282,7 +282,36 @@ if os.is("Windows") then
end
end
-
+ if _OPTIONS["audio"] then
+ files {
+ "../TinyAudio/b3ADSR.cpp",
+ "../TinyAudio/b3AudioListener.cpp",
+ "../TinyAudio/b3ReadWavFile.cpp",
+ "../TinyAudio/b3SoundEngine.cpp",
+ "../TinyAudio/b3SoundSource.cpp",
+ "../TinyAudio/b3WriteWavFile.cpp",
+ "../TinyAudio/RtAudio.cpp",
+ }
+
+ defines {"B3_ENABLE_TINY_AUDIO"}
+
+ if os.is("Windows") then
+ links {"winmm","Wsock32","dsound"}
+ defines {"WIN32","__WINDOWS_MM__","__WINDOWS_DS__"}
+ end
+
+ if os.is("Linux") then initX11()
+ defines {"__OS_LINUX__","__LINUX_ALSA__"}
+ links {"asound","pthread"}
+ end
+
+
+ if os.is("MacOSX") then
+ links{"Cocoa.framework"}
+ links{"CoreAudio.framework", "coreMIDI.framework", "Cocoa.framework"}
+ defines {"__OS_MACOSX__","__MACOSX_CORE__"}
+ end
+ end
includedirs {
".","../../src", "../ThirdPartyLibs",
"../ThirdPartyLibs/openvr/headers",
diff --git a/examples/TinyAudio/b3ADSR.cpp b/examples/TinyAudio/b3ADSR.cpp
index c1d1c9600..2a526a4c8 100644
--- a/examples/TinyAudio/b3ADSR.cpp
+++ b/examples/TinyAudio/b3ADSR.cpp
@@ -85,6 +85,10 @@ void b3ADSR::keyOn()
{
if (m_target <= 0.0)
m_target = 1.0;
+ if (m_attackRate==1)
+ {
+ m_value = 1.0;
+ }
m_state = ADSR_ATTACK;
}