plumb URDF/SDF audio_source into PhysicsServerCommandProcessor, allow to play sounds on collision !
See also https://youtu.be/eppOjTfx5Jg for a first test, and this modified URDF how to add sounds: https://github.com/bulletphysics/bullet3/blob/master/data/plane_with_collision_audio.urdf Add the --audio flag to enable sound in pybullet/Bullet-C-API
This commit is contained in:
@@ -5,7 +5,7 @@
|
||||
#include "LinearMath/btAlignedObjectArray.h"
|
||||
#include "LinearMath/btTransform.h"
|
||||
#include "URDFJointTypes.h"
|
||||
|
||||
#include "SDFAudioTypes.h"
|
||||
|
||||
class URDFImporterInterface
|
||||
{
|
||||
@@ -40,6 +40,8 @@ public:
|
||||
///this API will likely change, don't override it!
|
||||
virtual bool getLinkContactInfo(int linkIndex, URDFLinkContactInfo& contactInfo ) const { return false;}
|
||||
|
||||
virtual bool getLinkAudioSource(int linkIndex, SDFAudioSource& audioSource) const { return false;}
|
||||
|
||||
virtual std::string getJointName(int linkIndex) const = 0;
|
||||
|
||||
//fill mass and inertial data. If inertial data is missing, please initialize mass, inertia to sensitive values, and inertialFrame to identity.
|
||||
|
||||
Reference in New Issue
Block a user