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:
Erwin Coumans
2017-05-01 11:14:09 -07:00
parent 3a330c4280
commit af6bf8ddc8
22 changed files with 389 additions and 108 deletions

View File

@@ -1134,9 +1134,9 @@ bool BulletURDFImporter::getLinkColor(int linkIndex, btVector4& colorRGBA) const
return false;
}
bool BulletURDFImporter::getLinkContactInfo(int linkIndex, URDFLinkContactInfo& contactInfo ) const
bool BulletURDFImporter::getLinkContactInfo(int urdflinkIndex, URDFLinkContactInfo& contactInfo ) const
{
UrdfLink* const* linkPtr = m_data->m_urdfParser.getModel().m_links.getAtIndex(linkIndex);
UrdfLink* const* linkPtr = m_data->m_urdfParser.getModel().m_links.getAtIndex(urdflinkIndex);
if (linkPtr)
{
const UrdfLink* link = *linkPtr;
@@ -1146,6 +1146,22 @@ bool BulletURDFImporter::getLinkContactInfo(int linkIndex, URDFLinkContactInfo&
return false;
}
bool BulletURDFImporter::getLinkAudioSource(int linkIndex, SDFAudioSource& audioSource) const
{
UrdfLink* const* linkPtr = m_data->m_urdfParser.getModel().m_links.getAtIndex(linkIndex);
if (linkPtr)
{
const UrdfLink* link = *linkPtr;
if (link->m_audioSource.m_flags & SDFAudioSource::SDFAudioSourceValid)
{
audioSource = link->m_audioSource;
return true;
}
}
return false;
}
void BulletURDFImporter::convertLinkVisualShapes2(int linkIndex, int urdfIndex, const char* pathPrefix, const btTransform& localInertiaFrame, class btCollisionObject* colObj, int bodyUniqueId) const
{
if (m_data->m_customVisualShapesConverter)

View File

@@ -41,8 +41,10 @@ public:
virtual bool getLinkColor(int linkIndex, btVector4& colorRGBA) const;
virtual bool getLinkContactInfo(int linkIndex, URDFLinkContactInfo& contactInfo ) const;
virtual bool getLinkContactInfo(int urdflinkIndex, URDFLinkContactInfo& contactInfo ) const;
virtual bool getLinkAudioSource(int linkIndex, SDFAudioSource& audioSource) const;
virtual std::string getJointName(int linkIndex) const;
virtual void getMassAndInertia(int linkIndex, btScalar& mass,btVector3& localInertiaDiagonal, btTransform& inertialFrame) const;

View File

@@ -4,6 +4,7 @@
#include "MultiBodyCreationInterface.h"
#include "LinearMath/btAlignedObjectArray.h"
#include "LinearMath/btHashMap.h"
struct GUIHelperInterface;
class btMultiBody;
@@ -28,7 +29,6 @@ protected:
struct GUIHelperInterface* m_guiHelper;
btAlignedObjectArray<btGeneric6DofSpring2Constraint*> m_6DofConstraints;
public:

View File

@@ -0,0 +1,46 @@
#ifndef SDF_AUDIO_TYPES_H
#define SDF_AUDIO_TYPES_H
#include <string>
///See audio_source element in http://sdformat.org/spec?ver=1.6&elem=link
struct SDFAudioSource
{
enum
{
SDFAudioSourceValid=1,
SDFAudioSourceLooping=2,
};
int m_flags; //repeat mode (0 = no repeat, 1 = loop forever)
std::string m_uri; //media filename of the sound, .wav file
double m_pitch; //1 = regular rate, -1 play in reverse
double m_gain; //normalized volume in range [0..1] where 0 is silent, 1 is most loud
double m_attackRate;
double m_decayRate;
double m_sustainLevel;
double m_releaseRate;
double m_collisionForceThreshold; //force that will trigger the audio, in Newton. If < 0, audio source is invalid
int m_userIndex;
SDFAudioSource()
: m_flags(0),
m_pitch(1),
m_gain(1),
m_attackRate(0.0001),
m_decayRate(0.00001),
m_sustainLevel(0.5),
m_releaseRate(0.0005),
m_collisionForceThreshold(0.5),
m_userIndex(-1)
{
}
};
#endif //SDF_AUDIO_TYPES_H

View File

@@ -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.

View File

@@ -663,6 +663,82 @@ bool UrdfParser::parseLink(UrdfModel& model, UrdfLink& link, TiXmlElement *confi
}
}
{
//optional 'audio_source' parameters
//modified version of SDF audio_source specification in //http://sdformat.org/spec?ver=1.6&elem=link
#if 0
<audio_source>
<uri>file://media/audio/cheer.mp3</uri>
<pitch>2.0</pitch>
<gain>1.0</gain>
<loop>false</loop>
<contact>
<collision>collision</collision>
</contact>
</audio_source>
#endif
TiXmlElement* ci = config->FirstChildElement("audio_source");
if (ci)
{
link.m_audioSource.m_flags |= SDFAudioSource::SDFAudioSourceValid;
const char* fn = ci->Attribute("filename");
if (fn)
{
link.m_audioSource.m_uri = fn;
} else
{
if (TiXmlElement* filename_xml = ci->FirstChildElement("uri"))
{
link.m_audioSource.m_uri = filename_xml->GetText();
}
}
if (TiXmlElement* pitch_xml = ci->FirstChildElement("pitch"))
{
link.m_audioSource.m_pitch = urdfLexicalCast<double>(pitch_xml->GetText());
}
if (TiXmlElement* gain_xml = ci->FirstChildElement("gain"))
{
link.m_audioSource.m_gain = urdfLexicalCast<double>(gain_xml->GetText());
}
if (TiXmlElement* attack_rate_xml = ci->FirstChildElement("attack_rate"))
{
link.m_audioSource.m_attackRate = urdfLexicalCast<double>(attack_rate_xml->GetText());
}
if (TiXmlElement* decay_rate_xml = ci->FirstChildElement("decay_rate"))
{
link.m_audioSource.m_decayRate = urdfLexicalCast<double>(decay_rate_xml->GetText());
}
if (TiXmlElement* sustain_level_xml = ci->FirstChildElement("sustain_level"))
{
link.m_audioSource.m_sustainLevel = urdfLexicalCast<double>(sustain_level_xml->GetText());
}
if (TiXmlElement* release_rate_xml = ci->FirstChildElement("release_rate"))
{
link.m_audioSource.m_releaseRate = urdfLexicalCast<double>(release_rate_xml->GetText());
}
if (TiXmlElement* loop_xml = ci->FirstChildElement("loop"))
{
std::string looptxt = loop_xml->GetText();
if (looptxt == "true")
{
link.m_audioSource.m_flags |= SDFAudioSource::SDFAudioSourceLooping;
}
}
if (TiXmlElement* forceThreshold_xml = ci->FirstChildElement("collision_force_threshold"))
{
link.m_audioSource.m_collisionForceThreshold= urdfLexicalCast<double>(forceThreshold_xml->GetText());
}
//todo: see other audio_source children
//pitch, gain, loop, contact
}
}
{
//optional 'contact' parameters
TiXmlElement* ci = config->FirstChildElement("contact");

View File

@@ -5,6 +5,7 @@
#include "LinearMath/btAlignedObjectArray.h"
#include "LinearMath/btHashMap.h"
#include "URDFJointTypes.h"
#include "SDFAudioTypes.h"
#define btArray btAlignedObjectArray
#include <string>
@@ -140,6 +141,8 @@ struct UrdfLink
URDFLinkContactInfo m_contactInfo;
SDFAudioSource m_audioSource;
UrdfLink()
:m_parentLink(0),
m_parentJoint(0)