Merge pull request #1086 from erwincoumans/master

TinyAudio, preparation to allow sound in our robot simulator (C-API, pybullet)
This commit is contained in:
erwincoumans
2017-05-02 06:10:12 +00:00
committed by GitHub
59 changed files with 7041 additions and 147 deletions

View File

@@ -158,6 +158,12 @@ end
description = "Double precision version of Bullet"
}
newoption
{
trigger = "serial",
description = "Enable serial, for testing the VR glove in C++"
}
newoption
{
trigger = "audio",
@@ -259,6 +265,10 @@ end
include "../examples/TinyAudio"
end
if _OPTIONS["serial"] then
include "../examples/ThirdPartyLibs/serial"
end
if not _OPTIONS["no-demos"] then
include "../examples/ExampleBrowser"
include "../examples/RobotSimulator"

View File

@@ -17,6 +17,9 @@ 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 --double --midi --enable_openvr --enable_pybullet --python_include_dir="%myvar%/include" --python_lib_dir="%myvar%/libs" --targetdir="../bin" vs2010
#premake4 --serial --audio --double --midi --enable_openvr --enable_pybullet --python_include_dir="%myvar%/include" --python_lib_dir="%myvar%/libs" --targetdir="../bin" vs2010
start vs2010

View File

@@ -0,0 +1,37 @@
<?xml version="0.0" ?>
<robot name="plane">
<link name="planeLink">
<audio_source filename="wav/cardboardbox0.wav">
<collision_force_threshold>0.4</collision_force_threshold>
<attack_rate>0.01</attack_rate>
<decay_rate>0.0001</decay_rate>
<sustain_level>0.5</sustain_level>
<release_rate>0.005</release_rate>
<gain>.5</gain>
</audio_source>
<contact>
<lateral_friction value="1"/>
</contact>
<inertial>
<origin rpy="0 0 0" xyz="0 0 0"/>
<mass value=".0"/>
<inertia ixx="0" ixy="0" ixz="0" iyy="0" iyz="0" izz="0"/>
</inertial>
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="plane.obj" scale="1 1 1"/>
</geometry>
<material name="white">
<color rgba="1 1 1 1"/>
</material>
</visual>
<collision>
<origin rpy="0 0 0" xyz="0 0 -5"/>
<geometry>
<box size="30 30 10"/>
</geometry>
</collision>
</link>
</robot>

BIN
data/wav/cardboardbox0.wav Normal file

Binary file not shown.

BIN
data/wav/cardboardbox1.wav Normal file

Binary file not shown.

BIN
data/wav/cardboardbox2.wav Normal file

Binary file not shown.

Binary file not shown.

Binary file not shown.

View File

@@ -52,6 +52,10 @@
#include "../RoboticsLearning/GripperGraspExample.h"
#include "../InverseKinematics/InverseKinematicsExample.h"
#ifdef B3_ENABLE_TINY_AUDIO
#include "../TinyAudio/TinyAudioExample.h"
#endif //B3_ENABLE_TINY_AUDIO
#ifdef ENABLE_LUA
#include "../LuaDemo/LuaPhysicsSetup.h"
#endif
@@ -100,7 +104,6 @@ struct ExampleEntry
static ExampleEntry gDefaultExamples[]=
{
ExampleEntry(0,"API"),
ExampleEntry(1,"Basic Example","Create some rigid bodies using box collision shapes. This is a good example to familiarize with the basic initialization of Bullet. The Basic Example can also be compiled without graphical user interface, as a console application. Press W for wireframe, A to show AABBs, I to suspend/restart physics simulation. Press D to toggle auto-deactivation of the simulation. ", BasicExampleCreateFunc),
@@ -307,7 +310,11 @@ static ExampleEntry gDefaultExamples[]=
ExampleEntry(1,"TinyRenderer", "Very small software renderer.", TinyRendererCreateFunc),
ExampleEntry(1,"Dynamic Texture", "Dynamic updated textured applied to a cube.", DynamicTexturedCubeDemoCreateFunc),
#ifdef B3_ENABLE_TINY_AUDIO
ExampleEntry(0,"Audio"),
ExampleEntry(1,"Simple Audio","Play some sound", TinyAudioExampleCreateFunc),
#endif
//Extended Tutorials Added by Mobeen
ExampleEntry(0,"Extended Tutorials"),

View File

@@ -48,7 +48,6 @@
//quick test for file import, @todo(erwincoumans) make it more general and add other file formats
#include "../Importers/ImportURDFDemo/ImportURDFSetup.h"
#include "../Importers/ImportBullet/SerializeSetup.h"
#include "Bullet3Common/b3HashMap.h"
struct GL3TexLoader : public MyTextureLoader

View File

@@ -35,6 +35,28 @@ project "App_BulletExampleBrowser"
}
end
if _OPTIONS["audio"] then
files {"../TinyAudio/*.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
if _OPTIONS["lua"] then
includedirs{"../ThirdPartyLibs/lua-5.2.3/src"}
links {"lua-5.2.3"}
@@ -184,6 +206,8 @@ project "BulletExampleBrowserLib"
files {"../LuaDemo/LuaPhysicsSetup.cpp"}
end
initOpenGL()
initGlew()

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)

View File

@@ -258,7 +258,7 @@ LRESULT CALLBACK WndProc(HWND hWnd, UINT message, WPARAM wParam, LPARAM lParam)
break;
};
}
if (keycode>=0 && sData && sData->m_keyboardCallback)// && ((HIWORD(lParam) & KF_REPEAT) == 0))
if (keycode>=0 && sData && sData->m_keyboardCallback && ((HIWORD(lParam) & KF_REPEAT) == 0))
{
int state = 1;
(*sData->m_keyboardCallback)(keycode,state);

View File

@@ -140,4 +140,3 @@ int main(int argc, char* argv[])
}

View File

@@ -0,0 +1,295 @@
//VR Glove hand simulator is a C++ conversion from the Python pybullet vrhand_vive_tracker.py
//For more details about the VR glove, see also https://docs.google.com/document/d/1_qwXJRBTGKmhktdBtVQ6zdOdxwud1K30jt0G5dkAr10/edit
#include "b3RobotSimulatorClientAPI.h"
#include "../Utils/b3Clock.h"
#include "Bullet3Common/b3CommandLineArgs.h"
#include <string.h>
#include <stdio.h>
#include <assert.h>
#include "serial/serial.h"
#include "../Importers/ImportURDFDemo/urdfStringSplit.h"
double convertSensor(int inputV, int minV, int maxV)
{
b3Clamp(inputV,minV,maxV);
double outVal =(double)inputV;
double b = (outVal-(double)minV)/float(maxV-minV);
return (b);
}
void setJointMotorPositionControl(b3RobotSimulatorClientAPI* sim, int obUid, int linkIndex, double targetPosition)
{
b3RobotSimulatorJointMotorArgs controlArgs(CONTROL_MODE_POSITION_VELOCITY_PD);
controlArgs.m_maxTorqueValue = 50.;
controlArgs.m_targetPosition = targetPosition;
controlArgs.m_targetVelocity = 0;
sim->setJointMotorControl(obUid,linkIndex,controlArgs);
}
int main(int argc, char* argv[])
{
b3CommandLineArgs args(argc,argv);
std::string port="COM10";
args.GetCmdLineArgument("port",port);
int baud = 115200;
args.GetCmdLineArgument("speed",baud);
std::string mode = "SHARED_MEMORY";
args.GetCmdLineArgument("mode",mode);
int disableGui = 0;
args.GetCmdLineArgument("disableGui",disableGui);
int disableShadows = 0;
args.GetCmdLineArgument("disableShadows",disableShadows);
printf("port=%s, speed=%d, connection mode=%s\n", port.c_str(), baud,mode.c_str());
// port, baudrate, timeout in milliseconds
serial::Serial my_serial(port, baud, serial::Timeout::simpleTimeout(1));
if (!my_serial.isOpen())
{
printf("Cannot open serial port\n");
return -1;
}
b3RobotSimulatorClientAPI* sim = new b3RobotSimulatorClientAPI();
//Can also use eCONNECT_UDP,eCONNECT_TCP, for example: sim->connect(eCONNECT_UDP, "localhost", 1234);
if (mode=="GUI")
{
sim->connect(eCONNECT_GUI);
} else
{
if (mode=="DIRECT")
{
sim->connect(eCONNECT_DIRECT);
} else
{
sim->connect(eCONNECT_SHARED_MEMORY);
}
}
sim->setRealTimeSimulation(true);
sim->setInternalSimFlags(0);
sim->resetSimulation();
if (disableGui)
{
sim->configureDebugVisualizer( COV_ENABLE_GUI, 0);
}
if (disableShadows)
{
sim->configureDebugVisualizer( COV_ENABLE_SHADOWS, 0);
}
sim->setTimeOut(12345);
//syncBodies is only needed when connecting to an existing physics server that has already some bodies
sim->syncBodies();
b3Scalar fixedTimeStep = 1./240.;
sim->setTimeStep(fixedTimeStep);
b3Quaternion q = sim->getQuaternionFromEuler(b3MakeVector3(0.1,0.2,0.3));
b3Vector3 rpy;
rpy = sim->getEulerFromQuaternion(q);
sim->setGravity(b3MakeVector3(0,0,-9.8));
sim->setContactBreakingThreshold(0.001);
sim->loadURDF("plane_with_collision_audio.urdf");
sim->loadURDF("jenga/jenga.urdf",b3RobotSimulatorLoadUrdfFileArgs(b3MakeVector3(1.300000,-0.700000,0.750000),b3Quaternion(0.000000,0.707107,0.000000,0.707107)));
sim->loadURDF("jenga/jenga.urdf",b3RobotSimulatorLoadUrdfFileArgs(b3MakeVector3(1.200000,-0.700000,0.750000),b3Quaternion(0.000000,0.707107,0.000000,0.707107)));
sim->loadURDF("jenga/jenga.urdf",b3RobotSimulatorLoadUrdfFileArgs(b3MakeVector3(1.100000,-0.700000,0.750000),b3Quaternion(0.000000,0.707107,0.000000,0.707107)));
sim->loadURDF("jenga/jenga.urdf",b3RobotSimulatorLoadUrdfFileArgs(b3MakeVector3(1.000000,-0.700000,0.750000),b3Quaternion(0.000000,0.707107,0.000000,0.707107)));
sim->loadURDF("jenga/jenga.urdf",b3RobotSimulatorLoadUrdfFileArgs(b3MakeVector3(0.900000,-0.700000,0.750000),b3Quaternion(0.000000,0.707107,0.000000,0.707107)));
sim->loadURDF("jenga/jenga.urdf",b3RobotSimulatorLoadUrdfFileArgs(b3MakeVector3(0.800000,-0.700000,0.750000),b3Quaternion(0.000000,0.707107,0.000000,0.707107)));
sim->loadURDF("jenga/jenga.urdf",b3RobotSimulatorLoadUrdfFileArgs(b3MakeVector3(0.700000,-0.700000,0.750000),b3Quaternion(0.000000,0.707107,0.000000,0.707107)));
sim->loadURDF("jenga/jenga.urdf",b3RobotSimulatorLoadUrdfFileArgs(b3MakeVector3(0.600000,-0.700000,0.750000),b3Quaternion(0.000000,0.707107,0.000000,0.707107)));
sim->loadURDF("table/table.urdf",b3RobotSimulatorLoadUrdfFileArgs(b3MakeVector3(1.000000,-0.200000,0.000000),b3Quaternion(0.000000,0.000000,0.707107,0.707107)));
sim->loadURDF("cube_small.urdf",b3RobotSimulatorLoadUrdfFileArgs(b3MakeVector3( 0.950000,-0.100000,0.700000),b3Quaternion(0.000000,0.000000,0.707107,0.707107)));
sim->loadURDF("sphere_small.urdf",b3RobotSimulatorLoadUrdfFileArgs(b3MakeVector3(0.850000,-0.400000,0.700000),b3Quaternion(0.000000,0.000000,0.707107,0.707107)));
int handUid = -1;
b3RobotSimulatorLoadFileResults mjcfResults;
const char* mjcfFileName = "MPL/mpl2.xml";
if (sim->loadMJCF(mjcfFileName,mjcfResults))
{
printf("mjcfResults = %d\n", mjcfResults.m_uniqueObjectIds.size());
if (mjcfResults.m_uniqueObjectIds.size()==1)
{
handUid = mjcfResults.m_uniqueObjectIds[0];
}
}
if (handUid<0)
{
printf("Cannot load MJCF file %s\n", mjcfFileName);
}
b3Quaternion handOrn = sim->getQuaternionFromEuler(b3MakeVector3(3.14,-3.14/2,0));
b3Vector3 handPos = b3MakeVector3(-0.05,0,0.02);
b3JointInfo jointInfo;
jointInfo.m_jointType = eFixedType;
b3Vector3 handStartPosWorld = b3MakeVector3(0.500000,0.300006,0.900000);
b3Quaternion handStartOrnWorld = b3Quaternion ::getIdentity();
jointInfo.m_childFrame[0] = handStartPosWorld[0];
jointInfo.m_childFrame[1] = handStartPosWorld[1];
jointInfo.m_childFrame[2] = handStartPosWorld[2];
jointInfo.m_childFrame[3] = handStartOrnWorld[0];
jointInfo.m_childFrame[4] = handStartOrnWorld[1];
jointInfo.m_childFrame[5] = handStartOrnWorld[2];
jointInfo.m_childFrame[6] = handStartOrnWorld[3];
jointInfo.m_parentFrame[0] = handPos[0];
jointInfo.m_parentFrame[1] = handPos[1];
jointInfo.m_parentFrame[2] = handPos[2];
jointInfo.m_parentFrame[3] = handOrn[0];
jointInfo.m_parentFrame[4] = handOrn[1];
jointInfo.m_parentFrame[5] = handOrn[2];
jointInfo.m_parentFrame[6] = handOrn[3];
int handConstraintId = sim->createConstraint(handUid,-1,-1,-1,&jointInfo);
double maxFingerForce = 50;
for (int j=0; j<sim->getNumJoints(handUid);j++)
{
b3RobotSimulatorJointMotorArgs controlArgs(CONTROL_MODE_POSITION_VELOCITY_PD);
controlArgs.m_maxTorqueValue = maxFingerForce ;
controlArgs.m_targetPosition = 0;
controlArgs.m_targetVelocity = 0;
sim->setJointMotorControl(handUid,j,controlArgs);
}
b3Clock clock;
double startTime = clock.getTimeInSeconds();
double simWallClockSeconds = 20.;
int vidLogId = -1;
int minitaurLogId = -1;
int rotateCamera = 0;
while (sim->canSubmitCommand())
{
b3VREventsData vrEvents;
int deviceTypeFilter = VR_DEVICE_GENERIC_TRACKER;
sim->getVREvents(&vrEvents, deviceTypeFilter);
//instead of iterating over all vr events, we just take the most up-to-date one
if (vrEvents.m_numControllerEvents)
{
int i = vrEvents.m_numControllerEvents - 1;
b3VRControllerEvent& e = vrEvents.m_controllerEvents[i];
// printf("e.pos=%f,%f,%f\n",e.m_pos[0],e.m_pos[1],e.m_pos[2]);
b3JointInfo changeConstraintInfo;
changeConstraintInfo.m_flags = 0;
changeConstraintInfo.m_jointMaxForce = 50;
changeConstraintInfo.m_flags |= eJointChangeMaxForce;
changeConstraintInfo.m_childFrame[0] = e.m_pos[0];
changeConstraintInfo.m_childFrame[1] = e.m_pos[1];
changeConstraintInfo.m_childFrame[2] = e.m_pos[2];
changeConstraintInfo.m_flags |= eJointChangeChildFramePosition;
changeConstraintInfo.m_childFrame[3] = e.m_orn[0];
changeConstraintInfo.m_childFrame[4] = e.m_orn[1];
changeConstraintInfo.m_childFrame[5] = e.m_orn[2];
changeConstraintInfo.m_childFrame[6] = e.m_orn[3];
changeConstraintInfo.m_flags |= eJointChangeChildFrameOrientation;
sim->changeConstraint(handConstraintId, &changeConstraintInfo);
}
//read the serial output from the hand, extract into parts
std::string result = my_serial.readline();
//my_serial.flush();
if (result.length())
{
int res = result.find("\n");
while (res<0)
{
result += my_serial.readline();
res = result.find("\n");
}
btAlignedObjectArray<std::string> pieces;
btAlignedObjectArray<std::string> separators;
separators.push_back(",");
urdfStringSplit( pieces, result, separators);
//printf("serial: %s\n", result.c_str());
if (pieces.size()==6)
{
double pinkTarget = 0;
double middleTarget = 0;
double indexTarget = 0;
double thumbTarget = 0;
{
int pink = atoi(pieces[1].c_str());
int middle = atoi(pieces[2].c_str());
int index = atoi(pieces[3].c_str());
int thumb = atoi(pieces[4].c_str());
pinkTarget = convertSensor(pink,250,400);
middleTarget = convertSensor(middle,250,400);
indexTarget = convertSensor(index,250,400);
thumbTarget = convertSensor(thumb,250,400);
}
//printf("pink = %d, middle=%d, index=%d, thumb=%d\n", pink,middle,index,thumb);
setJointMotorPositionControl(sim,handUid,5,1.3);
setJointMotorPositionControl(sim,handUid,7,thumbTarget);
setJointMotorPositionControl(sim,handUid,9,thumbTarget);
setJointMotorPositionControl(sim,handUid,11,thumbTarget);
setJointMotorPositionControl(sim,handUid,15,indexTarget);
setJointMotorPositionControl(sim,handUid,17,indexTarget);
setJointMotorPositionControl(sim,handUid,19,indexTarget);
setJointMotorPositionControl(sim,handUid,22,middleTarget);
setJointMotorPositionControl(sim,handUid,24,middleTarget);
setJointMotorPositionControl(sim,handUid,27,middleTarget);
double ringTarget = 0.5f*(pinkTarget+middleTarget);
setJointMotorPositionControl(sim,handUid,30,ringTarget);
setJointMotorPositionControl(sim,handUid,32,ringTarget);
setJointMotorPositionControl(sim,handUid,34,ringTarget);
setJointMotorPositionControl(sim,handUid,38,pinkTarget);
setJointMotorPositionControl(sim,handUid,40,pinkTarget);
setJointMotorPositionControl(sim,handUid,42,pinkTarget);
}
}
b3KeyboardEventsData keyEvents;
sim->getKeyboardEvents(&keyEvents);
//sim->stepSimulation();
if (rotateCamera)
{
static double yaw=0;
double distance = 1;
yaw+=0.1;
b3Vector3 basePos;
b3Quaternion baseOrn;
// sim->getBasePositionAndOrientation(minitaurUid,basePos,baseOrn);
// sim->resetDebugVisualizerCamera(distance,yaw,20,basePos);
}
//b3Clock::usleep(1000.*1000.*fixedTimeStep);
}
printf("serial.close()\n");
my_serial.close();
printf("sim->disconnect\n");
sim->disconnect();
printf("delete sim\n");
delete sim;
printf("exit\n");
}

View File

@@ -506,6 +506,22 @@ bool b3RobotSimulatorClientAPI::resetBaseVelocity(int bodyUniqueId, const b3Vect
return true;
}
void b3RobotSimulatorClientAPI::setInternalSimFlags(int flags)
{
if (!isConnected())
{
b3Warning("Not connected");
return;
}
{
b3SharedMemoryCommandHandle command = b3InitPhysicsParamCommand(m_data->m_physicsClientHandle);
b3SharedMemoryStatusHandle statusHandle;
b3PhysicsParamSetInternalSimFlags(command, flags);
statusHandle = b3SubmitClientCommandAndWaitStatus(m_data->m_physicsClientHandle, command);
}
}
void b3RobotSimulatorClientAPI::setRealTimeSimulation(bool enableRealTimeSimulation)
{
if (!isConnected())
@@ -544,21 +560,70 @@ bool b3RobotSimulatorClientAPI::getJointInfo(int bodyUniqueId, int jointIndex, b
return (b3GetJointInfo(m_data->m_physicsClientHandle, bodyUniqueId, jointIndex, jointInfo) != 0);
}
void b3RobotSimulatorClientAPI::createConstraint(int parentBodyIndex, int parentJointIndex, int childBodyIndex, int childJointIndex, b3JointInfo* jointInfo)
int b3RobotSimulatorClientAPI::createConstraint(int parentBodyIndex, int parentJointIndex, int childBodyIndex, int childJointIndex, b3JointInfo* jointInfo)
{
if (!isConnected())
{
b3Warning("Not connected");
return;
return -1;
}
b3SharedMemoryStatusHandle statusHandle;
b3Assert(b3CanSubmitCommand(m_data->m_physicsClientHandle));
if (b3CanSubmitCommand(m_data->m_physicsClientHandle))
{
statusHandle = b3SubmitClientCommandAndWaitStatus(m_data->m_physicsClientHandle, b3InitCreateUserConstraintCommand(m_data->m_physicsClientHandle, parentBodyIndex, parentJointIndex, childBodyIndex, childJointIndex, jointInfo));
int statusType = b3GetStatusType(statusHandle);
if (statusType == CMD_USER_CONSTRAINT_COMPLETED)
{
int userConstraintUid = b3GetStatusUserConstraintUniqueId(statusHandle);
return userConstraintUid;
}
}
return -1;
}
int b3RobotSimulatorClientAPI::changeConstraint(int constraintId, b3JointInfo* jointInfo)
{
if (!isConnected())
{
b3Warning("Not connected");
return -1;
}
b3SharedMemoryCommandHandle commandHandle = b3InitChangeUserConstraintCommand(m_data->m_physicsClientHandle, constraintId);
if (jointInfo->m_flags & eJointChangeMaxForce)
{
b3InitChangeUserConstraintSetMaxForce(commandHandle, jointInfo->m_jointMaxForce);
}
if (jointInfo->m_flags & eJointChangeChildFramePosition)
{
b3InitChangeUserConstraintSetPivotInB(commandHandle, &jointInfo->m_childFrame[0]);
}
if (jointInfo->m_flags & eJointChangeChildFrameOrientation)
{
b3InitChangeUserConstraintSetFrameInB(commandHandle, &jointInfo->m_childFrame[3]);
}
b3SharedMemoryStatusHandle statusHandle = b3SubmitClientCommandAndWaitStatus(m_data->m_physicsClientHandle, commandHandle);
int statusType = b3GetStatusType(statusHandle);
return statusType;
}
void b3RobotSimulatorClientAPI::removeConstraint(int constraintId)
{
if (!isConnected())
{
b3Warning("Not connected");
return;
}
b3SharedMemoryCommandHandle commandHandle = b3InitRemoveUserConstraintCommand(m_data->m_physicsClientHandle, constraintId);
b3SharedMemoryStatusHandle statusHandle = b3SubmitClientCommandAndWaitStatus(m_data->m_physicsClientHandle, commandHandle);
int statusType = b3GetStatusType(statusHandle);
}
bool b3RobotSimulatorClientAPI::getJointState(int bodyUniqueId, int jointIndex, struct b3JointSensorState* state)
{
if (!isConnected())
@@ -669,6 +734,21 @@ void b3RobotSimulatorClientAPI::setNumSolverIterations(int numIterations)
b3Assert(b3GetStatusType(statusHandle) == CMD_CLIENT_COMMAND_COMPLETED);
}
void b3RobotSimulatorClientAPI::setContactBreakingThreshold(double threshold)
{
if (!isConnected())
{
b3Warning("Not connected");
return;
}
b3SharedMemoryCommandHandle command = b3InitPhysicsParamCommand(m_data->m_physicsClientHandle);
b3SharedMemoryStatusHandle statusHandle;
b3PhysicsParamSetContactBreakingThreshold(command,threshold);
statusHandle = b3SubmitClientCommandAndWaitStatus(m_data->m_physicsClientHandle, command);
b3Assert(b3GetStatusType(statusHandle) == CMD_CLIENT_COMMAND_COMPLETED);
}
void b3RobotSimulatorClientAPI::setTimeStep(double timeStepInSeconds)
{
if (!isConnected())
@@ -799,7 +879,7 @@ void b3RobotSimulatorClientAPI::configureDebugVisualizer(b3ConfigureDebugVisuali
b3SubmitClientCommandAndWaitStatus(m_data->m_physicsClientHandle, commandHandle);
}
void b3RobotSimulatorClientAPI::getVREvents(b3VREventsData* vrEventsData)
void b3RobotSimulatorClientAPI::getVREvents(b3VREventsData* vrEventsData,int deviceTypeFilter)
{
vrEventsData->m_numControllerEvents = 0;
vrEventsData->m_controllerEvents = 0;
@@ -810,6 +890,7 @@ void b3RobotSimulatorClientAPI::getVREvents(b3VREventsData* vrEventsData)
}
b3SharedMemoryCommandHandle commandHandle = b3RequestVREventsCommandInit(m_data->m_physicsClientHandle);
b3VREventsSetDeviceTypeFilter(commandHandle, deviceTypeFilter);
b3SubmitClientCommandAndWaitStatus(m_data->m_physicsClientHandle, commandHandle);
b3GetVREventsData(m_data->m_physicsClientHandle, vrEventsData);
}

View File

@@ -17,6 +17,15 @@ struct b3RobotSimulatorLoadUrdfFileArgs
bool m_useMultiBody;
int m_flags;
b3RobotSimulatorLoadUrdfFileArgs(const b3Vector3& startPos, const b3Quaternion& startOrn)
: m_startPosition(startPos),
m_startOrientation(startOrn),
m_forceOverrideFixedBase(false),
m_useMultiBody(true),
m_flags(0)
{
}
b3RobotSimulatorLoadUrdfFileArgs()
: m_startPosition(b3MakeVector3(0, 0, 0)),
m_startOrientation(b3Quaternion(0, 0, 0, 1)),
@@ -123,6 +132,8 @@ class b3RobotSimulatorClientAPI
struct b3RobotSimulatorClientAPI_InternalData* m_data;
public:
b3RobotSimulatorClientAPI();
virtual ~b3RobotSimulatorClientAPI();
@@ -158,7 +169,11 @@ public:
bool getJointInfo(int bodyUniqueId, int jointIndex, b3JointInfo* jointInfo);
void createConstraint(int parentBodyIndex, int parentJointIndex, int childBodyIndex, int childJointIndex, b3JointInfo* jointInfo);
int createConstraint(int parentBodyIndex, int parentJointIndex, int childBodyIndex, int childJointIndex, b3JointInfo* jointInfo);
int changeConstraint(int constraintId, b3JointInfo* jointInfo);
void removeConstraint(int constraintId);
bool getJointState(int bodyUniqueId, int jointIndex, struct b3JointSensorState* state);
@@ -172,11 +187,14 @@ public:
void setRealTimeSimulation(bool enableRealTimeSimulation);
void setInternalSimFlags(int flags);
void setGravity(const b3Vector3& gravityAcceleration);
void setTimeStep(double timeStepInSeconds);
void setNumSimulationSubSteps(int numSubSteps);
void setNumSolverIterations(int numIterations);
void setContactBreakingThreshold(double threshold);
bool calculateInverseKinematics(const struct b3RobotSimulatorInverseKinematicArgs& args, struct b3RobotSimulatorInverseKinematicsResults& results);
@@ -190,7 +208,7 @@ public:
int startStateLogging(b3StateLoggingType loggingType, const std::string& fileName, const b3AlignedObjectArray<int>& objectUniqueIds=b3AlignedObjectArray<int>(), int maxLogDof = -1);
void stopStateLogging(int stateLoggerUniqueId);
void getVREvents(b3VREventsData* vrEventsData);
void getVREvents(b3VREventsData* vrEventsData, int deviceTypeFilter);
void getKeyboardEvents(b3KeyboardEventsData* keyboardEventsData);
};

View File

@@ -1,3 +1,67 @@
myfiles =
{
"../../examples/SharedMemory/IKTrajectoryHelper.cpp",
"../../examples/SharedMemory/IKTrajectoryHelper.h",
"../../examples/ExampleBrowser/InProcessExampleBrowser.cpp",
"../../examples/SharedMemory/InProcessMemory.cpp",
"../../examples/SharedMemory/PhysicsClient.cpp",
"../../examples/SharedMemory/PhysicsClient.h",
"../../examples/SharedMemory/PhysicsServer.cpp",
"../../examples/SharedMemory/PhysicsServer.h",
"../../examples/SharedMemory/PhysicsServerExample.cpp",
"../../examples/SharedMemory/SharedMemoryInProcessPhysicsC_API.cpp",
"../../examples/SharedMemory/PhysicsServerSharedMemory.cpp",
"../../examples/SharedMemory/PhysicsServerSharedMemory.h",
"../../examples/SharedMemory/PhysicsDirect.cpp",
"../../examples/SharedMemory/PhysicsDirect.h",
"../../examples/SharedMemory/PhysicsDirectC_API.cpp",
"../../examples/SharedMemory/PhysicsDirectC_API.h",
"../../examples/SharedMemory/PhysicsServerCommandProcessor.cpp",
"../../examples/SharedMemory/PhysicsServerCommandProcessor.h",
"../../examples/SharedMemory/PhysicsClientSharedMemory.cpp",
"../../examples/SharedMemory/PhysicsClientSharedMemory.h",
"../../examples/SharedMemory/PhysicsClientSharedMemory_C_API.cpp",
"../../examples/SharedMemory/PhysicsClientSharedMemory_C_API.h",
"../../examples/SharedMemory/PhysicsClientC_API.cpp",
"../../examples/SharedMemory/PhysicsClientC_API.h",
"../../examples/SharedMemory/Win32SharedMemory.cpp",
"../../examples/SharedMemory/Win32SharedMemory.h",
"../../examples/SharedMemory/PosixSharedMemory.cpp",
"../../examples/SharedMemory/PosixSharedMemory.h",
"../../examples/SharedMemory/TinyRendererVisualShapeConverter.cpp",
"../../examples/SharedMemory/TinyRendererVisualShapeConverter.h",
"../../examples/TinyRenderer/geometry.cpp",
"../../examples/TinyRenderer/model.cpp",
"../../examples/TinyRenderer/tgaimage.cpp",
"../../examples/TinyRenderer/our_gl.cpp",
"../../examples/TinyRenderer/TinyRenderer.cpp",
"../../examples/Utils/b3ResourcePath.cpp",
"../../examples/Utils/b3ResourcePath.h",
"../../examples/Utils/RobotLoggingUtil.cpp",
"../../examples/Utils/RobotLoggingUtil.h",
"../../examples/ThirdPartyLibs/tinyxml/tinystr.cpp",
"../../examples/ThirdPartyLibs/tinyxml/tinyxml.cpp",
"../../examples/ThirdPartyLibs/tinyxml/tinyxmlerror.cpp",
"../../examples/ThirdPartyLibs/tinyxml/tinyxmlparser.cpp",
"../../examples/ThirdPartyLibs/Wavefront/tiny_obj_loader.cpp",
"../../examples/ThirdPartyLibs/Wavefront/tiny_obj_loader.h",
"../../examples/Importers/ImportColladaDemo/LoadMeshFromCollada.cpp",
"../../examples/Importers/ImportObjDemo/LoadMeshFromObj.cpp",
"../../examples/Importers/ImportObjDemo/Wavefront2GLInstanceGraphicsShape.cpp",
"../../examples/Importers/ImportMJCFDemo/BulletMJCFImporter.cpp",
"../../examples/Importers/ImportURDFDemo/BulletUrdfImporter.cpp",
"../../examples/Importers/ImportURDFDemo/MyMultiBodyCreator.cpp",
"../../examples/Importers/ImportURDFDemo/URDF2Bullet.cpp",
"../../examples/Importers/ImportURDFDemo/UrdfParser.cpp",
"../../examples/Importers/ImportURDFDemo/urdfStringSplit.cpp",
"../../examples/MultiThreading/b3PosixThreadSupport.cpp",
"../../examples/MultiThreading/b3Win32ThreadSupport.cpp",
"../../examples/MultiThreading/b3ThreadSupportInterface.cpp",
"../../examples/Importers/ImportMeshUtility/b3ImportMeshUtility.cpp",
"../../examples/ThirdPartyLibs/stb_image/stb_image.cpp",
}
project ("App_RobotSimulator")
language "C++"
@@ -87,72 +151,132 @@ 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 _OPTIONS["serial"] then
defines{"B3_ENABLE_SERIAL"}
includedirs {"../../examples/ThirdPartyLibs/serial/include"}
links {"serial"}
end
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",
"b3RobotSimulatorClientAPI.h",
"MinitaurSetup.cpp",
"MinitaurSetup.h",
"../../examples/SharedMemory/IKTrajectoryHelper.cpp",
"../../examples/SharedMemory/IKTrajectoryHelper.h",
"../../examples/ExampleBrowser/InProcessExampleBrowser.cpp",
"../../examples/SharedMemory/InProcessMemory.cpp",
"../../examples/SharedMemory/PhysicsClient.cpp",
"../../examples/SharedMemory/PhysicsClient.h",
"../../examples/SharedMemory/PhysicsServer.cpp",
"../../examples/SharedMemory/PhysicsServer.h",
"../../examples/SharedMemory/PhysicsServerExample.cpp",
"../../examples/SharedMemory/SharedMemoryInProcessPhysicsC_API.cpp",
"../../examples/SharedMemory/PhysicsServerSharedMemory.cpp",
"../../examples/SharedMemory/PhysicsServerSharedMemory.h",
"../../examples/SharedMemory/PhysicsDirect.cpp",
"../../examples/SharedMemory/PhysicsDirect.h",
"../../examples/SharedMemory/PhysicsDirectC_API.cpp",
"../../examples/SharedMemory/PhysicsDirectC_API.h",
"../../examples/SharedMemory/PhysicsServerCommandProcessor.cpp",
"../../examples/SharedMemory/PhysicsServerCommandProcessor.h",
"../../examples/SharedMemory/PhysicsClientSharedMemory.cpp",
"../../examples/SharedMemory/PhysicsClientSharedMemory.h",
"../../examples/SharedMemory/PhysicsClientSharedMemory_C_API.cpp",
"../../examples/SharedMemory/PhysicsClientSharedMemory_C_API.h",
"../../examples/SharedMemory/PhysicsClientC_API.cpp",
"../../examples/SharedMemory/PhysicsClientC_API.h",
"../../examples/SharedMemory/Win32SharedMemory.cpp",
"../../examples/SharedMemory/Win32SharedMemory.h",
"../../examples/SharedMemory/PosixSharedMemory.cpp",
"../../examples/SharedMemory/PosixSharedMemory.h",
"../../examples/SharedMemory/TinyRendererVisualShapeConverter.cpp",
"../../examples/SharedMemory/TinyRendererVisualShapeConverter.h",
"../../examples/TinyRenderer/geometry.cpp",
"../../examples/TinyRenderer/model.cpp",
"../../examples/TinyRenderer/tgaimage.cpp",
"../../examples/TinyRenderer/our_gl.cpp",
"../../examples/TinyRenderer/TinyRenderer.cpp",
"../../examples/Utils/b3ResourcePath.cpp",
"../../examples/Utils/b3ResourcePath.h",
"../../examples/Utils/RobotLoggingUtil.cpp",
"../../examples/Utils/RobotLoggingUtil.h",
"../../examples/ThirdPartyLibs/tinyxml/tinystr.cpp",
"../../examples/ThirdPartyLibs/tinyxml/tinyxml.cpp",
"../../examples/ThirdPartyLibs/tinyxml/tinyxmlerror.cpp",
"../../examples/ThirdPartyLibs/tinyxml/tinyxmlparser.cpp",
"../../examples/ThirdPartyLibs/Wavefront/tiny_obj_loader.cpp",
"../../examples/ThirdPartyLibs/Wavefront/tiny_obj_loader.h",
"../../examples/Importers/ImportColladaDemo/LoadMeshFromCollada.cpp",
"../../examples/Importers/ImportObjDemo/LoadMeshFromObj.cpp",
"../../examples/Importers/ImportObjDemo/Wavefront2GLInstanceGraphicsShape.cpp",
"../../examples/Importers/ImportMJCFDemo/BulletMJCFImporter.cpp",
"../../examples/Importers/ImportURDFDemo/BulletUrdfImporter.cpp",
"../../examples/Importers/ImportURDFDemo/MyMultiBodyCreator.cpp",
"../../examples/Importers/ImportURDFDemo/URDF2Bullet.cpp",
"../../examples/Importers/ImportURDFDemo/UrdfParser.cpp",
"../../examples/Importers/ImportURDFDemo/urdfStringSplit.cpp",
"../../examples/MultiThreading/b3PosixThreadSupport.cpp",
"../../examples/MultiThreading/b3Win32ThreadSupport.cpp",
"../../examples/MultiThreading/b3ThreadSupportInterface.cpp",
"../../examples/Importers/ImportMeshUtility/b3ImportMeshUtility.cpp",
"../../examples/ThirdPartyLibs/stb_image/stb_image.cpp",
}
myfiles
}
if os.is("Linux") then
initX11()
end
project ("App_VRGloveHandSimulator")
language "C++"
kind "ConsoleApp"
includedirs {"../../src", "../../examples",
"../../examples/ThirdPartyLibs"}
defines {"PHYSICS_IN_PROCESS_EXAMPLE_BROWSER"}
hasCL = findOpenCL("clew")
links{"BulletExampleBrowserLib","gwen", "OpenGL_Window","BulletFileLoader","BulletWorldImporter","BulletSoftBody", "BulletInverseDynamicsUtils", "BulletInverseDynamics", "BulletDynamics","BulletCollision","LinearMath","BussIK","Bullet3Common"}
initOpenGL()
initGlew()
includedirs {
".",
"../../src",
"../ThirdPartyLibs",
}
if os.is("MacOSX") then
links{"Cocoa.framework"}
end
if (hasCL) then
links {
"Bullet3OpenCL_clew",
"Bullet3Dynamics",
"Bullet3Collision",
"Bullet3Geometry",
"Bullet3Common",
}
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 _OPTIONS["serial"] then
defines{"B3_ENABLE_SERIAL"}
includedirs {"../../examples/ThirdPartyLibs/serial/include"}
links {"serial"}
end
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 {
"VRGloveSimulatorMain.cpp",
"b3RobotSimulatorClientAPI.cpp",
"b3RobotSimulatorClientAPI.h",
myfiles
}
if os.is("Linux") then
initX11()
end

View File

@@ -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"
@@ -115,6 +119,7 @@ struct SharedMemoryDebugDrawer : public btIDebugDraw
};
struct InteralBodyData
{
btMultiBody* m_multiBody;
@@ -124,6 +129,9 @@ struct InteralBodyData
btTransform m_rootLocalInertialFrame;
btAlignedObjectArray<btTransform> m_linkLocalInertialFrames;
#ifdef B3_ENABLE_TINY_AUDIO
btHashMap<btHashInt, SDFAudioSource> m_audioSources;
#endif //B3_ENABLE_TINY_AUDIO
InteralBodyData()
:m_multiBody(0),
@@ -1297,6 +1305,9 @@ struct PhysicsServerCommandProcessorInternalData
btScalar m_oldPickingDist;
bool m_prevCanSleep;
TinyRendererVisualShapeConverter m_visualConverter;
#ifdef B3_ENABLE_TINY_AUDIO
b3SoundEngine m_soundEngine;
#endif
PhysicsServerCommandProcessorInternalData()
:
@@ -1456,11 +1467,118 @@ 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];
bool objHasSound[2];
objHasSound[0] = (0!=(manifold->getBody0()->getCollisionFlags() & btCollisionObject::CF_HAS_COLLISION_SOUND_TRIGGER));
objHasSound[1] = (0!=(manifold->getBody1()->getCollisionFlags() & btCollisionObject::CF_HAS_COLLISION_SOUND_TRIGGER));
const btCollisionObject* colObjs[2] = {manifold->getBody0(),manifold->getBody1()};
for (int ob = 0;ob<2;ob++)
{
if (objHasSound[ob])
{
int uid0 = -1;
int linkIndex = -2;
const btMultiBodyLinkCollider* mblB = btMultiBodyLinkCollider::upcast(colObjs[ob]);
if (mblB && mblB->m_multiBody)
{
linkIndex = mblB->m_link;
uid0 = mblB->m_multiBody->getUserIndex2();
}
const btRigidBody* bodyB = btRigidBody::upcast(colObjs[ob]);
if (bodyB)
{
uid0 = bodyB->getUserIndex2();
linkIndex = -1;
}
if ((uid0<0)||(linkIndex<-1))
continue;
InternalBodyHandle* bodyHandle0 = m_data->getHandle(uid0);
SDFAudioSource* audioSrc = bodyHandle0->m_audioSources[linkIndex];
if (audioSrc==0)
continue;
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>audioSrc->m_collisionForceThreshold && manifold->getContactPoint(p).getLifeTime()==1)
{
int soundSourceIndex = m_data->m_soundEngine.getAvailableSoundSource();
if (soundSourceIndex>=0)
{
b3SoundMessage msg;
msg.m_attackRate = audioSrc->m_attackRate;
msg.m_decayRate = audioSrc->m_decayRate;
msg.m_sustainLevel = audioSrc->m_sustainLevel;
msg.m_releaseRate = audioSrc->m_releaseRate;
msg.m_amplitude = audioSrc->m_gain;
msg.m_frequency = audioSrc->m_pitch;
msg.m_type = B3_SOUND_SOURCE_WAV_FILE;
msg.m_wavId = audioSrc->m_userIndex;
msg.m_autoKeyOff = true;
m_data->m_soundEngine.startSound(soundSourceIndex,msg);
}
}
}
}
}
}
#endif//B3_ENABLE_TINY_AUDIO
}
void PhysicsServerCommandProcessor::logObjectStates(btScalar timeStep)
{
@@ -1522,6 +1640,17 @@ 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);
//we don't use those callbacks (yet), experimental
// gContactAddedCallback = MyContactAddedCallback;
// gContactDestroyedCallback = MyContactDestroyedCallback;
// gContactProcessedCallback = MyContactProcessedCallback;
// gContactStartedCallback = MyContactStartedCallback;
// gContactEndedCallback = MyContactEndedCallback;
#endif
}
void PhysicsServerCommandProcessor::deleteStateLoggers()
@@ -1565,6 +1694,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();
@@ -1919,7 +2056,6 @@ bool PhysicsServerCommandProcessor::loadUrdf(const char* fileName, const btVecto
BulletURDFImporter u2b(m_data->m_guiHelper, &m_data->m_visualConverter);
bool loadOk = u2b.loadURDF(fileName, useFixedBase);
@@ -1991,6 +2127,22 @@ bool PhysicsServerCommandProcessor::loadUrdf(const char* fileName, const btVecto
}
createJointMotors(mb);
#ifdef B3_ENABLE_TINY_AUDIO
{
SDFAudioSource audioSource;
int urdfRootLink = u2b.getRootLinkIndex();//LinkIndex = creation.m_mb2urdfLink[-1];
if (u2b.getLinkAudioSource(urdfRootLink,audioSource))
{
int flags = mb->getBaseCollider()->getCollisionFlags();
mb->getBaseCollider()->setCollisionFlags(flags | btCollisionObject::CF_HAS_COLLISION_SOUND_TRIGGER);
audioSource.m_userIndex = m_data->m_soundEngine.loadWavFile(audioSource.m_uri.c_str());
if (audioSource.m_userIndex>=0)
{
bodyHandle->m_audioSources.insert(-1, audioSource);
}
}
}
#endif
//serialize the btMultiBody and send the data to the client. This is one way to get the link/joint names across the (shared memory) wire
UrdfLinkNameMapUtil* util = new UrdfLinkNameMapUtil;
@@ -2010,6 +2162,7 @@ bool PhysicsServerCommandProcessor::loadUrdf(const char* fileName, const btVecto
bodyHandle->m_linkLocalInertialFrames.reserve(mb->getNumLinks());
for (int i=0;i<mb->getNumLinks();i++)
{
int link=i;
//disable serialization of the collision objects
util->m_memSerializer->m_skipPointers.insert(mb->getLink(i).m_collider,0);
int urdfLinkIndex = creation.m_mb2urdfLink[i];
@@ -2028,9 +2181,25 @@ bool PhysicsServerCommandProcessor::loadUrdf(const char* fileName, const btVecto
m_data->m_strings.push_back(jointName);
util->m_memSerializer->registerNameForPointer(jointName->c_str(),jointName->c_str());
mb->getLink(i).m_jointName = jointName->c_str();
}
#ifdef B3_ENABLE_TINY_AUDIO
{
SDFAudioSource audioSource;
int urdfLinkIndex = creation.m_mb2urdfLink[link];
if (u2b.getLinkAudioSource(urdfLinkIndex,audioSource))
{
int flags = mb->getLink(link).m_collider->getCollisionFlags();
mb->getLink(i).m_collider->setCollisionFlags(flags | btCollisionObject::CF_HAS_COLLISION_SOUND_TRIGGER);
audioSource.m_userIndex = m_data->m_soundEngine.loadWavFile(audioSource.m_uri.c_str());
if (audioSource.m_userIndex>=0)
{
bodyHandle->m_audioSources.insert(link, audioSource);
}
}
}
#endif
}
std::string* baseName = new std::string(u2b.getLinkName(u2b.getRootLinkIndex()));
std::string* baseName = new std::string(u2b.getLinkName(u2b.getRootLinkIndex()));
m_data->m_strings.push_back(baseName);
mb->setBaseName(baseName->c_str());

View File

@@ -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);

View File

@@ -167,6 +167,14 @@ enum JointType {
ePoint2PointType = 5,
};
enum b3JointInfoFlags
{
eJointChangeMaxForce = 1,
eJointChangeChildFramePosition = 2,
eJointChangeChildFrameOrientation = 4,
};
struct b3JointInfo
{
char* m_linkName;
@@ -317,11 +325,7 @@ struct b3VREventsData
{
int m_numControllerEvents;
struct b3VRControllerEvent* m_controllerEvents;
int m_numHmdEvents;
struct b3VRMoveEvent* m_hmdEvents;
int m_numGenericTrackerEvents;
struct b3VRMoveEvent* m_genericTrackerEvents;
};

View File

@@ -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",

View File

@@ -0,0 +1,78 @@
# Serial Communication Library
[![Build Status](https://travis-ci.org/wjwwood/serial.svg?branch=master)](https://travis-ci.org/wjwwood/serial)*(Linux and OS X)* [![Build Status](https://ci.appveyor.com/api/projects/status/github/wjwwood/serial)](https://ci.appveyor.com/project/wjwwood/serial)*(Windows)*
This is a cross-platform library for interfacing with rs-232 serial like ports written in C++. It provides a modern C++ interface with a workflow designed to look and feel like PySerial, but with the speed and control provided by C++.
This library is in use in several robotics related projects and can be built and installed to the OS like most unix libraries with make and then sudo make install, but because it is a catkin project it can also be built along side other catkin projects in a catkin workspace.
Serial is a class that provides the basic interface common to serial libraries (open, close, read, write, etc..) and requires no extra dependencies. It also provides tight control over timeouts and control over handshaking lines.
### Documentation
Website: http://wjwwood.github.com/serial/
API Documentation: http://wjwwood.github.com/serial/doc/1.1.0/index.html
### Dependencies
Required:
* [catkin](http://www.ros.org/wiki/catkin) - cmake and Python based buildsystem
* [cmake](http://www.cmake.org) - buildsystem
* [Python](http://www.python.org) - scripting language
* [empy](http://www.alcyone.com/pyos/empy/) - Python templating library
* [catkin_pkg](http://pypi.python.org/pypi/catkin_pkg/) - Runtime Python library for catkin
Optional (for tests):
* [Boost](http://www.boost.org/) - Boost C++ librairies
Optional (for documentation):
* [Doxygen](http://www.doxygen.org/) - Documentation generation tool
* [graphviz](http://www.graphviz.org/) - Graph visualization software
### Install
Get the code:
git clone https://github.com/wjwwood/serial.git
Build:
make
Build and run the tests:
make test
Build the documentation:
make doc
Install:
make install
Uninstall:
make uninstall
### License
The MIT License
Copyright (c) 2012 William Woodall, John Harrison
Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files (the "Software"), to deal in the Software without restriction, including without limitation the rights to use, copy, modify, merge, publish, distribute, sublicense, and/or sell copies of the Software, and to permit persons to whom the Software is furnished to do so, subject to the following conditions:
The above copyright notice and this permission notice shall be included in all copies or substantial portions of the Software.
THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE.
### Authors
William Woodall <wjwwood@gmail.com>
John Harrison <ash.gti@gmail.com>
### Contact
William Woodall <william@osrfoundation.org>

View File

@@ -0,0 +1,221 @@
/*!
* \file serial/impl/unix.h
* \author William Woodall <wjwwood@gmail.com>
* \author John Harrison <ash@greaterthaninfinity.com>
* \version 0.1
*
* \section LICENSE
*
* The MIT License
*
* Copyright (c) 2012 William Woodall, John Harrison
*
* Permission is hereby granted, free of charge, to any person obtaining a
* copy of this software and associated documentation files (the "Software"),
* to deal in the Software without restriction, including without limitation
* the rights to use, copy, modify, merge, publish, distribute, sublicense,
* and/or sell copies of the Software, and to permit persons to whom the
* Software is furnished to do so, subject to the following conditions:
*
* The above copyright notice and this permission notice shall be included in
* all copies or substantial portions of the Software.
*
* THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
* IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
* FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
* AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
* LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING
* FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER
* DEALINGS IN THE SOFTWARE.
*
* \section DESCRIPTION
*
* This provides a unix based pimpl for the Serial class. This implementation is
* based off termios.h and uses select for multiplexing the IO ports.
*
*/
#if !defined(_WIN32)
#ifndef SERIAL_IMPL_UNIX_H
#define SERIAL_IMPL_UNIX_H
#include "serial/serial.h"
#include <pthread.h>
namespace serial {
using std::size_t;
using std::string;
using std::invalid_argument;
using serial::SerialException;
using serial::IOException;
class MillisecondTimer {
public:
MillisecondTimer(const uint32_t millis);
int64_t remaining();
private:
static timespec timespec_now();
timespec expiry;
};
class serial::Serial::SerialImpl {
public:
SerialImpl (const string &port,
unsigned long baudrate,
bytesize_t bytesize,
parity_t parity,
stopbits_t stopbits,
flowcontrol_t flowcontrol);
virtual ~SerialImpl ();
void
open ();
void
close ();
bool
isOpen () const;
size_t
available ();
bool
waitReadable (uint32_t timeout);
void
waitByteTimes (size_t count);
size_t
read (uint8_t *buf, size_t size = 1);
size_t
write (const uint8_t *data, size_t length);
void
flush ();
void
flushInput ();
void
flushOutput ();
void
sendBreak (int duration);
void
setBreak (bool level);
void
setRTS (bool level);
void
setDTR (bool level);
bool
waitForChange ();
bool
getCTS ();
bool
getDSR ();
bool
getRI ();
bool
getCD ();
void
setPort (const string &port);
string
getPort () const;
void
setTimeout (Timeout &timeout);
Timeout
getTimeout () const;
void
setBaudrate (unsigned long baudrate);
unsigned long
getBaudrate () const;
void
setBytesize (bytesize_t bytesize);
bytesize_t
getBytesize () const;
void
setParity (parity_t parity);
parity_t
getParity () const;
void
setStopbits (stopbits_t stopbits);
stopbits_t
getStopbits () const;
void
setFlowcontrol (flowcontrol_t flowcontrol);
flowcontrol_t
getFlowcontrol () const;
void
readLock ();
void
readUnlock ();
void
writeLock ();
void
writeUnlock ();
protected:
void reconfigurePort ();
private:
string port_; // Path to the file descriptor
int fd_; // The current file descriptor
bool is_open_;
bool xonxoff_;
bool rtscts_;
Timeout timeout_; // Timeout for read operations
unsigned long baudrate_; // Baudrate
uint32_t byte_time_ns_; // Nanoseconds to transmit/receive a single byte
parity_t parity_; // Parity
bytesize_t bytesize_; // Size of the bytes
stopbits_t stopbits_; // Stop Bits
flowcontrol_t flowcontrol_; // Flow Control
// Mutex used to lock the read functions
pthread_mutex_t read_mutex;
// Mutex used to lock the write functions
pthread_mutex_t write_mutex;
};
}
#endif // SERIAL_IMPL_UNIX_H
#endif // !defined(_WIN32)

View File

@@ -0,0 +1,207 @@
/*!
* \file serial/impl/windows.h
* \author William Woodall <wjwwood@gmail.com>
* \author John Harrison <ash@greaterthaninfinity.com>
* \version 0.1
*
* \section LICENSE
*
* The MIT License
*
* Copyright (c) 2012 William Woodall, John Harrison
*
* Permission is hereby granted, free of charge, to any person obtaining a
* copy of this software and associated documentation files (the "Software"),
* to deal in the Software without restriction, including without limitation
* the rights to use, copy, modify, merge, publish, distribute, sublicense,
* and/or sell copies of the Software, and to permit persons to whom the
* Software is furnished to do so, subject to the following conditions:
*
* The above copyright notice and this permission notice shall be included in
* all copies or substantial portions of the Software.
*
* THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
* IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
* FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
* AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
* LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING
* FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER
* DEALINGS IN THE SOFTWARE.
*
* \section DESCRIPTION
*
* This provides a windows implementation of the Serial class interface.
*
*/
#if defined(_WIN32)
#ifndef SERIAL_IMPL_WINDOWS_H
#define SERIAL_IMPL_WINDOWS_H
#include "serial/serial.h"
#include "windows.h"
namespace serial {
using std::string;
using std::wstring;
using std::invalid_argument;
using serial::SerialException;
using serial::IOException;
class serial::Serial::SerialImpl {
public:
SerialImpl (const string &port,
unsigned long baudrate,
bytesize_t bytesize,
parity_t parity,
stopbits_t stopbits,
flowcontrol_t flowcontrol);
virtual ~SerialImpl ();
void
open ();
void
close ();
bool
isOpen () const;
size_t
available ();
bool
waitReadable (uint32_t timeout);
void
waitByteTimes (size_t count);
size_t
read (uint8_t *buf, size_t size = 1);
size_t
write (const uint8_t *data, size_t length);
void
flush ();
void
flushInput ();
void
flushOutput ();
void
sendBreak (int duration);
void
setBreak (bool level);
void
setRTS (bool level);
void
setDTR (bool level);
bool
waitForChange ();
bool
getCTS ();
bool
getDSR ();
bool
getRI ();
bool
getCD ();
void
setPort (const string &port);
string
getPort () const;
void
setTimeout (Timeout &timeout);
Timeout
getTimeout () const;
void
setBaudrate (unsigned long baudrate);
unsigned long
getBaudrate () const;
void
setBytesize (bytesize_t bytesize);
bytesize_t
getBytesize () const;
void
setParity (parity_t parity);
parity_t
getParity () const;
void
setStopbits (stopbits_t stopbits);
stopbits_t
getStopbits () const;
void
setFlowcontrol (flowcontrol_t flowcontrol);
flowcontrol_t
getFlowcontrol () const;
void
readLock ();
void
readUnlock ();
void
writeLock ();
void
writeUnlock ();
protected:
void reconfigurePort ();
private:
wstring port_; // Path to the file descriptor
HANDLE fd_;
bool is_open_;
Timeout timeout_; // Timeout for read operations
unsigned long baudrate_; // Baudrate
parity_t parity_; // Parity
bytesize_t bytesize_; // Size of the bytes
stopbits_t stopbits_; // Stop Bits
flowcontrol_t flowcontrol_; // Flow Control
// Mutex used to lock the read functions
HANDLE read_mutex;
// Mutex used to lock the write functions
HANDLE write_mutex;
};
}
#endif // SERIAL_IMPL_WINDOWS_H
#endif // if defined(_WIN32)

View File

@@ -0,0 +1,775 @@
/*!
* \file serial/serial.h
* \author William Woodall <wjwwood@gmail.com>
* \author John Harrison <ash.gti@gmail.com>
* \version 0.1
*
* \section LICENSE
*
* The MIT License
*
* Copyright (c) 2012 William Woodall
*
* Permission is hereby granted, free of charge, to any person obtaining a
* copy of this software and associated documentation files (the "Software"),
* to deal in the Software without restriction, including without limitation
* the rights to use, copy, modify, merge, publish, distribute, sublicense,
* and/or sell copies of the Software, and to permit persons to whom the
* Software is furnished to do so, subject to the following conditions:
*
* The above copyright notice and this permission notice shall be included in
* all copies or substantial portions of the Software.
*
* THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
* IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
* FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
* AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
* LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING
* FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER
* DEALINGS IN THE SOFTWARE.
*
* \section DESCRIPTION
*
* This provides a cross platform interface for interacting with Serial Ports.
*/
#ifndef SERIAL_H
#define SERIAL_H
#include <limits>
#include <vector>
#include <string>
#include <cstring>
#include <sstream>
#include <exception>
#include <stdexcept>
#include <serial/v8stdint.h>
#define THROW(exceptionClass, message) throw exceptionClass(__FILE__, \
__LINE__, (message) )
namespace serial {
/*!
* Enumeration defines the possible bytesizes for the serial port.
*/
typedef enum {
fivebits = 5,
sixbits = 6,
sevenbits = 7,
eightbits = 8
} bytesize_t;
/*!
* Enumeration defines the possible parity types for the serial port.
*/
typedef enum {
parity_none = 0,
parity_odd = 1,
parity_even = 2,
parity_mark = 3,
parity_space = 4
} parity_t;
/*!
* Enumeration defines the possible stopbit types for the serial port.
*/
typedef enum {
stopbits_one = 1,
stopbits_two = 2,
stopbits_one_point_five
} stopbits_t;
/*!
* Enumeration defines the possible flowcontrol types for the serial port.
*/
typedef enum {
flowcontrol_none = 0,
flowcontrol_software,
flowcontrol_hardware
} flowcontrol_t;
/*!
* Structure for setting the timeout of the serial port, times are
* in milliseconds.
*
* In order to disable the interbyte timeout, set it to Timeout::max().
*/
struct Timeout {
#ifdef max
# undef max
#endif
static uint32_t max() {return std::numeric_limits<uint32_t>::max();}
/*!
* Convenience function to generate Timeout structs using a
* single absolute timeout.
*
* \param timeout A long that defines the time in milliseconds until a
* timeout occurs after a call to read or write is made.
*
* \return Timeout struct that represents this simple timeout provided.
*/
static Timeout simpleTimeout(uint32_t timeout) {
return Timeout(max(), timeout, 0, timeout, 0);
}
/*! Number of milliseconds between bytes received to timeout on. */
uint32_t inter_byte_timeout;
/*! A constant number of milliseconds to wait after calling read. */
uint32_t read_timeout_constant;
/*! A multiplier against the number of requested bytes to wait after
* calling read.
*/
uint32_t read_timeout_multiplier;
/*! A constant number of milliseconds to wait after calling write. */
uint32_t write_timeout_constant;
/*! A multiplier against the number of requested bytes to wait after
* calling write.
*/
uint32_t write_timeout_multiplier;
explicit Timeout (uint32_t inter_byte_timeout_=0,
uint32_t read_timeout_constant_=0,
uint32_t read_timeout_multiplier_=0,
uint32_t write_timeout_constant_=0,
uint32_t write_timeout_multiplier_=0)
: inter_byte_timeout(inter_byte_timeout_),
read_timeout_constant(read_timeout_constant_),
read_timeout_multiplier(read_timeout_multiplier_),
write_timeout_constant(write_timeout_constant_),
write_timeout_multiplier(write_timeout_multiplier_)
{}
};
/*!
* Class that provides a portable serial port interface.
*/
class Serial {
public:
/*!
* Creates a Serial object and opens the port if a port is specified,
* otherwise it remains closed until serial::Serial::open is called.
*
* \param port A std::string containing the address of the serial port,
* which would be something like 'COM1' on Windows and '/dev/ttyS0'
* on Linux.
*
* \param baudrate An unsigned 32-bit integer that represents the baudrate
*
* \param timeout A serial::Timeout struct that defines the timeout
* conditions for the serial port. \see serial::Timeout
*
* \param bytesize Size of each byte in the serial transmission of data,
* default is eightbits, possible values are: fivebits, sixbits, sevenbits,
* eightbits
*
* \param parity Method of parity, default is parity_none, possible values
* are: parity_none, parity_odd, parity_even
*
* \param stopbits Number of stop bits used, default is stopbits_one,
* possible values are: stopbits_one, stopbits_one_point_five, stopbits_two
*
* \param flowcontrol Type of flowcontrol used, default is
* flowcontrol_none, possible values are: flowcontrol_none,
* flowcontrol_software, flowcontrol_hardware
*
* \throw serial::PortNotOpenedException
* \throw serial::IOException
* \throw std::invalid_argument
*/
Serial (const std::string &port = "",
uint32_t baudrate = 9600,
Timeout timeout = Timeout(),
bytesize_t bytesize = eightbits,
parity_t parity = parity_none,
stopbits_t stopbits = stopbits_one,
flowcontrol_t flowcontrol = flowcontrol_none);
/*! Destructor */
virtual ~Serial ();
/*!
* Opens the serial port as long as the port is set and the port isn't
* already open.
*
* If the port is provided to the constructor then an explicit call to open
* is not needed.
*
* \see Serial::Serial
*
* \throw std::invalid_argument
* \throw serial::SerialException
* \throw serial::IOException
*/
void
open ();
/*! Gets the open status of the serial port.
*
* \return Returns true if the port is open, false otherwise.
*/
bool
isOpen () const;
/*! Closes the serial port. */
void
close ();
/*! Return the number of characters in the buffer. */
size_t
available ();
/*! Block until there is serial data to read or read_timeout_constant
* number of milliseconds have elapsed. The return value is true when
* the function exits with the port in a readable state, false otherwise
* (due to timeout or select interruption). */
bool
waitReadable ();
/*! Block for a period of time corresponding to the transmission time of
* count characters at present serial settings. This may be used in con-
* junction with waitReadable to read larger blocks of data from the
* port. */
void
waitByteTimes (size_t count);
/*! Read a given amount of bytes from the serial port into a given buffer.
*
* The read function will return in one of three cases:
* * The number of requested bytes was read.
* * In this case the number of bytes requested will match the size_t
* returned by read.
* * A timeout occurred, in this case the number of bytes read will not
* match the amount requested, but no exception will be thrown. One of
* two possible timeouts occurred:
* * The inter byte timeout expired, this means that number of
* milliseconds elapsed between receiving bytes from the serial port
* exceeded the inter byte timeout.
* * The total timeout expired, which is calculated by multiplying the
* read timeout multiplier by the number of requested bytes and then
* added to the read timeout constant. If that total number of
* milliseconds elapses after the initial call to read a timeout will
* occur.
* * An exception occurred, in this case an actual exception will be thrown.
*
* \param buffer An uint8_t array of at least the requested size.
* \param size A size_t defining how many bytes to be read.
*
* \return A size_t representing the number of bytes read as a result of the
* call to read.
*
* \throw serial::PortNotOpenedException
* \throw serial::SerialException
*/
size_t
read (uint8_t *buffer, size_t size);
/*! Read a given amount of bytes from the serial port into a give buffer.
*
* \param buffer A reference to a std::vector of uint8_t.
* \param size A size_t defining how many bytes to be read.
*
* \return A size_t representing the number of bytes read as a result of the
* call to read.
*
* \throw serial::PortNotOpenedException
* \throw serial::SerialException
*/
size_t
read (std::vector<uint8_t> &buffer, size_t size = 1);
/*! Read a given amount of bytes from the serial port into a give buffer.
*
* \param buffer A reference to a std::string.
* \param size A size_t defining how many bytes to be read.
*
* \return A size_t representing the number of bytes read as a result of the
* call to read.
*
* \throw serial::PortNotOpenedException
* \throw serial::SerialException
*/
size_t
read (std::string &buffer, size_t size = 1);
/*! Read a given amount of bytes from the serial port and return a string
* containing the data.
*
* \param size A size_t defining how many bytes to be read.
*
* \return A std::string containing the data read from the port.
*
* \throw serial::PortNotOpenedException
* \throw serial::SerialException
*/
std::string
read (size_t size = 1);
/*! Reads in a line or until a given delimiter has been processed.
*
* Reads from the serial port until a single line has been read.
*
* \param buffer A std::string reference used to store the data.
* \param size A maximum length of a line, defaults to 65536 (2^16)
* \param eol A string to match against for the EOL.
*
* \return A size_t representing the number of bytes read.
*
* \throw serial::PortNotOpenedException
* \throw serial::SerialException
*/
size_t
readline (std::string &buffer, size_t size = 65536, std::string eol = "\n");
/*! Reads in a line or until a given delimiter has been processed.
*
* Reads from the serial port until a single line has been read.
*
* \param size A maximum length of a line, defaults to 65536 (2^16)
* \param eol A string to match against for the EOL.
*
* \return A std::string containing the line.
*
* \throw serial::PortNotOpenedException
* \throw serial::SerialException
*/
std::string
readline (size_t size = 65536, std::string eol = "\n");
/*! Reads in multiple lines until the serial port times out.
*
* This requires a timeout > 0 before it can be run. It will read until a
* timeout occurs and return a list of strings.
*
* \param size A maximum length of combined lines, defaults to 65536 (2^16)
*
* \param eol A string to match against for the EOL.
*
* \return A vector<string> containing the lines.
*
* \throw serial::PortNotOpenedException
* \throw serial::SerialException
*/
std::vector<std::string>
readlines (size_t size = 65536, std::string eol = "\n");
/*! Write a string to the serial port.
*
* \param data A const reference containing the data to be written
* to the serial port.
*
* \param size A size_t that indicates how many bytes should be written from
* the given data buffer.
*
* \return A size_t representing the number of bytes actually written to
* the serial port.
*
* \throw serial::PortNotOpenedException
* \throw serial::SerialException
* \throw serial::IOException
*/
size_t
write (const uint8_t *data, size_t size);
/*! Write a string to the serial port.
*
* \param data A const reference containing the data to be written
* to the serial port.
*
* \return A size_t representing the number of bytes actually written to
* the serial port.
*
* \throw serial::PortNotOpenedException
* \throw serial::SerialException
* \throw serial::IOException
*/
size_t
write (const std::vector<uint8_t> &data);
/*! Write a string to the serial port.
*
* \param data A const reference containing the data to be written
* to the serial port.
*
* \return A size_t representing the number of bytes actually written to
* the serial port.
*
* \throw serial::PortNotOpenedException
* \throw serial::SerialException
* \throw serial::IOException
*/
size_t
write (const std::string &data);
/*! Sets the serial port identifier.
*
* \param port A const std::string reference containing the address of the
* serial port, which would be something like 'COM1' on Windows and
* '/dev/ttyS0' on Linux.
*
* \throw std::invalid_argument
*/
void
setPort (const std::string &port);
/*! Gets the serial port identifier.
*
* \see Serial::setPort
*
* \throw std::invalid_argument
*/
std::string
getPort () const;
/*! Sets the timeout for reads and writes using the Timeout struct.
*
* There are two timeout conditions described here:
* * The inter byte timeout:
* * The inter_byte_timeout component of serial::Timeout defines the
* maximum amount of time, in milliseconds, between receiving bytes on
* the serial port that can pass before a timeout occurs. Setting this
* to zero will prevent inter byte timeouts from occurring.
* * Total time timeout:
* * The constant and multiplier component of this timeout condition,
* for both read and write, are defined in serial::Timeout. This
* timeout occurs if the total time since the read or write call was
* made exceeds the specified time in milliseconds.
* * The limit is defined by multiplying the multiplier component by the
* number of requested bytes and adding that product to the constant
* component. In this way if you want a read call, for example, to
* timeout after exactly one second regardless of the number of bytes
* you asked for then set the read_timeout_constant component of
* serial::Timeout to 1000 and the read_timeout_multiplier to zero.
* This timeout condition can be used in conjunction with the inter
* byte timeout condition with out any problems, timeout will simply
* occur when one of the two timeout conditions is met. This allows
* users to have maximum control over the trade-off between
* responsiveness and efficiency.
*
* Read and write functions will return in one of three cases. When the
* reading or writing is complete, when a timeout occurs, or when an
* exception occurs.
*
* A timeout of 0 enables non-blocking mode.
*
* \param timeout A serial::Timeout struct containing the inter byte
* timeout, and the read and write timeout constants and multipliers.
*
* \see serial::Timeout
*/
void
setTimeout (Timeout &timeout);
/*! Sets the timeout for reads and writes. */
void
setTimeout (uint32_t inter_byte_timeout, uint32_t read_timeout_constant,
uint32_t read_timeout_multiplier, uint32_t write_timeout_constant,
uint32_t write_timeout_multiplier)
{
Timeout timeout(inter_byte_timeout, read_timeout_constant,
read_timeout_multiplier, write_timeout_constant,
write_timeout_multiplier);
return setTimeout(timeout);
}
/*! Gets the timeout for reads in seconds.
*
* \return A Timeout struct containing the inter_byte_timeout, and read
* and write timeout constants and multipliers.
*
* \see Serial::setTimeout
*/
Timeout
getTimeout () const;
/*! Sets the baudrate for the serial port.
*
* Possible baudrates depends on the system but some safe baudrates include:
* 110, 300, 600, 1200, 2400, 4800, 9600, 14400, 19200, 28800, 38400, 56000,
* 57600, 115200
* Some other baudrates that are supported by some comports:
* 128000, 153600, 230400, 256000, 460800, 921600
*
* \param baudrate An integer that sets the baud rate for the serial port.
*
* \throw std::invalid_argument
*/
void
setBaudrate (uint32_t baudrate);
/*! Gets the baudrate for the serial port.
*
* \return An integer that sets the baud rate for the serial port.
*
* \see Serial::setBaudrate
*
* \throw std::invalid_argument
*/
uint32_t
getBaudrate () const;
/*! Sets the bytesize for the serial port.
*
* \param bytesize Size of each byte in the serial transmission of data,
* default is eightbits, possible values are: fivebits, sixbits, sevenbits,
* eightbits
*
* \throw std::invalid_argument
*/
void
setBytesize (bytesize_t bytesize);
/*! Gets the bytesize for the serial port.
*
* \see Serial::setBytesize
*
* \throw std::invalid_argument
*/
bytesize_t
getBytesize () const;
/*! Sets the parity for the serial port.
*
* \param parity Method of parity, default is parity_none, possible values
* are: parity_none, parity_odd, parity_even
*
* \throw std::invalid_argument
*/
void
setParity (parity_t parity);
/*! Gets the parity for the serial port.
*
* \see Serial::setParity
*
* \throw std::invalid_argument
*/
parity_t
getParity () const;
/*! Sets the stopbits for the serial port.
*
* \param stopbits Number of stop bits used, default is stopbits_one,
* possible values are: stopbits_one, stopbits_one_point_five, stopbits_two
*
* \throw std::invalid_argument
*/
void
setStopbits (stopbits_t stopbits);
/*! Gets the stopbits for the serial port.
*
* \see Serial::setStopbits
*
* \throw std::invalid_argument
*/
stopbits_t
getStopbits () const;
/*! Sets the flow control for the serial port.
*
* \param flowcontrol Type of flowcontrol used, default is flowcontrol_none,
* possible values are: flowcontrol_none, flowcontrol_software,
* flowcontrol_hardware
*
* \throw std::invalid_argument
*/
void
setFlowcontrol (flowcontrol_t flowcontrol);
/*! Gets the flow control for the serial port.
*
* \see Serial::setFlowcontrol
*
* \throw std::invalid_argument
*/
flowcontrol_t
getFlowcontrol () const;
/*! Flush the input and output buffers */
void
flush ();
/*! Flush only the input buffer */
void
flushInput ();
/*! Flush only the output buffer */
void
flushOutput ();
/*! Sends the RS-232 break signal. See tcsendbreak(3). */
void
sendBreak (int duration);
/*! Set the break condition to a given level. Defaults to true. */
void
setBreak (bool level = true);
/*! Set the RTS handshaking line to the given level. Defaults to true. */
void
setRTS (bool level = true);
/*! Set the DTR handshaking line to the given level. Defaults to true. */
void
setDTR (bool level = true);
/*!
* Blocks until CTS, DSR, RI, CD changes or something interrupts it.
*
* Can throw an exception if an error occurs while waiting.
* You can check the status of CTS, DSR, RI, and CD once this returns.
* Uses TIOCMIWAIT via ioctl if available (mostly only on Linux) with a
* resolution of less than +-1ms and as good as +-0.2ms. Otherwise a
* polling method is used which can give +-2ms.
*
* \return Returns true if one of the lines changed, false if something else
* occurred.
*
* \throw SerialException
*/
bool
waitForChange ();
/*! Returns the current status of the CTS line. */
bool
getCTS ();
/*! Returns the current status of the DSR line. */
bool
getDSR ();
/*! Returns the current status of the RI line. */
bool
getRI ();
/*! Returns the current status of the CD line. */
bool
getCD ();
private:
// Disable copy constructors
Serial(const Serial&);
Serial& operator=(const Serial&);
// Pimpl idiom, d_pointer
class SerialImpl;
SerialImpl *pimpl_;
// Scoped Lock Classes
class ScopedReadLock;
class ScopedWriteLock;
// Read common function
size_t
read_ (uint8_t *buffer, size_t size);
// Write common function
size_t
write_ (const uint8_t *data, size_t length);
};
class SerialException : public std::exception
{
// Disable copy constructors
SerialException& operator=(const SerialException&);
std::string e_what_;
public:
SerialException (const char *description) {
std::stringstream ss;
ss << "SerialException " << description << " failed.";
e_what_ = ss.str();
}
SerialException (const SerialException& other) : e_what_(other.e_what_) {}
virtual ~SerialException() throw() {}
virtual const char* what () const throw () {
return e_what_.c_str();
}
};
class IOException : public std::exception
{
// Disable copy constructors
IOException& operator=(const IOException&);
std::string file_;
int line_;
std::string e_what_;
int errno_;
public:
explicit IOException (std::string file, int line, int errnum)
: file_(file), line_(line), errno_(errnum) {
std::stringstream ss;
#if defined(_WIN32) && !defined(__MINGW32__)
char error_str [1024];
strerror_s(error_str, 1024, errnum);
#else
char * error_str = strerror(errnum);
#endif
ss << "IO Exception (" << errno_ << "): " << error_str;
ss << ", file " << file_ << ", line " << line_ << ".";
e_what_ = ss.str();
}
explicit IOException (std::string file, int line, const char * description)
: file_(file), line_(line), errno_(0) {
std::stringstream ss;
ss << "IO Exception: " << description;
ss << ", file " << file_ << ", line " << line_ << ".";
e_what_ = ss.str();
}
virtual ~IOException() throw() {}
IOException (const IOException& other) : line_(other.line_), e_what_(other.e_what_), errno_(other.errno_) {}
int getErrorNumber () const { return errno_; }
virtual const char* what () const throw () {
return e_what_.c_str();
}
};
class PortNotOpenedException : public std::exception
{
// Disable copy constructors
const PortNotOpenedException& operator=(PortNotOpenedException);
std::string e_what_;
public:
PortNotOpenedException (const char * description) {
std::stringstream ss;
ss << "PortNotOpenedException " << description << " failed.";
e_what_ = ss.str();
}
PortNotOpenedException (const PortNotOpenedException& other) : e_what_(other.e_what_) {}
virtual ~PortNotOpenedException() throw() {}
virtual const char* what () const throw () {
return e_what_.c_str();
}
};
/*!
* Structure that describes a serial device.
*/
struct PortInfo {
/*! Address of the serial port (this can be passed to the constructor of Serial). */
std::string port;
/*! Human readable description of serial device if available. */
std::string description;
/*! Hardware ID (e.g. VID:PID of USB serial devices) or "n/a" if not available. */
std::string hardware_id;
};
/* Lists the serial ports available on the system
*
* Returns a vector of available serial ports, each represented
* by a serial::PortInfo data structure:
*
* \return vector of serial::PortInfo.
*/
std::vector<PortInfo>
list_ports();
} // namespace serial
#endif

View File

@@ -0,0 +1,57 @@
// This header is from the v8 google project:
// http://code.google.com/p/v8/source/browse/trunk/include/v8stdint.h
// Copyright 2012 the V8 project authors. All rights reserved.
// Redistribution and use in source and binary forms, with or without
// modification, are permitted provided that the following conditions are
// met:
//
// * Redistributions of source code must retain the above copyright
// notice, this list of conditions and the following disclaimer.
// * Redistributions in binary form must reproduce the above
// copyright notice, this list of conditions and the following
// disclaimer in the documentation and/or other materials provided
// with the distribution.
// * Neither the name of Google Inc. nor the names of its
// contributors may be used to endorse or promote products derived
// from this software without specific prior written permission.
//
// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
// "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
// LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR
// A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT
// OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL,
// SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT
// LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE,
// DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY
// THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
// (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
// OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
// Load definitions of standard types.
#ifndef V8STDINT_H_
#define V8STDINT_H_
#include <stddef.h>
#include <stdio.h>
#if defined(_WIN32) && !defined(__MINGW32__)
typedef signed char int8_t;
typedef unsigned char uint8_t;
typedef short int16_t; // NOLINT
typedef unsigned short uint16_t; // NOLINT
typedef int int32_t;
typedef unsigned int uint32_t;
typedef __int64 int64_t;
typedef unsigned __int64 uint64_t;
// intptr_t and friends are defined in crtdefs.h through stdio.h.
#else
#include <stdint.h>
#endif
#endif // V8STDINT_H_

View File

@@ -0,0 +1,31 @@
project "serial"
kind "StaticLib"
includedirs {"include"}
if os.is("Windows") then
files{
"src/impl/win.cc",
"src/impl/list_ports/list_ports_win.cc"
}
end
if os.is("Linux") then
files{
"src/impl/unix.cc",
"src/impl/list_ports/list_ports_linux.cc"
}
end
if os.is("MacOSX") then
files{
"src/impl/unix.cc",
"src/impl/list_ports/list_ports_osx.cc"
}
end
files {
"src/serial.cc",
"**.h"
}

View File

@@ -0,0 +1,335 @@
#if defined(__linux__)
/*
* Copyright (c) 2014 Craig Lilley <cralilley@gmail.com>
* This software is made available under the terms of the MIT licence.
* A copy of the licence can be obtained from:
* http://opensource.org/licenses/MIT
*/
#include <vector>
#include <string>
#include <sstream>
#include <stdexcept>
#include <iostream>
#include <fstream>
#include <cstdio>
#include <cstdarg>
#include <cstdlib>
#include <glob.h>
#include <sys/types.h>
#include <sys/stat.h>
#include <unistd.h>
#include "serial/serial.h"
using serial::PortInfo;
using std::istringstream;
using std::ifstream;
using std::getline;
using std::vector;
using std::string;
using std::cout;
using std::endl;
static vector<string> glob(const vector<string>& patterns);
static string basename(const string& path);
static string dirname(const string& path);
static bool path_exists(const string& path);
static string realpath(const string& path);
static string usb_sysfs_friendly_name(const string& sys_usb_path);
static vector<string> get_sysfs_info(const string& device_path);
static string read_line(const string& file);
static string usb_sysfs_hw_string(const string& sysfs_path);
static string format(const char* format, ...);
vector<string>
glob(const vector<string>& patterns)
{
vector<string> paths_found;
if(patterns.size() == 0)
return paths_found;
glob_t glob_results;
int glob_retval = glob(patterns[0].c_str(), 0, NULL, &glob_results);
vector<string>::const_iterator iter = patterns.begin();
while(++iter != patterns.end())
{
glob_retval = glob(iter->c_str(), GLOB_APPEND, NULL, &glob_results);
}
for(int path_index = 0; path_index < glob_results.gl_pathc; path_index++)
{
paths_found.push_back(glob_results.gl_pathv[path_index]);
}
globfree(&glob_results);
return paths_found;
}
string
basename(const string& path)
{
size_t pos = path.rfind("/");
if(pos == std::string::npos)
return path;
return string(path, pos+1, string::npos);
}
string
dirname(const string& path)
{
size_t pos = path.rfind("/");
if(pos == std::string::npos)
return path;
else if(pos == 0)
return "/";
return string(path, 0, pos);
}
bool
path_exists(const string& path)
{
struct stat sb;
if( stat(path.c_str(), &sb ) == 0 )
return true;
return false;
}
string
realpath(const string& path)
{
char* real_path = realpath(path.c_str(), NULL);
string result;
if(real_path != NULL)
{
result = real_path;
free(real_path);
}
return result;
}
string
usb_sysfs_friendly_name(const string& sys_usb_path)
{
unsigned int device_number = 0;
istringstream( read_line(sys_usb_path + "/devnum") ) >> device_number;
string manufacturer = read_line( sys_usb_path + "/manufacturer" );
string product = read_line( sys_usb_path + "/product" );
string serial = read_line( sys_usb_path + "/serial" );
if( manufacturer.empty() && product.empty() && serial.empty() )
return "";
return format("%s %s %s", manufacturer.c_str(), product.c_str(), serial.c_str() );
}
vector<string>
get_sysfs_info(const string& device_path)
{
string device_name = basename( device_path );
string friendly_name;
string hardware_id;
string sys_device_path = format( "/sys/class/tty/%s/device", device_name.c_str() );
if( device_name.compare(0,6,"ttyUSB") == 0 )
{
sys_device_path = dirname( dirname( realpath( sys_device_path ) ) );
if( path_exists( sys_device_path ) )
{
friendly_name = usb_sysfs_friendly_name( sys_device_path );
hardware_id = usb_sysfs_hw_string( sys_device_path );
}
}
else if( device_name.compare(0,6,"ttyACM") == 0 )
{
sys_device_path = dirname( realpath( sys_device_path ) );
if( path_exists( sys_device_path ) )
{
friendly_name = usb_sysfs_friendly_name( sys_device_path );
hardware_id = usb_sysfs_hw_string( sys_device_path );
}
}
else
{
// Try to read ID string of PCI device
string sys_id_path = sys_device_path + "/id";
if( path_exists( sys_id_path ) )
hardware_id = read_line( sys_id_path );
}
if( friendly_name.empty() )
friendly_name = device_name;
if( hardware_id.empty() )
hardware_id = "n/a";
vector<string> result;
result.push_back(friendly_name);
result.push_back(hardware_id);
return result;
}
string
read_line(const string& file)
{
ifstream ifs(file.c_str(), ifstream::in);
string line;
if(ifs)
{
getline(ifs, line);
}
return line;
}
string
format(const char* format, ...)
{
va_list ap;
size_t buffer_size_bytes = 256;
string result;
char* buffer = (char*)malloc(buffer_size_bytes);
if( buffer == NULL )
return result;
bool done = false;
unsigned int loop_count = 0;
while(!done)
{
va_start(ap, format);
int return_value = vsnprintf(buffer, buffer_size_bytes, format, ap);
if( return_value < 0 )
{
done = true;
}
else if( return_value >= buffer_size_bytes )
{
// Realloc and try again.
buffer_size_bytes = return_value + 1;
char* new_buffer_ptr = (char*)realloc(buffer, buffer_size_bytes);
if( new_buffer_ptr == NULL )
{
done = true;
}
else
{
buffer = new_buffer_ptr;
}
}
else
{
result = buffer;
done = true;
}
va_end(ap);
if( ++loop_count > 5 )
done = true;
}
free(buffer);
return result;
}
string
usb_sysfs_hw_string(const string& sysfs_path)
{
string serial_number = read_line( sysfs_path + "/serial" );
if( serial_number.length() > 0 )
{
serial_number = format( "SNR=%s", serial_number.c_str() );
}
string vid = read_line( sysfs_path + "/idVendor" );
string pid = read_line( sysfs_path + "/idProduct" );
return format("USB VID:PID=%s:%s %s", vid.c_str(), pid.c_str(), serial_number.c_str() );
}
vector<PortInfo>
serial::list_ports()
{
vector<PortInfo> results;
vector<string> search_globs;
search_globs.push_back("/dev/ttyACM*");
search_globs.push_back("/dev/ttyS*");
search_globs.push_back("/dev/ttyUSB*");
search_globs.push_back("/dev/tty.*");
search_globs.push_back("/dev/cu.*");
vector<string> devices_found = glob( search_globs );
vector<string>::iterator iter = devices_found.begin();
while( iter != devices_found.end() )
{
string device = *iter++;
vector<string> sysfs_info = get_sysfs_info( device );
string friendly_name = sysfs_info[0];
string hardware_id = sysfs_info[1];
PortInfo device_entry;
device_entry.port = device;
device_entry.description = friendly_name;
device_entry.hardware_id = hardware_id;
results.push_back( device_entry );
}
return results;
}
#endif // defined(__linux__)

View File

@@ -0,0 +1,286 @@
#if defined(__APPLE__)
#include <sys/param.h>
#include <stdint.h>
#include <CoreFoundation/CoreFoundation.h>
#include <IOKit/IOKitLib.h>
#include <IOKit/serial/IOSerialKeys.h>
#include <IOKit/IOBSD.h>
#include <iostream>
#include <string>
#include <vector>
#include "serial/serial.h"
using serial::PortInfo;
using std::string;
using std::vector;
#define HARDWARE_ID_STRING_LENGTH 128
string cfstring_to_string( CFStringRef cfstring );
string get_device_path( io_object_t& serial_port );
string get_class_name( io_object_t& obj );
io_registry_entry_t get_parent_iousb_device( io_object_t& serial_port );
string get_string_property( io_object_t& device, const char* property );
uint16_t get_int_property( io_object_t& device, const char* property );
string rtrim(const string& str);
string
cfstring_to_string( CFStringRef cfstring )
{
char cstring[MAXPATHLEN];
string result;
if( cfstring )
{
Boolean success = CFStringGetCString( cfstring,
cstring,
sizeof(cstring),
kCFStringEncodingASCII );
if( success )
result = cstring;
}
return result;
}
string
get_device_path( io_object_t& serial_port )
{
CFTypeRef callout_path;
string device_path;
callout_path = IORegistryEntryCreateCFProperty( serial_port,
CFSTR(kIOCalloutDeviceKey),
kCFAllocatorDefault,
0 );
if (callout_path)
{
if( CFGetTypeID(callout_path) == CFStringGetTypeID() )
device_path = cfstring_to_string( static_cast<CFStringRef>(callout_path) );
CFRelease(callout_path);
}
return device_path;
}
string
get_class_name( io_object_t& obj )
{
string result;
io_name_t class_name;
kern_return_t kern_result;
kern_result = IOObjectGetClass( obj, class_name );
if( kern_result == KERN_SUCCESS )
result = class_name;
return result;
}
io_registry_entry_t
get_parent_iousb_device( io_object_t& serial_port )
{
io_object_t device = serial_port;
io_registry_entry_t parent = 0;
io_registry_entry_t result = 0;
kern_return_t kern_result = KERN_FAILURE;
string name = get_class_name(device);
// Walk the IO Registry tree looking for this devices parent IOUSBDevice.
while( name != "IOUSBDevice" )
{
kern_result = IORegistryEntryGetParentEntry( device,
kIOServicePlane,
&parent );
if(kern_result != KERN_SUCCESS)
{
result = 0;
break;
}
device = parent;
name = get_class_name(device);
}
if(kern_result == KERN_SUCCESS)
result = device;
return result;
}
string
get_string_property( io_object_t& device, const char* property )
{
string property_name;
if( device )
{
CFStringRef property_as_cfstring = CFStringCreateWithCString (
kCFAllocatorDefault,
property,
kCFStringEncodingASCII );
CFTypeRef name_as_cfstring = IORegistryEntryCreateCFProperty(
device,
property_as_cfstring,
kCFAllocatorDefault,
0 );
if( name_as_cfstring )
{
if( CFGetTypeID(name_as_cfstring) == CFStringGetTypeID() )
property_name = cfstring_to_string( static_cast<CFStringRef>(name_as_cfstring) );
CFRelease(name_as_cfstring);
}
if(property_as_cfstring)
CFRelease(property_as_cfstring);
}
return property_name;
}
uint16_t
get_int_property( io_object_t& device, const char* property )
{
uint16_t result = 0;
if( device )
{
CFStringRef property_as_cfstring = CFStringCreateWithCString (
kCFAllocatorDefault,
property,
kCFStringEncodingASCII );
CFTypeRef number = IORegistryEntryCreateCFProperty( device,
property_as_cfstring,
kCFAllocatorDefault,
0 );
if(property_as_cfstring)
CFRelease(property_as_cfstring);
if( number )
{
if( CFGetTypeID(number) == CFNumberGetTypeID() )
{
bool success = CFNumberGetValue( static_cast<CFNumberRef>(number),
kCFNumberSInt16Type,
&result );
if( !success )
result = 0;
}
CFRelease(number);
}
}
return result;
}
string rtrim(const string& str)
{
string result = str;
string whitespace = " \t\f\v\n\r";
std::size_t found = result.find_last_not_of(whitespace);
if (found != std::string::npos)
result.erase(found+1);
else
result.clear();
return result;
}
vector<PortInfo>
serial::list_ports(void)
{
vector<PortInfo> devices_found;
CFMutableDictionaryRef classes_to_match;
io_iterator_t serial_port_iterator;
io_object_t serial_port;
mach_port_t master_port;
kern_return_t kern_result;
kern_result = IOMasterPort(MACH_PORT_NULL, &master_port);
if(kern_result != KERN_SUCCESS)
return devices_found;
classes_to_match = IOServiceMatching(kIOSerialBSDServiceValue);
if (classes_to_match == NULL)
return devices_found;
CFDictionarySetValue( classes_to_match,
CFSTR(kIOSerialBSDTypeKey),
CFSTR(kIOSerialBSDAllTypes) );
kern_result = IOServiceGetMatchingServices(master_port, classes_to_match, &serial_port_iterator);
if (KERN_SUCCESS != kern_result)
return devices_found;
while ( (serial_port = IOIteratorNext(serial_port_iterator)) )
{
string device_path = get_device_path( serial_port );
io_registry_entry_t parent = get_parent_iousb_device( serial_port );
IOObjectRelease(serial_port);
if( device_path.empty() )
continue;
PortInfo port_info;
port_info.port = device_path;
port_info.description = "n/a";
port_info.hardware_id = "n/a";
string device_name = rtrim( get_string_property( parent, "USB Product Name" ) );
string vendor_name = rtrim( get_string_property( parent, "USB Vendor Name") );
string description = rtrim( vendor_name + " " + device_name );
if( !description.empty() )
port_info.description = description;
string serial_number = rtrim(get_string_property( parent, "USB Serial Number" ) );
uint16_t vendor_id = get_int_property( parent, "idVendor" );
uint16_t product_id = get_int_property( parent, "idProduct" );
if( vendor_id && product_id )
{
char cstring[HARDWARE_ID_STRING_LENGTH];
if(serial_number.empty())
serial_number = "None";
int ret = snprintf( cstring, HARDWARE_ID_STRING_LENGTH, "USB VID:PID=%04x:%04x SNR=%s",
vendor_id,
product_id,
serial_number.c_str() );
if( (ret >= 0) && (ret < HARDWARE_ID_STRING_LENGTH) )
port_info.hardware_id = cstring;
}
devices_found.push_back(port_info);
}
IOObjectRelease(serial_port_iterator);
return devices_found;
}
#endif // defined(__APPLE__)

View File

@@ -0,0 +1,152 @@
#if defined(_WIN32)
/*
* Copyright (c) 2014 Craig Lilley <cralilley@gmail.com>
* This software is made available under the terms of the MIT licence.
* A copy of the licence can be obtained from:
* http://opensource.org/licenses/MIT
*/
#include "serial/serial.h"
#include <tchar.h>
#include <windows.h>
#include <setupapi.h>
#include <initguid.h>
#include <devguid.h>
#include <cstring>
using serial::PortInfo;
using std::vector;
using std::string;
static const DWORD port_name_max_length = 256;
static const DWORD friendly_name_max_length = 256;
static const DWORD hardware_id_max_length = 256;
// Convert a wide Unicode string to an UTF8 string
std::string utf8_encode(const std::wstring &wstr)
{
int size_needed = WideCharToMultiByte(CP_UTF8, 0, &wstr[0], (int)wstr.size(), NULL, 0, NULL, NULL);
std::string strTo( size_needed, 0 );
WideCharToMultiByte (CP_UTF8, 0, &wstr[0], (int)wstr.size(), &strTo[0], size_needed, NULL, NULL);
return strTo;
}
vector<PortInfo>
serial::list_ports()
{
vector<PortInfo> devices_found;
HDEVINFO device_info_set = SetupDiGetClassDevs(
(const GUID *) &GUID_DEVCLASS_PORTS,
NULL,
NULL,
DIGCF_PRESENT);
unsigned int device_info_set_index = 0;
SP_DEVINFO_DATA device_info_data;
device_info_data.cbSize = sizeof(SP_DEVINFO_DATA);
while(SetupDiEnumDeviceInfo(device_info_set, device_info_set_index, &device_info_data))
{
device_info_set_index++;
// Get port name
HKEY hkey = SetupDiOpenDevRegKey(
device_info_set,
&device_info_data,
DICS_FLAG_GLOBAL,
0,
DIREG_DEV,
KEY_READ);
TCHAR port_name[port_name_max_length];
DWORD port_name_length = port_name_max_length;
LONG return_code = RegQueryValueEx(
hkey,
_T("PortName"),
NULL,
NULL,
(LPBYTE)port_name,
&port_name_length);
RegCloseKey(hkey);
if(return_code != EXIT_SUCCESS)
continue;
if(port_name_length > 0 && port_name_length <= port_name_max_length)
port_name[port_name_length-1] = '\0';
else
port_name[0] = '\0';
// Ignore parallel ports
if(_tcsstr(port_name, _T("LPT")) != NULL)
continue;
// Get port friendly name
TCHAR friendly_name[friendly_name_max_length];
DWORD friendly_name_actual_length = 0;
BOOL got_friendly_name = SetupDiGetDeviceRegistryProperty(
device_info_set,
&device_info_data,
SPDRP_FRIENDLYNAME,
NULL,
(PBYTE)friendly_name,
friendly_name_max_length,
&friendly_name_actual_length);
if(got_friendly_name == TRUE && friendly_name_actual_length > 0)
friendly_name[friendly_name_actual_length-1] = '\0';
else
friendly_name[0] = '\0';
// Get hardware ID
TCHAR hardware_id[hardware_id_max_length];
DWORD hardware_id_actual_length = 0;
BOOL got_hardware_id = SetupDiGetDeviceRegistryProperty(
device_info_set,
&device_info_data,
SPDRP_HARDWAREID,
NULL,
(PBYTE)hardware_id,
hardware_id_max_length,
&hardware_id_actual_length);
if(got_hardware_id == TRUE && hardware_id_actual_length > 0)
hardware_id[hardware_id_actual_length-1] = '\0';
else
hardware_id[0] = '\0';
#ifdef UNICODE
std::string portName = utf8_encode(port_name);
std::string friendlyName = utf8_encode(friendly_name);
std::string hardwareId = utf8_encode(hardware_id);
#else
std::string portName = port_name;
std::string friendlyName = friendly_name;
std::string hardwareId = hardware_id;
#endif
PortInfo port_entry;
port_entry.port = portName;
port_entry.description = friendlyName;
port_entry.hardware_id = hardwareId;
devices_found.push_back(port_entry);
}
SetupDiDestroyDeviceInfoList(device_info_set);
return devices_found;
}
#endif // #if defined(_WIN32)

File diff suppressed because it is too large Load Diff

View File

@@ -0,0 +1,640 @@
#if defined(_WIN32)
/* Copyright 2012 William Woodall and John Harrison */
#include <sstream>
#include "serial/impl/win.h"
using std::string;
using std::wstring;
using std::stringstream;
using std::invalid_argument;
using serial::Serial;
using serial::Timeout;
using serial::bytesize_t;
using serial::parity_t;
using serial::stopbits_t;
using serial::flowcontrol_t;
using serial::SerialException;
using serial::PortNotOpenedException;
using serial::IOException;
inline wstring
_prefix_port_if_needed(const wstring &input)
{
static wstring windows_com_port_prefix = L"\\\\.\\";
if (input.compare(windows_com_port_prefix) != 0)
{
return windows_com_port_prefix + input;
}
return input;
}
Serial::SerialImpl::SerialImpl (const string &port, unsigned long baudrate,
bytesize_t bytesize,
parity_t parity, stopbits_t stopbits,
flowcontrol_t flowcontrol)
: port_ (port.begin(), port.end()), fd_ (INVALID_HANDLE_VALUE), is_open_ (false),
baudrate_ (baudrate), parity_ (parity),
bytesize_ (bytesize), stopbits_ (stopbits), flowcontrol_ (flowcontrol)
{
if (port_.empty () == false)
open ();
read_mutex = CreateMutex(NULL, false, NULL);
write_mutex = CreateMutex(NULL, false, NULL);
}
Serial::SerialImpl::~SerialImpl ()
{
this->close();
CloseHandle(read_mutex);
CloseHandle(write_mutex);
}
void
Serial::SerialImpl::open ()
{
if (port_.empty ()) {
throw invalid_argument ("Empty port is invalid.");
}
if (is_open_ == true) {
throw SerialException ("Serial port already open.");
}
// See: https://github.com/wjwwood/serial/issues/84
wstring port_with_prefix = _prefix_port_if_needed(port_);
LPCWSTR lp_port = port_with_prefix.c_str();
fd_ = CreateFileW(lp_port,
GENERIC_READ | GENERIC_WRITE,
0,
0,
OPEN_EXISTING,
FILE_ATTRIBUTE_NORMAL,
0);
if (fd_ == INVALID_HANDLE_VALUE) {
DWORD errno_ = GetLastError();
stringstream ss;
switch (errno_) {
case ERROR_FILE_NOT_FOUND:
// Use this->getPort to convert to a std::string
ss << "Specified port, " << this->getPort() << ", does not exist.";
THROW (IOException, ss.str().c_str());
default:
ss << "Unknown error opening the serial port: " << errno;
THROW (IOException, ss.str().c_str());
}
}
reconfigurePort();
is_open_ = true;
}
void
Serial::SerialImpl::reconfigurePort ()
{
if (fd_ == INVALID_HANDLE_VALUE) {
// Can only operate on a valid file descriptor
THROW (IOException, "Invalid file descriptor, is the serial port open?");
}
DCB dcbSerialParams = {0};
dcbSerialParams.DCBlength=sizeof(dcbSerialParams);
if (!GetCommState(fd_, &dcbSerialParams)) {
//error getting state
THROW (IOException, "Error getting the serial port state.");
}
// setup baud rate
switch (baudrate_) {
#ifdef CBR_0
case 0: dcbSerialParams.BaudRate = CBR_0; break;
#endif
#ifdef CBR_50
case 50: dcbSerialParams.BaudRate = CBR_50; break;
#endif
#ifdef CBR_75
case 75: dcbSerialParams.BaudRate = CBR_75; break;
#endif
#ifdef CBR_110
case 110: dcbSerialParams.BaudRate = CBR_110; break;
#endif
#ifdef CBR_134
case 134: dcbSerialParams.BaudRate = CBR_134; break;
#endif
#ifdef CBR_150
case 150: dcbSerialParams.BaudRate = CBR_150; break;
#endif
#ifdef CBR_200
case 200: dcbSerialParams.BaudRate = CBR_200; break;
#endif
#ifdef CBR_300
case 300: dcbSerialParams.BaudRate = CBR_300; break;
#endif
#ifdef CBR_600
case 600: dcbSerialParams.BaudRate = CBR_600; break;
#endif
#ifdef CBR_1200
case 1200: dcbSerialParams.BaudRate = CBR_1200; break;
#endif
#ifdef CBR_1800
case 1800: dcbSerialParams.BaudRate = CBR_1800; break;
#endif
#ifdef CBR_2400
case 2400: dcbSerialParams.BaudRate = CBR_2400; break;
#endif
#ifdef CBR_4800
case 4800: dcbSerialParams.BaudRate = CBR_4800; break;
#endif
#ifdef CBR_7200
case 7200: dcbSerialParams.BaudRate = CBR_7200; break;
#endif
#ifdef CBR_9600
case 9600: dcbSerialParams.BaudRate = CBR_9600; break;
#endif
#ifdef CBR_14400
case 14400: dcbSerialParams.BaudRate = CBR_14400; break;
#endif
#ifdef CBR_19200
case 19200: dcbSerialParams.BaudRate = CBR_19200; break;
#endif
#ifdef CBR_28800
case 28800: dcbSerialParams.BaudRate = CBR_28800; break;
#endif
#ifdef CBR_57600
case 57600: dcbSerialParams.BaudRate = CBR_57600; break;
#endif
#ifdef CBR_76800
case 76800: dcbSerialParams.BaudRate = CBR_76800; break;
#endif
#ifdef CBR_38400
case 38400: dcbSerialParams.BaudRate = CBR_38400; break;
#endif
#ifdef CBR_115200
case 115200: dcbSerialParams.BaudRate = CBR_115200; break;
#endif
#ifdef CBR_128000
case 128000: dcbSerialParams.BaudRate = CBR_128000; break;
#endif
#ifdef CBR_153600
case 153600: dcbSerialParams.BaudRate = CBR_153600; break;
#endif
#ifdef CBR_230400
case 230400: dcbSerialParams.BaudRate = CBR_230400; break;
#endif
#ifdef CBR_256000
case 256000: dcbSerialParams.BaudRate = CBR_256000; break;
#endif
#ifdef CBR_460800
case 460800: dcbSerialParams.BaudRate = CBR_460800; break;
#endif
#ifdef CBR_921600
case 921600: dcbSerialParams.BaudRate = CBR_921600; break;
#endif
default:
// Try to blindly assign it
dcbSerialParams.BaudRate = baudrate_;
}
// setup char len
if (bytesize_ == eightbits)
dcbSerialParams.ByteSize = 8;
else if (bytesize_ == sevenbits)
dcbSerialParams.ByteSize = 7;
else if (bytesize_ == sixbits)
dcbSerialParams.ByteSize = 6;
else if (bytesize_ == fivebits)
dcbSerialParams.ByteSize = 5;
else
throw invalid_argument ("invalid char len");
// setup stopbits
if (stopbits_ == stopbits_one)
dcbSerialParams.StopBits = ONESTOPBIT;
else if (stopbits_ == stopbits_one_point_five)
dcbSerialParams.StopBits = ONE5STOPBITS;
else if (stopbits_ == stopbits_two)
dcbSerialParams.StopBits = TWOSTOPBITS;
else
throw invalid_argument ("invalid stop bit");
// setup parity
if (parity_ == parity_none) {
dcbSerialParams.Parity = NOPARITY;
} else if (parity_ == parity_even) {
dcbSerialParams.Parity = EVENPARITY;
} else if (parity_ == parity_odd) {
dcbSerialParams.Parity = ODDPARITY;
} else if (parity_ == parity_mark) {
dcbSerialParams.Parity = MARKPARITY;
} else if (parity_ == parity_space) {
dcbSerialParams.Parity = SPACEPARITY;
} else {
throw invalid_argument ("invalid parity");
}
// setup flowcontrol
if (flowcontrol_ == flowcontrol_none) {
dcbSerialParams.fOutxCtsFlow = false;
dcbSerialParams.fRtsControl = 0x00;
dcbSerialParams.fOutX = false;
dcbSerialParams.fInX = false;
}
if (flowcontrol_ == flowcontrol_software) {
dcbSerialParams.fOutxCtsFlow = false;
dcbSerialParams.fRtsControl = 0x00;
dcbSerialParams.fOutX = true;
dcbSerialParams.fInX = true;
}
if (flowcontrol_ == flowcontrol_hardware) {
dcbSerialParams.fOutxCtsFlow = true;
dcbSerialParams.fRtsControl = 0x03;
dcbSerialParams.fOutX = false;
dcbSerialParams.fInX = false;
}
// activate settings
if (!SetCommState(fd_, &dcbSerialParams)){
CloseHandle(fd_);
THROW (IOException, "Error setting serial port settings.");
}
// Setup timeouts
COMMTIMEOUTS timeouts = {0};
timeouts.ReadIntervalTimeout = timeout_.inter_byte_timeout;
timeouts.ReadTotalTimeoutConstant = timeout_.read_timeout_constant;
timeouts.ReadTotalTimeoutMultiplier = timeout_.read_timeout_multiplier;
timeouts.WriteTotalTimeoutConstant = timeout_.write_timeout_constant;
timeouts.WriteTotalTimeoutMultiplier = timeout_.write_timeout_multiplier;
if (!SetCommTimeouts(fd_, &timeouts)) {
THROW (IOException, "Error setting timeouts.");
}
}
void
Serial::SerialImpl::close ()
{
if (is_open_ == true) {
if (fd_ != INVALID_HANDLE_VALUE) {
int ret;
ret = CloseHandle(fd_);
if (ret == 0) {
stringstream ss;
ss << "Error while closing serial port: " << GetLastError();
THROW (IOException, ss.str().c_str());
} else {
fd_ = INVALID_HANDLE_VALUE;
}
}
is_open_ = false;
}
}
bool
Serial::SerialImpl::isOpen () const
{
return is_open_;
}
size_t
Serial::SerialImpl::available ()
{
if (!is_open_) {
return 0;
}
COMSTAT cs;
if (!ClearCommError(fd_, NULL, &cs)) {
stringstream ss;
ss << "Error while checking status of the serial port: " << GetLastError();
THROW (IOException, ss.str().c_str());
}
return static_cast<size_t>(cs.cbInQue);
}
bool
Serial::SerialImpl::waitReadable (uint32_t /*timeout*/)
{
THROW (IOException, "waitReadable is not implemented on Windows.");
return false;
}
void
Serial::SerialImpl::waitByteTimes (size_t /*count*/)
{
THROW (IOException, "waitByteTimes is not implemented on Windows.");
}
size_t
Serial::SerialImpl::read (uint8_t *buf, size_t size)
{
if (!is_open_) {
throw PortNotOpenedException ("Serial::read");
}
DWORD bytes_read;
if (!ReadFile(fd_, buf, static_cast<DWORD>(size), &bytes_read, NULL)) {
stringstream ss;
ss << "Error while reading from the serial port: " << GetLastError();
THROW (IOException, ss.str().c_str());
}
return (size_t) (bytes_read);
}
size_t
Serial::SerialImpl::write (const uint8_t *data, size_t length)
{
if (is_open_ == false) {
throw PortNotOpenedException ("Serial::write");
}
DWORD bytes_written;
if (!WriteFile(fd_, data, static_cast<DWORD>(length), &bytes_written, NULL)) {
stringstream ss;
ss << "Error while writing to the serial port: " << GetLastError();
THROW (IOException, ss.str().c_str());
}
return (size_t) (bytes_written);
}
void
Serial::SerialImpl::setPort (const string &port)
{
port_ = wstring(port.begin(), port.end());
}
string
Serial::SerialImpl::getPort () const
{
return string(port_.begin(), port_.end());
}
void
Serial::SerialImpl::setTimeout (serial::Timeout &timeout)
{
timeout_ = timeout;
if (is_open_) {
reconfigurePort ();
}
}
serial::Timeout
Serial::SerialImpl::getTimeout () const
{
return timeout_;
}
void
Serial::SerialImpl::setBaudrate (unsigned long baudrate)
{
baudrate_ = baudrate;
if (is_open_) {
reconfigurePort ();
}
}
unsigned long
Serial::SerialImpl::getBaudrate () const
{
return baudrate_;
}
void
Serial::SerialImpl::setBytesize (serial::bytesize_t bytesize)
{
bytesize_ = bytesize;
if (is_open_) {
reconfigurePort ();
}
}
serial::bytesize_t
Serial::SerialImpl::getBytesize () const
{
return bytesize_;
}
void
Serial::SerialImpl::setParity (serial::parity_t parity)
{
parity_ = parity;
if (is_open_) {
reconfigurePort ();
}
}
serial::parity_t
Serial::SerialImpl::getParity () const
{
return parity_;
}
void
Serial::SerialImpl::setStopbits (serial::stopbits_t stopbits)
{
stopbits_ = stopbits;
if (is_open_) {
reconfigurePort ();
}
}
serial::stopbits_t
Serial::SerialImpl::getStopbits () const
{
return stopbits_;
}
void
Serial::SerialImpl::setFlowcontrol (serial::flowcontrol_t flowcontrol)
{
flowcontrol_ = flowcontrol;
if (is_open_) {
reconfigurePort ();
}
}
serial::flowcontrol_t
Serial::SerialImpl::getFlowcontrol () const
{
return flowcontrol_;
}
void
Serial::SerialImpl::flush ()
{
if (is_open_ == false) {
throw PortNotOpenedException ("Serial::flush");
}
FlushFileBuffers (fd_);
}
void
Serial::SerialImpl::flushInput ()
{
THROW (IOException, "flushInput is not supported on Windows.");
}
void
Serial::SerialImpl::flushOutput ()
{
THROW (IOException, "flushOutput is not supported on Windows.");
}
void
Serial::SerialImpl::sendBreak (int /*duration*/)
{
THROW (IOException, "sendBreak is not supported on Windows.");
}
void
Serial::SerialImpl::setBreak (bool level)
{
if (is_open_ == false) {
throw PortNotOpenedException ("Serial::setBreak");
}
if (level) {
EscapeCommFunction (fd_, SETBREAK);
} else {
EscapeCommFunction (fd_, CLRBREAK);
}
}
void
Serial::SerialImpl::setRTS (bool level)
{
if (is_open_ == false) {
throw PortNotOpenedException ("Serial::setRTS");
}
if (level) {
EscapeCommFunction (fd_, SETRTS);
} else {
EscapeCommFunction (fd_, CLRRTS);
}
}
void
Serial::SerialImpl::setDTR (bool level)
{
if (is_open_ == false) {
throw PortNotOpenedException ("Serial::setDTR");
}
if (level) {
EscapeCommFunction (fd_, SETDTR);
} else {
EscapeCommFunction (fd_, CLRDTR);
}
}
bool
Serial::SerialImpl::waitForChange ()
{
if (is_open_ == false) {
throw PortNotOpenedException ("Serial::waitForChange");
}
DWORD dwCommEvent;
if (!SetCommMask(fd_, EV_CTS | EV_DSR | EV_RING | EV_RLSD)) {
// Error setting communications mask
return false;
}
if (!WaitCommEvent(fd_, &dwCommEvent, NULL)) {
// An error occurred waiting for the event.
return false;
} else {
// Event has occurred.
return true;
}
}
bool
Serial::SerialImpl::getCTS ()
{
if (is_open_ == false) {
throw PortNotOpenedException ("Serial::getCTS");
}
DWORD dwModemStatus;
if (!GetCommModemStatus(fd_, &dwModemStatus)) {
THROW (IOException, "Error getting the status of the CTS line.");
}
return (MS_CTS_ON & dwModemStatus) != 0;
}
bool
Serial::SerialImpl::getDSR ()
{
if (is_open_ == false) {
throw PortNotOpenedException ("Serial::getDSR");
}
DWORD dwModemStatus;
if (!GetCommModemStatus(fd_, &dwModemStatus)) {
THROW (IOException, "Error getting the status of the DSR line.");
}
return (MS_DSR_ON & dwModemStatus) != 0;
}
bool
Serial::SerialImpl::getRI()
{
if (is_open_ == false) {
throw PortNotOpenedException ("Serial::getRI");
}
DWORD dwModemStatus;
if (!GetCommModemStatus(fd_, &dwModemStatus)) {
THROW (IOException, "Error getting the status of the RI line.");
}
return (MS_RING_ON & dwModemStatus) != 0;
}
bool
Serial::SerialImpl::getCD()
{
if (is_open_ == false) {
throw PortNotOpenedException ("Serial::getCD");
}
DWORD dwModemStatus;
if (!GetCommModemStatus(fd_, &dwModemStatus)) {
// Error in GetCommModemStatus;
THROW (IOException, "Error getting the status of the CD line.");
}
return (MS_RLSD_ON & dwModemStatus) != 0;
}
void
Serial::SerialImpl::readLock()
{
if (WaitForSingleObject(read_mutex, INFINITE) != WAIT_OBJECT_0) {
THROW (IOException, "Error claiming read mutex.");
}
}
void
Serial::SerialImpl::readUnlock()
{
if (!ReleaseMutex(read_mutex)) {
THROW (IOException, "Error releasing read mutex.");
}
}
void
Serial::SerialImpl::writeLock()
{
if (WaitForSingleObject(write_mutex, INFINITE) != WAIT_OBJECT_0) {
THROW (IOException, "Error claiming write mutex.");
}
}
void
Serial::SerialImpl::writeUnlock()
{
if (!ReleaseMutex(write_mutex)) {
THROW (IOException, "Error releasing write mutex.");
}
}
#endif // #if defined(_WIN32)

View File

@@ -0,0 +1,414 @@
/* Copyright 2012 William Woodall and John Harrison */
#include <algorithm>
#if !defined(_WIN32) && !defined(__OpenBSD__) && !defined(__FreeBSD__)
# include <alloca.h>
#endif
#if defined (__MINGW32__)
# define alloca __builtin_alloca
#endif
#include "serial/serial.h"
#ifdef _WIN32
#include "serial/impl/win.h"
#else
#include "serial/impl/unix.h"
#endif
using std::invalid_argument;
using std::min;
using std::numeric_limits;
using std::vector;
using std::size_t;
using std::string;
using serial::Serial;
using serial::SerialException;
using serial::IOException;
using serial::bytesize_t;
using serial::parity_t;
using serial::stopbits_t;
using serial::flowcontrol_t;
class Serial::ScopedReadLock {
public:
ScopedReadLock(SerialImpl *pimpl) : pimpl_(pimpl) {
this->pimpl_->readLock();
}
~ScopedReadLock() {
this->pimpl_->readUnlock();
}
private:
// Disable copy constructors
ScopedReadLock(const ScopedReadLock&);
const ScopedReadLock& operator=(ScopedReadLock);
SerialImpl *pimpl_;
};
class Serial::ScopedWriteLock {
public:
ScopedWriteLock(SerialImpl *pimpl) : pimpl_(pimpl) {
this->pimpl_->writeLock();
}
~ScopedWriteLock() {
this->pimpl_->writeUnlock();
}
private:
// Disable copy constructors
ScopedWriteLock(const ScopedWriteLock&);
const ScopedWriteLock& operator=(ScopedWriteLock);
SerialImpl *pimpl_;
};
Serial::Serial (const string &port, uint32_t baudrate, serial::Timeout timeout,
bytesize_t bytesize, parity_t parity, stopbits_t stopbits,
flowcontrol_t flowcontrol)
: pimpl_(new SerialImpl (port, baudrate, bytesize, parity,
stopbits, flowcontrol))
{
pimpl_->setTimeout(timeout);
}
Serial::~Serial ()
{
delete pimpl_;
}
void
Serial::open ()
{
pimpl_->open ();
}
void
Serial::close ()
{
pimpl_->close ();
}
bool
Serial::isOpen () const
{
return pimpl_->isOpen ();
}
size_t
Serial::available ()
{
return pimpl_->available ();
}
bool
Serial::waitReadable ()
{
serial::Timeout timeout(pimpl_->getTimeout ());
return pimpl_->waitReadable(timeout.read_timeout_constant);
}
void
Serial::waitByteTimes (size_t count)
{
pimpl_->waitByteTimes(count);
}
size_t
Serial::read_ (uint8_t *buffer, size_t size)
{
return this->pimpl_->read (buffer, size);
}
size_t
Serial::read (uint8_t *buffer, size_t size)
{
ScopedReadLock lock(this->pimpl_);
return this->pimpl_->read (buffer, size);
}
size_t
Serial::read (std::vector<uint8_t> &buffer, size_t size)
{
ScopedReadLock lock(this->pimpl_);
uint8_t *buffer_ = new uint8_t[size];
size_t bytes_read = this->pimpl_->read (buffer_, size);
buffer.insert (buffer.end (), buffer_, buffer_+bytes_read);
delete[] buffer_;
return bytes_read;
}
size_t
Serial::read (std::string &buffer, size_t size)
{
ScopedReadLock lock(this->pimpl_);
uint8_t *buffer_ = new uint8_t[size];
size_t bytes_read = this->pimpl_->read (buffer_, size);
buffer.append (reinterpret_cast<const char*>(buffer_), bytes_read);
delete[] buffer_;
return bytes_read;
}
string
Serial::read (size_t size)
{
std::string buffer;
this->read (buffer, size);
return buffer;
}
size_t
Serial::readline (string &buffer, size_t size, string eol)
{
ScopedReadLock lock(this->pimpl_);
size_t eol_len = eol.length ();
uint8_t *buffer_ = static_cast<uint8_t*>
(alloca (size * sizeof (uint8_t)));
size_t read_so_far = 0;
while (true)
{
size_t bytes_read = this->read_ (buffer_ + read_so_far, 1);
read_so_far += bytes_read;
if (bytes_read == 0) {
break; // Timeout occured on reading 1 byte
}
if (string (reinterpret_cast<const char*>
(buffer_ + read_so_far - eol_len), eol_len) == eol) {
break; // EOL found
}
if (read_so_far == size) {
break; // Reached the maximum read length
}
}
buffer.append(reinterpret_cast<const char*> (buffer_), read_so_far);
return read_so_far;
}
string
Serial::readline (size_t size, string eol)
{
std::string buffer;
this->readline (buffer, size, eol);
return buffer;
}
vector<string>
Serial::readlines (size_t size, string eol)
{
ScopedReadLock lock(this->pimpl_);
std::vector<std::string> lines;
size_t eol_len = eol.length ();
uint8_t *buffer_ = static_cast<uint8_t*>
(alloca (size * sizeof (uint8_t)));
size_t read_so_far = 0;
size_t start_of_line = 0;
while (read_so_far < size) {
size_t bytes_read = this->read_ (buffer_+read_so_far, 1);
read_so_far += bytes_read;
if (bytes_read == 0) {
if (start_of_line != read_so_far) {
lines.push_back (
string (reinterpret_cast<const char*> (buffer_ + start_of_line),
read_so_far - start_of_line));
}
break; // Timeout occured on reading 1 byte
}
if (string (reinterpret_cast<const char*>
(buffer_ + read_so_far - eol_len), eol_len) == eol) {
// EOL found
lines.push_back(
string(reinterpret_cast<const char*> (buffer_ + start_of_line),
read_so_far - start_of_line));
start_of_line = read_so_far;
}
if (read_so_far == size) {
if (start_of_line != read_so_far) {
lines.push_back(
string(reinterpret_cast<const char*> (buffer_ + start_of_line),
read_so_far - start_of_line));
}
break; // Reached the maximum read length
}
}
return lines;
}
size_t
Serial::write (const string &data)
{
ScopedWriteLock lock(this->pimpl_);
return this->write_ (reinterpret_cast<const uint8_t*>(data.c_str()),
data.length());
}
size_t
Serial::write (const std::vector<uint8_t> &data)
{
ScopedWriteLock lock(this->pimpl_);
return this->write_ (&data[0], data.size());
}
size_t
Serial::write (const uint8_t *data, size_t size)
{
ScopedWriteLock lock(this->pimpl_);
return this->write_(data, size);
}
size_t
Serial::write_ (const uint8_t *data, size_t length)
{
return pimpl_->write (data, length);
}
void
Serial::setPort (const string &port)
{
ScopedReadLock rlock(this->pimpl_);
ScopedWriteLock wlock(this->pimpl_);
bool was_open = pimpl_->isOpen ();
if (was_open) close();
pimpl_->setPort (port);
if (was_open) open ();
}
string
Serial::getPort () const
{
return pimpl_->getPort ();
}
void
Serial::setTimeout (serial::Timeout &timeout)
{
pimpl_->setTimeout (timeout);
}
serial::Timeout
Serial::getTimeout () const {
return pimpl_->getTimeout ();
}
void
Serial::setBaudrate (uint32_t baudrate)
{
pimpl_->setBaudrate (baudrate);
}
uint32_t
Serial::getBaudrate () const
{
return uint32_t(pimpl_->getBaudrate ());
}
void
Serial::setBytesize (bytesize_t bytesize)
{
pimpl_->setBytesize (bytesize);
}
bytesize_t
Serial::getBytesize () const
{
return pimpl_->getBytesize ();
}
void
Serial::setParity (parity_t parity)
{
pimpl_->setParity (parity);
}
parity_t
Serial::getParity () const
{
return pimpl_->getParity ();
}
void
Serial::setStopbits (stopbits_t stopbits)
{
pimpl_->setStopbits (stopbits);
}
stopbits_t
Serial::getStopbits () const
{
return pimpl_->getStopbits ();
}
void
Serial::setFlowcontrol (flowcontrol_t flowcontrol)
{
pimpl_->setFlowcontrol (flowcontrol);
}
flowcontrol_t
Serial::getFlowcontrol () const
{
return pimpl_->getFlowcontrol ();
}
void Serial::flush ()
{
ScopedReadLock rlock(this->pimpl_);
ScopedWriteLock wlock(this->pimpl_);
pimpl_->flush ();
}
void Serial::flushInput ()
{
ScopedReadLock lock(this->pimpl_);
pimpl_->flushInput ();
}
void Serial::flushOutput ()
{
ScopedWriteLock lock(this->pimpl_);
pimpl_->flushOutput ();
}
void Serial::sendBreak (int duration)
{
pimpl_->sendBreak (duration);
}
void Serial::setBreak (bool level)
{
pimpl_->setBreak (level);
}
void Serial::setRTS (bool level)
{
pimpl_->setRTS (level);
}
void Serial::setDTR (bool level)
{
pimpl_->setDTR (level);
}
bool Serial::waitForChange()
{
return pimpl_->waitForChange();
}
bool Serial::getCTS ()
{
return pimpl_->getCTS ();
}
bool Serial::getDSR ()
{
return pimpl_->getDSR ();
}
bool Serial::getRI ()
{
return pimpl_->getRI ();
}
bool Serial::getCD ()
{
return pimpl_->getCD ();
}

View File

@@ -1,19 +1,73 @@
#include "TinyAudioExample.h"
#include "../CommonInterfaces/CommonExampleInterface.h"
#include "../CommonInterfaces/CommonGUIHelperInterface.h"
#include "Bullet3Common/b3AlignedObjectArray.h"
#include "Bullet3Common/b3HashMap.h"
#include "RtAudio.h"
#include "b3AudioListener.h"
#include "b3SoundEngine.h"
#include "b3SoundSource.h"
#include <string>
///very basic hashable string implementation, compatible with b3HashMap
struct MyHashString
{
std::string m_string;
unsigned int m_hash;
B3_FORCE_INLINE unsigned int getHash()const
{
return m_hash;
}
MyHashString(const char* name)
:m_string(name)
{
/* magic numbers from http://www.isthe.com/chongo/tech/comp/fnv/ */
static const unsigned int InitialFNV = 2166136261u;
static const unsigned int FNVMultiple = 16777619u;
/* Fowler / Noll / Vo (FNV) Hash */
unsigned int hash = InitialFNV;
for(int i = 0; m_string[i]; i++)
{
hash = hash ^ (m_string[i]); /* xor the low 8 bits */
hash = hash * FNVMultiple; /* multiply by the magic number */
}
m_hash = hash;
}
bool equals(const MyHashString& other) const
{
return (m_string == other.m_string);
}
};
double base_frequency = 440.0;
double base_pitch = 69.0;
double MidiPitch2Frequency(double incoming_note) {
return base_frequency * pow (2.0, (incoming_note - base_pitch) / 12.0);
}
double FrequencytoMidiPitch(double incoming_frequency) {
return base_pitch + (12.0 * log(incoming_frequency / base_frequency) / log(2));
}
class TinyAudioExample : public CommonExampleInterface
{
b3AudioListener m_listener;
b3SoundSource m_soundA;
RtAudio m_dac;
GUIHelperInterface* m_guiHelper;
int m_soundIndexA;
b3SoundEngine m_soundEngine;
int m_wavId;
b3HashMap<MyHashString,int> m_keyToSoundSource;
public:
TinyAudioExample(struct GUIHelperInterface* helper)
:m_guiHelper(helper)
@@ -26,35 +80,19 @@ public:
virtual void initPhysics()
{
m_soundIndexA = m_listener.addSoundSource(&m_soundA);
RtAudioFormat format = ( sizeof(double) == 8 ) ? RTAUDIO_FLOAT64 : RTAUDIO_FLOAT32;
RtAudio::StreamParameters parameters;
parameters.deviceId = 1;// dac.getDefaultOutputDevice();
parameters.nChannels = 2;
int numSoundSources = 32;
bool useRealTimeDac = true;
// The default real-time audio input and output buffer size. If
// clicks are occuring in the input and/or output sound stream, a
// larger buffer size may help. Larger buffer sizes, however, produce
// more latency.
const unsigned int RT_BUFFER_SIZE = 512;
unsigned int bufferFrames = RT_BUFFER_SIZE;
int sampleRate = m_listener.getSampleRate();
m_dac.openStream( &parameters, NULL, format, (unsigned int)sampleRate, &bufferFrames, &b3AudioListener::tick,
(void *)m_listener.getTickData());
// Install an interrupt handler function.
// (void) signal( SIGINT, finish );
m_dac.startStream();
m_soundEngine.init(numSoundSources, useRealTimeDac);
m_wavId = m_soundEngine.loadWavFile("wav/xylophone.rosewood.ff.C5B5_1.wav");
int sampleRate = m_soundEngine.getSampleRate();
}
virtual void exitPhysics()
{
m_dac.closeStream();
m_listener.removeSoundSource(m_soundIndexA);
m_soundEngine.exit();
}
virtual void renderScene()
@@ -76,8 +114,81 @@ public:
{
return false;
}
virtual bool keyboardCallback(int key, int state)
{
if (key>='a' && key<='z')
{
char keyStr[2];
keyStr[0] = (char)key;
keyStr[1] = 0;
MyHashString hs (keyStr);
if (state)
{
int soundSourceIndex = m_soundEngine.getAvailableSoundSource();
if (soundSourceIndex>=0)
{
int note = key-(97-58);
double freq = MidiPitch2Frequency(note);
b3SoundMessage msg;
msg.m_type = B3_SOUND_SOURCE_SINE_OSCILLATOR;
msg.m_frequency = freq;
msg.m_amplitude = 1;
msg.m_type = B3_SOUND_SOURCE_WAV_FILE;
msg.m_wavId = m_wavId;
msg.m_attackRate = 1;
msg.m_sustainLevel = 1;
msg.m_releaseRate = 0.001;
m_soundEngine.startSound(soundSourceIndex, msg);
m_keyToSoundSource.insert(hs,soundSourceIndex);
//printf("soundSourceIndex:%d\n", soundSourceIndex);
#if 0
b3SoundSource* soundSource = this->m_soundSourcesPool[soundSourceIndex];
soundSource->setOscillatorFrequency(0, freq );
soundSource->setOscillatorFrequency(1, freq );
soundSource->startSound();
{
int* soundSourceIndexPtr = m_keyToSoundSource[hs];
if (soundSourceIndexPtr)
{
int newIndex = *soundSourceIndexPtr;
printf("just inserted: %d\n", newIndex);
}
}
#endif
}
} else
{
int* soundSourceIndexPtr = m_keyToSoundSource[hs];
if (soundSourceIndexPtr)
{
int soundSourceIndex = *soundSourceIndexPtr;
//printf("releaseSound: %d\n", soundSourceIndex);
m_soundEngine.releaseSound(soundSourceIndex);
}
#if 0
if (soundSourceIndex>=0)
{
printf("releasing %d\n", soundSourceIndex);
b3SoundSource* soundSource = this->m_soundSourcesPool[soundSourceIndex];
soundSource->stopSound();
}
}
#endif
}
}
return false;
}

View File

@@ -0,0 +1,112 @@
#include "b3ADSR.h"
//ADSR mostly copied/reimplemented from Stk, see
//http://github.com/thestk/stk
//! ADSR envelope states.
enum
{
ADSR_ATTACK, /*!< Attack */
ADSR_DECAY, /*!< Decay */
ADSR_SUSTAIN, /*!< Sustain */
ADSR_RELEASE, /*!< Release */
ADSR_IDLE /*!< Before attack / after release */
};
b3ADSR::b3ADSR()
{
m_target = 0.0;
m_value = 0.0;
m_attackRate = 0.001;
m_decayRate = 0.00001;
m_releaseRate = 0.0005;
m_sustainLevel = 0.5;
m_state = ADSR_IDLE;
m_autoKeyOff = false;
}
b3ADSR::~b3ADSR()
{
}
double b3ADSR::tick()
{
switch (m_state)
{
case ADSR_ATTACK:
m_value += m_attackRate;
if (m_value >= m_target)
{
m_value = m_target;
m_target = m_sustainLevel;
m_state = ADSR_DECAY;
}
break;
case ADSR_DECAY:
if (m_value > m_sustainLevel)
{
m_value -= m_decayRate;
if (m_value <= m_sustainLevel)
{
m_value = m_sustainLevel;
m_state = ADSR_SUSTAIN;
if (m_autoKeyOff)
{
keyOff();
}
}
}
else
{
m_value += m_decayRate; // attack target < sustain level
if (m_value >= m_sustainLevel)
{
m_value = m_sustainLevel;
m_state = ADSR_SUSTAIN;
if (m_autoKeyOff)
{
keyOff();
}
}
}
break;
case ADSR_RELEASE:
m_value -= m_releaseRate;
if (m_value <= 0.0)
{
m_value = 0.0;
m_state = ADSR_IDLE;
}
}
return m_value;
}
bool b3ADSR::isIdle() const
{
return m_state == ADSR_IDLE;
}
void b3ADSR::keyOn(bool autoKeyOff)
{
m_autoKeyOff = autoKeyOff;
if (m_target <= 0.0)
m_target = 1.0;
if (m_attackRate==1)
{
m_value = 1.0;
}
m_state = ADSR_ATTACK;
}
void b3ADSR::keyOff()
{
m_autoKeyOff = false;
m_target = 0.0;
m_state = ADSR_RELEASE;
}

View File

@@ -0,0 +1,35 @@
#ifndef B3_ADSR_H
#define B3_ADSR_H
class b3ADSR
{
int m_state;
double m_value;
double m_target;
double m_attackRate;
double m_decayRate;
double m_releaseRate;
double m_releaseTime;
double m_sustainLevel;
bool m_autoKeyOff;
public:
b3ADSR();
virtual ~b3ADSR();
double tick();
bool isIdle() const;
void keyOn(bool autoKeyOff);
void keyOff();
void setValues(double attack,double decay,double sustain,double release)
{
m_attackRate = attack;
m_decayRate = decay;
m_sustainLevel = sustain;
m_releaseRate = release;
}
};
#endif //B3_ADSR_H

View File

@@ -1,5 +1,7 @@
#include "b3AudioListener.h"
#include "b3SoundSource.h"
#include "Bullet3Common/b3Logging.h"
#include "b3WriteWavFile.h"
template <class T>
inline const T& MyMin(const T& a, const T& b)
@@ -7,6 +9,7 @@ inline const T& MyMin(const T& a, const T& b)
return a < b ? a : b ;
}
#define MAX_SOUND_SOURCES 128
#define B3_SAMPLE_RATE 48000
struct b3AudioListenerInternalData
{
@@ -15,10 +18,16 @@ struct b3AudioListenerInternalData
b3SoundSource* m_soundSources[MAX_SOUND_SOURCES];
b3WriteWavFile m_wavOut2;
bool m_writeWavOut;
b3AudioListenerInternalData()
:m_numControlTicks(64),
m_sampleRate(48000)
m_sampleRate(B3_SAMPLE_RATE),
m_writeWavOut(false)
{
for (int i=0;i<MAX_SOUND_SOURCES;i++)
{
m_soundSources[i] = 0;
@@ -29,10 +38,19 @@ struct b3AudioListenerInternalData
b3AudioListener::b3AudioListener()
{
m_data = new b3AudioListenerInternalData();
if (m_data->m_writeWavOut)
{
m_data->m_wavOut2.setWavFile("bulletAudio2.wav",B3_SAMPLE_RATE,2,false);
}
}
b3AudioListener::~b3AudioListener()
{
if (m_data->m_writeWavOut)
{
m_data->m_wavOut2.closeWavFile();
}
delete m_data;
}
@@ -52,11 +70,14 @@ int b3AudioListener::addSoundSource(b3SoundSource* source)
return soundIndex;
}
void b3AudioListener::removeSoundSource(int soundSourceIndex)
void b3AudioListener::removeSoundSource(b3SoundSource* source)
{
if (soundSourceIndex >=0 && soundSourceIndex<MAX_SOUND_SOURCES)
for (int i=0;i<MAX_SOUND_SOURCES;i++)
{
m_data->m_soundSources[soundSourceIndex] = 0;
if (m_data->m_soundSources[i]==source)
{
m_data->m_soundSources[i] = 0;
}
}
}
@@ -75,16 +96,24 @@ double b3AudioListener::getSampleRate() const
return m_data->m_sampleRate;
}
void b3AudioListener::setSampleRate(double sampleRate)
{
m_data->m_sampleRate = sampleRate;
}
int b3AudioListener::tick(void *outputBuffer,void *inputBuffer1,unsigned int nBufferFrames,
double streamTime,unsigned int status,void *dataPointer)
{
B3_PROFILE("b3AudioListener::tick");
b3AudioListenerInternalData *data = (b3AudioListenerInternalData *)dataPointer;
register double outs[2],*samples = (double *)outputBuffer;
register double tempOuts[2];
int counter,nTicks = (int)nBufferFrames;
bool done = false;
int numSamples = 0;
while(nTicks > 0 && !done)
{
@@ -103,6 +132,9 @@ int b3AudioListener::tick(void *outputBuffer,void *inputBuffer1,unsigned int nBu
{
if (data->m_soundSources[i])
{
tempOuts[0] = 0;
tempOuts[1] = 0;
if (data->m_soundSources[i]->computeSamples(tempOuts,1, data->m_sampleRate))
{
numActiveSources++;
@@ -113,20 +145,25 @@ int b3AudioListener::tick(void *outputBuffer,void *inputBuffer1,unsigned int nBu
}
}
//simple mixer
if (numActiveSources)
{
outs[0] *= 1./numActiveSources;
outs[1] *= 1./numActiveSources;
}
//soft-clipping of sounds
outs[0] = tanh(outs[0]);
outs[1] = tanh(outs[1]);
*samples++ = outs[0];
*samples++ = outs[1];
numSamples++;
}
nTicks -= counter;
}
if(nTicks == 0)
break;
}
//logging to wav file
if (data->m_writeWavOut && numSamples)
{
data->m_wavOut2.tick( (double *)outputBuffer,numSamples);
}
return 0;
}

View File

@@ -16,12 +16,13 @@ public:
double streamTime, unsigned int status, void *dataPointer);
int addSoundSource(b3SoundSource* source);
void removeSoundSource(int soundSourceIndex);
void removeSoundSource(b3SoundSource* source);
b3AudioListenerInternalData* getTickData();
const b3AudioListenerInternalData* getTickData() const;
double getSampleRate() const;
void setSampleRate(double sampleRate);
};

View File

@@ -0,0 +1,492 @@
//b3ReadWavFile is implemented based on code from the STK toolkit
//See https://github.com/thestk/stk
//Some improvement: the ticking data (b3WavTicker) is separate from wav file,
//This makes it possoble to play a single wav multiple times at the same time
#include "b3ReadWavFile.h"
#include "b3SwapUtils.h"
const unsigned long B3_SINT8 = 0x1;
const unsigned long B3_SINT16 = 0x2;
const unsigned long B3_SINT24 = 0x4;
const unsigned long B3_SINT32 = 0x8;
const unsigned long B3_FLOAT32 = 0x10;
const unsigned long B3_FLOAT64 = 0x20;
b3ReadWavFile::b3ReadWavFile()
{
fd_ = 0;
m_machineIsLittleEndian = b3MachineIsLittleEndian();
}
b3ReadWavFile::~b3ReadWavFile()
{
if (fd_)
fclose(fd_);
}
void b3ReadWavFile::normalize(double peak)
{
int i;
double max = 0.0;
for (i = 0; i < m_frames.size(); i++)
{
if (fabs(m_frames[i]) > max)
max = (double)fabs((double)m_frames[i]);
}
if (max > 0.0)
{
max = 1.0 / max;
max *= peak;
for (i = 0; i < m_frames.size(); i++)
m_frames[i] *= max;
}
}
double b3ReadWavFile::interpolate(double frame, unsigned int channel) const
{
int iIndex = (int)frame; // integer part of index
double output, alpha = frame - (double)iIndex; // fractional part of index
iIndex = iIndex * channels_ + channel;
output = m_frames[iIndex];
if (alpha > 0.0)
output += (alpha * (m_frames[iIndex + channels_] - output));
return output;
}
double b3ReadWavFile::tick(unsigned int channel, b3WavTicker *ticker)
{
if (ticker->finished_) return 0.0;
if (ticker->time_ < 0.0 || ticker->time_ > (double)(this->m_numFrames - 1.0))
{
for (int i = 0; i < ticker->lastFrame_.size(); i++) ticker->lastFrame_[i] = 0.0;
ticker->finished_ = true;
return 0.0;
}
double tyme = ticker->time_;
bool interpolate_ = true; //for now
if (interpolate_)
{
for (int i = 0; i < ticker->lastFrame_.size(); i++)
ticker->lastFrame_[i] = interpolate(tyme, i);
}
// Increment time, which can be negative.
ticker->time_ += ticker->rate_;
return ticker->lastFrame_[channel];
}
void b3ReadWavFile::resize()
{
m_frames.resize(channels_ * m_numFrames);
}
b3WavTicker b3ReadWavFile::createWavTicker(double sampleRate)
{
b3WavTicker ticker;
ticker.lastFrame_.resize(this->channels_);
ticker.time_ = 0;
ticker.finished_ = false;
ticker.rate_ = fileDataRate_ / sampleRate;
return ticker;
}
bool b3ReadWavFile::getWavInfo(const char *fileName)
{
fd_ = fopen(fileName,"rb");
if (fd_ == 0)
return false;
char header[12];
if (fread(&header, 4, 3, fd_) != 3)
return false;
bool res = false;
if (!strncmp(header, "RIFF", 4) &&
!strncmp(&header[8], "WAVE", 4))
res = true;
//getWavInfo( fileName );
// Find "format" chunk ... it must come before the "data" chunk.
char id[4];
int chunkSize;
if (fread(&id, 4, 1, fd_) != 1)
return false;
while (strncmp(id, "fmt ", 4))
{
if (fread(&chunkSize, 4, 1, fd_) != 1)
return false;
if (!m_machineIsLittleEndian)
{
b3Swap32((unsigned char *)&chunkSize);
}
if (fseek(fd_, chunkSize, SEEK_CUR) == -1)
return false;
if (fread(&id, 4, 1, fd_) != 1)
return false;
}
// Check that the data is not compressed.
unsigned short format_tag;
if (fread(&chunkSize, 4, 1, fd_) != 1)
return false; // Read fmt chunk size.
if (fread(&format_tag, 2, 1, fd_) != 1)
return false;
if (!m_machineIsLittleEndian)
{
b3Swap16((unsigned char *)&format_tag);
b3Swap32((unsigned char *)&chunkSize);
}
if (format_tag == 0xFFFE)
{ // WAVE_FORMAT_EXTENSIBLE
dataOffset_ = ftell(fd_);
if (fseek(fd_, 14, SEEK_CUR) == -1)
return false;
unsigned short extSize;
if (fread(&extSize, 2, 1, fd_) != 1)
return false;
if (!m_machineIsLittleEndian)
{
b3Swap16((unsigned char *)&extSize);
}
if (extSize == 0)
return false;
if (fseek(fd_, 6, SEEK_CUR) == -1)
return false;
if (fread(&format_tag, 2, 1, fd_) != 1)
return false;
if (!m_machineIsLittleEndian)
{
b3Swap16((unsigned char *)&format_tag);
}
if (fseek(fd_, dataOffset_, SEEK_SET) == -1)
return false;
}
if (format_tag != 1 && format_tag != 3)
{ // PCM = 1, FLOAT = 3
// oStream_ << "FileRead: "<< fileName << " contains an unsupported data format type (" << format_tag << ").";
return false;
}
// Get number of channels from the header.
short int temp;
if (fread(&temp, 2, 1, fd_) != 1)
return false;
if (!m_machineIsLittleEndian)
{
b3Swap16((unsigned char *)&temp);
}
channels_ = (unsigned int)temp;
// Get file sample rate from the header.
int srate;
if (fread(&srate, 4, 1, fd_) != 1)
return false;
if (!m_machineIsLittleEndian)
{
b3Swap32((unsigned char *)&srate);
}
fileDataRate_ = (double)srate;
// Determine the data type.
dataType_ = 0;
if (fseek(fd_, 6, SEEK_CUR) == -1)
return false; // Locate bits_per_sample info.
if (fread(&temp, 2, 1, fd_) != 1)
return false;
if (!m_machineIsLittleEndian)
{
b3Swap16((unsigned char *)&temp);
}
if (format_tag == 1)
{
if (temp == 8)
dataType_ = B3_SINT8;
else if (temp == 16)
dataType_ = B3_SINT16;
else if (temp == 24)
dataType_ = B3_SINT24;
else if (temp == 32)
dataType_ = B3_SINT32;
}
else if (format_tag == 3)
{
if (temp == 32)
dataType_ = B3_FLOAT32;
else if (temp == 64)
dataType_ = B3_FLOAT64;
}
if (dataType_ == 0)
{
// oStream_ << "FileRead: " << temp << " bits per sample with data format " << format_tag << " are not supported (" << fileName << ").";
return false;
}
// Jump over any remaining part of the "fmt" chunk.
if (fseek(fd_, chunkSize - 16, SEEK_CUR) == -1)
return false;
// Find "data" chunk ... it must come after the "fmt" chunk.
if (fread(&id, 4, 1, fd_) != 1)
return false;
while (strncmp(id, "data", 4))
{
if (fread(&chunkSize, 4, 1, fd_) != 1)
return false;
if (!m_machineIsLittleEndian)
{
b3Swap32((unsigned char *)&chunkSize);
}
chunkSize += chunkSize % 2; // chunk sizes must be even
if (fseek(fd_, chunkSize, SEEK_CUR) == -1)
return false;
if (fread(&id, 4, 1, fd_) != 1)
return false;
}
// Get length of data from the header.
int bytes;
if (fread(&bytes, 4, 1, fd_) != 1)
return false;
if (!m_machineIsLittleEndian)
{
b3Swap32((unsigned char *)&bytes);
}
m_numFrames = bytes / temp / channels_; // sample frames
m_numFrames *= 8; // sample frames
dataOffset_ = ftell(fd_);
byteswap_ = false;
if (!m_machineIsLittleEndian)
{
byteswap_ = true;
}
wavFile_ = true;
return true;
}
bool b3ReadWavFile::read(unsigned long startFrame, bool doNormalize)
{
// Make sure we have an open file.
if (fd_ == 0)
{
// oStream_ << "FileRead::read: a file is not open!";
// Stk::handleError( StkError::WARNING ); return;
return false;
}
// Check the m_frames size.
unsigned long nFrames = this->m_numFrames; //m_frames.frames();
if (nFrames == 0)
{
// oStream_ << "FileRead::read: StkFrames m_frames size is zero ... no data read!";
// Stk::handleError( StkError::WARNING );
return false;
}
if (startFrame >= m_numFrames)
{
return false;
//oStream_ << "FileRead::read: startFrame argument is greater than or equal to the file size!";
//Stk::handleError( StkError::FUNCTION_ARGUMENT );
}
// Check for file end.
if (startFrame + nFrames > m_numFrames)
nFrames = m_numFrames - startFrame;
long i, nSamples = (long)(nFrames * channels_);
unsigned long offset = startFrame * channels_;
// Read samples into StkFrames data m_frames.
if (dataType_ == B3_SINT16)
{
signed short int *buf = (signed short int *)&m_frames[0];
if (fseek(fd_, dataOffset_ + (offset * 2), SEEK_SET) == -1)
return false;
if (fread(buf, nSamples * 2, 1, fd_) != 1)
return false;
if (byteswap_)
{
signed short int *ptr = buf;
for (i = nSamples - 1; i >= 0; i--)
b3Swap16((unsigned char *)ptr++);
}
if (doNormalize)
{
double gain = 1.0 / 32768.0;
for (i = nSamples - 1; i >= 0; i--)
m_frames[i] = buf[i] * gain;
}
else
{
for (i = nSamples - 1; i >= 0; i--)
m_frames[i] = buf[i];
}
}
else if (dataType_ == B3_SINT32)
{
int *buf = (int *)&m_frames[0];
if (fseek(fd_, dataOffset_ + (offset * 4), SEEK_SET) == -1)
return false;
if (fread(buf, nSamples * 4, 1, fd_) != 1)
return false;
if (byteswap_)
{
int *ptr = buf;
for (i = nSamples - 1; i >= 0; i--)
b3Swap32((unsigned char *)ptr++);
}
if (doNormalize)
{
double gain = 1.0 / 2147483648.0;
for (i = nSamples - 1; i >= 0; i--)
m_frames[i] = buf[i] * gain;
}
else
{
for (i = nSamples - 1; i >= 0; i--)
m_frames[i] = buf[i];
}
}
else if (dataType_ == B3_FLOAT32)
{
float *buf = (float *)&m_frames[0];
if (fseek(fd_, dataOffset_ + (offset * 4), SEEK_SET) == -1)
return false;
if (fread(buf, nSamples * 4, 1, fd_) != 1)
return false;
if (byteswap_)
{
float *ptr = buf;
for (i = nSamples - 1; i >= 0; i--)
b3Swap32((unsigned char *)ptr++);
}
for (i = nSamples - 1; i >= 0; i--)
m_frames[i] = buf[i];
}
else if (dataType_ == B3_FLOAT64)
{
double *buf = (double *)&m_frames[0];
if (fseek(fd_, dataOffset_ + (offset * 8), SEEK_SET) == -1)
return false;
if (fread(buf, nSamples * 8, 1, fd_) != 1)
return false;
if (byteswap_)
{
double *ptr = buf;
for (i = nSamples - 1; i >= 0; i--)
b3Swap64((unsigned char *)ptr++);
}
for (i = nSamples - 1; i >= 0; i--)
m_frames[i] = buf[i];
}
else if (dataType_ == B3_SINT8 && wavFile_)
{ // 8-bit WAV data is unsigned!
unsigned char *buf = (unsigned char *)&m_frames[0];
if (fseek(fd_, dataOffset_ + offset, SEEK_SET) == -1)
return false;
if (fread(buf, nSamples, 1, fd_) != 1)
return false;
if (doNormalize)
{
double gain = 1.0 / 128.0;
for (i = nSamples - 1; i >= 0; i--)
m_frames[i] = (buf[i] - 128) * gain;
}
else
{
for (i = nSamples - 1; i >= 0; i--)
m_frames[i] = buf[i] - 128.0;
}
}
else if (dataType_ == B3_SINT8)
{ // signed 8-bit data
char *buf = (char *)&m_frames[0];
if (fseek(fd_, dataOffset_ + offset, SEEK_SET) == -1)
return false;
if (fread(buf, nSamples, 1, fd_) != 1)
return false;
if (doNormalize)
{
double gain = 1.0 / 128.0;
for (i = nSamples - 1; i >= 0; i--)
m_frames[i] = buf[i] * gain;
}
else
{
for (i = nSamples - 1; i >= 0; i--)
m_frames[i] = buf[i];
}
}
else if (dataType_ == B3_SINT24)
{
// 24-bit values are harder to import efficiently since there is
// no native 24-bit type. The following routine works but is much
// less efficient than that used for the other data types.
int temp;
unsigned char *ptr = (unsigned char *)&temp;
double gain = 1.0 / 2147483648.0;
if (fseek(fd_, dataOffset_ + (offset * 3), SEEK_SET) == -1)
return false;
for (i = 0; i < nSamples; i++)
{
if (m_machineIsLittleEndian)
{
if (byteswap_)
{
if (fread(ptr, 3, 1, fd_) != 1)
return false;
temp &= 0x00ffffff;
b3Swap32((unsigned char *)ptr);
}
else
{
if (fread(ptr + 1, 3, 1, fd_) != 1)
return false;
temp &= 0xffffff00;
}
}
else
{
if (byteswap_)
{
if (fread(ptr + 1, 3, 1, fd_) != 1)
return false;
temp &= 0xffffff00;
b3Swap32((unsigned char *)ptr);
}
else
{
if (fread(ptr, 3, 1, fd_) != 1)
return false;
temp &= 0x00ffffff;
}
}
if (doNormalize)
{
m_frames[i] = (double)temp * gain; // "gain" also includes 1 / 256 factor.
}
else
m_frames[i] = (double)temp / 256; // right shift without affecting the sign bit
}
}
// m_frames.setDataRate( fileDataRate_ );
return true;
// error:
// oStream_ << "FileRead: Error reading file data.";
// handleError( StkError::FILE_ERROR);
}

View File

@@ -0,0 +1,57 @@
#ifndef B3_READ_WAV_FILE_H
#define B3_READ_WAV_FILE_H
#include "Bullet3Common/b3AlignedObjectArray.h"
#include <stdio.h>
#include <string.h>
struct b3WavTicker
{
b3AlignedObjectArray<double> lastFrame_;
bool finished_;
double time_;
double rate_;
};
class b3ReadWavFile
{
bool byteswap_;
bool wavFile_;
unsigned long m_numFrames;
unsigned long dataType_;
double fileDataRate_;
FILE *fd_;
unsigned long dataOffset_;
unsigned int channels_;
bool m_machineIsLittleEndian;
public:
b3ReadWavFile();
virtual ~b3ReadWavFile();
b3AlignedObjectArray<double> m_frames;
bool getWavInfo(const char *fileName);
void normalize(double peak);
double interpolate(double frame, unsigned int channel) const;
double tick(unsigned int channel, b3WavTicker *ticker);
void resize();
b3WavTicker createWavTicker(double sampleRate);
bool read(unsigned long startFrame, bool doNormalize);
int getNumFrames() const
{
return m_numFrames;
}
};
#endif //B3_READ_WAV_FILE_H

View File

@@ -0,0 +1,186 @@
#include "b3SoundEngine.h"
#include "RtAudio.h"
#include "b3AudioListener.h"
#include "b3SoundSource.h"
#include "Bullet3Common/b3AlignedObjectArray.h"
#include "b3ReadWavFile.h"
#include "../Utils/b3ResourcePath.h"
#include "Bullet3Common/b3HashMap.h"
// The default real-time audio input and output buffer size. If
// clicks are occuring in the input and/or output sound stream, a
// larger buffer size may help. Larger buffer sizes, however, produce
// more latency.
//const unsigned int RT_BUFFER_SIZE = 1024;
const unsigned int RT_BUFFER_SIZE = 256;
struct b3SoundEngineInternalData
{
b3AudioListener m_listener;
RtAudio m_dac;
bool m_useRealTimeDac;
b3AlignedObjectArray<b3SoundSource*> m_soundSources;
b3HashMap<b3HashInt, b3ReadWavFile*> m_wavFiles;
b3HashMap<b3HashString, int> m_name2wav;
int m_wavFileUidGenerator;
b3SoundEngineInternalData()
: m_useRealTimeDac(false),
m_wavFileUidGenerator(123)
{
}
};
b3SoundEngine::b3SoundEngine()
{
m_data = new b3SoundEngineInternalData();
}
b3SoundEngine::~b3SoundEngine()
{
exit();
delete m_data;
}
void b3SoundEngine::init(int maxNumSoundSources, bool useRealTimeDac)
{
for (int i = 0; i < maxNumSoundSources; i++)
{
b3SoundSource* source = new b3SoundSource();
m_data->m_soundSources.push_back(source);
m_data->m_listener.addSoundSource(source);
}
this->m_data->m_useRealTimeDac = useRealTimeDac;
if (useRealTimeDac)
{
RtAudioFormat format = (sizeof(double) == 8) ? RTAUDIO_FLOAT64 : RTAUDIO_FLOAT32;
RtAudio::StreamParameters parameters;
parameters.deviceId = m_data->m_dac.getDefaultOutputDevice();
parameters.nChannels = 2;
unsigned int bufferFrames = RT_BUFFER_SIZE;
double sampleRate = m_data->m_listener.getSampleRate();
m_data->m_dac.openStream(&parameters, NULL, format, (unsigned int)sampleRate, &bufferFrames, &b3AudioListener::tick,
(void*)m_data->m_listener.getTickData());
m_data->m_dac.startStream();
}
}
void b3SoundEngine::exit()
{
m_data->m_dac.closeStream();
m_data->m_useRealTimeDac = false;
for (int i = 0; i < m_data->m_soundSources.size(); i++)
{
m_data->m_listener.removeSoundSource(m_data->m_soundSources[i]);
m_data->m_soundSources[i]->stopSound();
delete m_data->m_soundSources[i];
}
m_data->m_soundSources.clear();
for (int i=0;i<m_data->m_wavFiles.size();i++)
{
b3ReadWavFile** wavPtr = m_data->m_wavFiles.getAtIndex(i);
if (wavPtr && *wavPtr)
{
b3ReadWavFile* wav = *wavPtr;
delete wav;
}
}
m_data->m_wavFiles.clear();
m_data->m_name2wav.clear();
}
int b3SoundEngine::getAvailableSoundSource()
{
for (int i = 0; i < m_data->m_soundSources.size(); i++)
{
if (m_data->m_soundSources[i]->isAvailable())
{
return i;
}
}
return -1;
}
void b3SoundEngine::startSound(int soundSourceIndex, b3SoundMessage msg)
{
b3SoundSource* soundSource = m_data->m_soundSources[soundSourceIndex];
soundSource->setOscillatorAmplitude(0,msg.m_amplitude);
soundSource->setOscillatorAmplitude(1,msg.m_amplitude);
soundSource->setADSR(msg.m_attackRate,msg.m_decayRate,msg.m_sustainLevel,msg.m_releaseRate);
switch (msg.m_type)
{
case B3_SOUND_SOURCE_SINE_OSCILLATOR:
{
soundSource->setOscillatorFrequency(0, msg.m_frequency);
soundSource->setOscillatorFrequency(1, msg.m_frequency);
soundSource->startSound(msg.m_autoKeyOff);
break;
}
case B3_SOUND_SOURCE_WAV_FILE:
{
b3ReadWavFile** wavFilePtr = m_data->m_wavFiles[msg.m_wavId];
if (wavFilePtr)
{
b3ReadWavFile* wavFile = *wavFilePtr;
soundSource->setWavFile(0,wavFile,getSampleRate());
soundSource->setWavFile(1,wavFile,getSampleRate());
soundSource->startSound(msg.m_autoKeyOff);
}
break;
}
default:
{
}
}
}
void b3SoundEngine::releaseSound(int soundSourceIndex)
{
b3SoundSource* soundSource = m_data->m_soundSources[soundSourceIndex];
soundSource->stopSound();
}
int b3SoundEngine::loadWavFile(const char* fileName)
{
int* wavUidPtr = m_data->m_name2wav[fileName];
if (wavUidPtr)
{
return *wavUidPtr;
}
char resourcePath[1024];
if (b3ResourcePath::findResourcePath(fileName, resourcePath, 1024))
{
b3ReadWavFile* wavFile = new b3ReadWavFile();
wavFile->getWavInfo(resourcePath);
wavFile->resize();
wavFile->read(0, true);
wavFile->normalize(1);
int wavUID = m_data->m_wavFileUidGenerator++;
m_data->m_wavFiles.insert(wavUID, wavFile);
m_data->m_name2wav.insert(fileName,wavUID);
return wavUID;
}
return 0;
}
double b3SoundEngine::getSampleRate() const
{
return m_data->m_listener.getSampleRate();
}

View File

@@ -0,0 +1,57 @@
#ifndef B3_SOUND_ENGINE_H
#define B3_SOUND_ENGINE_H
#include "Bullet3Common/b3Scalar.h"
#include "b3Sound_C_Api.h"
struct b3SoundMessage
{
int m_type;//B3_SOUND_SOURCE_TYPE
double m_amplitude;
double m_frequency;
int m_wavId;
double m_attackRate;
double m_decayRate;
double m_sustainLevel;
double m_releaseRate;
bool m_autoKeyOff;
b3SoundMessage()
:m_type(B3_SOUND_SOURCE_SINE_OSCILLATOR),
m_amplitude(0.5),
m_frequency(440),
m_wavId(-1),
m_attackRate(0.001),
m_decayRate(0.00001),
m_sustainLevel(0.5),
m_releaseRate(0.0005),
m_autoKeyOff(false)
{
}
};
class b3SoundEngine
{
struct b3SoundEngineInternalData* m_data;
public:
b3SoundEngine();
virtual ~b3SoundEngine();
void init(int maxNumSoundSources, bool useRealTimeDac);
void exit();
int getAvailableSoundSource();
void startSound(int soundSourceIndex, b3SoundMessage msg);
void releaseSound(int soundSourceIndex);
int loadWavFile(const char* fileName);
double getSampleRate() const;
};
#endif //B3_SOUND_ENGINE_H

View File

@@ -3,37 +3,71 @@
#define MY2PI (2.*3.14159265)
#include <math.h>
#include "Bullet3Common/b3FileUtils.h"
#include "b3ReadWavFile.h"
#include "b3ADSR.h"
#include "b3Sound_C_Api.h"
struct b3SoundOscillator
{
int m_type;
double m_frequency;
double m_amplitude;
double m_phase;
double m_frequency;
b3WavTicker m_wavTicker;
double sampleWaveForm(double sampleRate)
double sampleSineWaveForm(double sampleRate)
{
while (m_phase >= MY2PI)
m_phase -= MY2PI;
double z = sinf(m_phase);
double z = sinf(m_phase);
double sample = m_amplitude*z;
m_phase += MY2PI * (1./sampleRate) * m_frequency;
return sample;
}
b3SoundOscillator()
:m_phase(0),
m_amplitude(0.8),
m_frequency(442.)
double sampleSawWaveForm(double sampleRate)
{
while (m_phase >= MY2PI)
m_phase -= MY2PI;
double z = 2.*(m_phase)/MY2PI-1.;
double sample = m_amplitude*z;
m_phase += MY2PI * (1./sampleRate) * m_frequency;
return sample;
}
void reset()
{
m_phase = 0;
}
b3SoundOscillator()
:m_type(0),
m_frequency(442.),
m_amplitude(1),
m_phase(0)
{
}
};
#define MAX_OSCILLATORS 2
struct b3SoundSourceInternalData
{
b3SoundOscillator m_oscillator;
b3SoundOscillator m_oscillators[MAX_OSCILLATORS];
b3ADSR m_envelope;
b3ReadWavFile* m_wavFilePtr;
b3SoundSourceInternalData()
:m_wavFilePtr(0)
{
}
};
b3SoundSource::b3SoundSource()
@@ -46,21 +80,160 @@ b3SoundSource::~b3SoundSource()
delete m_data;
}
void b3SoundSource::setADSR( double attack, double decay, double sustain, double release)
{
m_data->m_envelope.setValues(attack,decay,sustain,release);
}
bool b3SoundSource::computeSamples(double* sampleBuffer, int numSamples, double sampleRate)
{
double* outputSamples = sampleBuffer;
int numActive = 0;
for (int i=0;i<numSamples;i++)
{
double sample = m_data->m_oscillator.sampleWaveForm(sampleRate);
double sampleLeft = sample;
double sampleRight = sample;
double samples[MAX_OSCILLATORS] ={0};
double env = m_data->m_envelope.tick();
if (env)
{
for (int osc=0;osc<MAX_OSCILLATORS;osc++)
{
if (m_data->m_oscillators[osc].m_type == 0)
{
samples[osc] += env * m_data->m_oscillators[osc].sampleSineWaveForm(sampleRate);
numActive++;
}
if (m_data->m_oscillators[osc].m_type == 1)
{
samples[osc] += env * m_data->m_oscillators[osc].sampleSawWaveForm(sampleRate);
numActive++;
}
if (m_data->m_oscillators[osc].m_type == 128)
{
int frame = 0;
double data = env * m_data->m_oscillators[osc].m_amplitude * m_data->m_wavFilePtr->tick(frame,&m_data->m_oscillators[osc].m_wavTicker);
samples[osc] += data;
numActive++;
}
}
} else
{
for (int osc=0;osc<MAX_OSCILLATORS;osc++)
{
if (m_data->m_oscillators[osc].m_type == 128)
{
m_data->m_oscillators[osc].m_wavTicker.finished_ = true;
}
}
}
//sample *= 1./double(MAX_OSCILLATORS);
double sampleLeft = samples[0];
double sampleRight = samples[1];
if (sampleLeft != sampleRight)
{
}
*outputSamples++ = sampleLeft;
*outputSamples++ = sampleRight;
*outputSamples++ = sampleLeft ;
}
return true;
/* if (m_data->m_flags & looping)
{
for (int osc=0;osc<MAX_OSCILLATORS;osc++)
{
if (m_data->m_oscillators[osc].m_waveIn.isFinished())
m_data->m_oscillators[osc].m_waveIn.reset();
}
}
*/
return numActive>0;
// return false;
}
int b3SoundSource::getNumOscillators() const
{
return MAX_OSCILLATORS;
}
void b3SoundSource::setOscillatorType(int oscillatorIndex, int type)
{
m_data->m_oscillators[oscillatorIndex].m_type = type;
}
void b3SoundSource::setOscillatorFrequency(int oscillatorIndex, double frequency)
{
m_data->m_oscillators[oscillatorIndex].m_frequency = frequency;
}
void b3SoundSource::setOscillatorAmplitude(int oscillatorIndex, double amplitude)
{
m_data->m_oscillators[oscillatorIndex].m_amplitude = amplitude;
}
void b3SoundSource::setOscillatorPhase(int oscillatorIndex, double phase)
{
m_data->m_oscillators[oscillatorIndex].m_phase = phase;
}
bool b3SoundSource::isAvailable() const
{
//available if ADSR is idle and wavticker is finished
return m_data->m_envelope.isIdle();
}
void b3SoundSource::startSound(bool autoKeyOff)
{
if (m_data->m_envelope.isIdle())
{
for (int osc=0;osc<MAX_OSCILLATORS;osc++)
{
m_data->m_oscillators[osc].reset();
if (m_data->m_oscillators[osc].m_type == B3_SOUND_SOURCE_WAV_FILE)// .m_wavTicker.finished_)
{
//test reverse playback of wav
//m_data->m_oscillators[osc].m_wavTicker.rate_ *= -1;
if (m_data->m_oscillators[osc].m_wavTicker.rate_<0)
{
m_data->m_oscillators[osc].m_wavTicker.time_ = m_data->m_wavFilePtr->getNumFrames()-1.;
} else
{
m_data->m_oscillators[osc].m_wavTicker.time_ = 0.f;
}
m_data->m_oscillators[osc].m_wavTicker.finished_ = false;
}
}
}
m_data->m_envelope.keyOn(autoKeyOff);
}
void b3SoundSource::stopSound()
{
m_data->m_envelope.keyOff();
}
bool b3SoundSource::setWavFile(int oscillatorIndex, b3ReadWavFile* wavFilePtr, int sampleRate)
{
{
m_data->m_wavFilePtr = wavFilePtr;
m_data->m_oscillators[oscillatorIndex].m_wavTicker = m_data->m_wavFilePtr->createWavTicker(sampleRate);
// waveIn.openFile(resourcePath);
double rate = 1.0;
// rate = waveIn.getFileRate() / stkSampleRate;
// waveIn.setRate( rate );
// waveIn.ignoreSampleRateChange();
// Find out how many channels we have.
// int channels = waveIn.channelsOut();
// m_data->m_oscillators[oscillatorIndex].m_frames.resize( 1, channels );
m_data->m_oscillators[oscillatorIndex].m_type = 128;
return true;
}
return false;
}

View File

@@ -1,6 +1,9 @@
#ifndef B3_SOUND_SOURCE_H
#define B3_SOUND_SOURCE_H
#include "b3Sound_C_Api.h"
class b3SoundSource
{
struct b3SoundSourceInternalData* m_data;
@@ -11,6 +14,20 @@ public:
virtual ~b3SoundSource();
virtual bool computeSamples(double *sampleBuffer, int numSamples, double sampleRate);
int getNumOscillators() const;
void setOscillatorType(int oscillatorIndex, int type);
void setOscillatorFrequency(int oscillatorIndex, double frequency);
void setOscillatorAmplitude(int oscillatorIndex, double amplitude);
void setOscillatorPhase(int oscillatorIndex, double phase);
void setADSR( double attackRate, double decayRate, double sustainLevel, double releaseRate);
bool setWavFile(int oscillatorIndex, class b3ReadWavFile* wavFilePtr, int sampleRate);
void startSound(bool autoKeyOff);
void stopSound();
bool isAvailable() const;
};
#endif //B3_SOUND_SOURCE_H

View File

@@ -0,0 +1,31 @@
#ifndef B3_SOUND_C_API_H
#define B3_SOUND_C_API_H
//todo: create a sound C-API
//create sound engine
//destroy sound engine
//getSoundSource
//startSound
//releaseSound
//etc
enum B3_SOUND_SOURCE_TYPE
{
B3_SOUND_SOURCE_SINE_OSCILLATOR=1,
B3_SOUND_SOURCE_SAW_OSCILLATOR,
B3_SOUND_SOURCE_WAV_FILE,
};
#ifdef __cplusplus
extern "C" {
#endif
#ifdef __cplusplus
}
#endif
#endif///B3_SOUND_C_API_H

View File

@@ -0,0 +1,59 @@
#ifndef B3_SWAP_UTILS_H
#define B3_SWAP_UTILS_H
inline void b3Swap16(unsigned char *ptr)
{
unsigned char val;
// Swap 1st and 2nd bytes
val = *(ptr);
*(ptr) = *(ptr+1);
*(ptr+1) = val;
}
inline void b3Swap32(unsigned char *ptr)
{
unsigned char val;
// Swap 1st and 4th bytes
val = *(ptr);
*(ptr) = *(ptr+3);
*(ptr+3) = val;
//Swap 2nd and 3rd bytes
ptr += 1;
val = *(ptr);
*(ptr) = *(ptr+1);
*(ptr+1) = val;
}
inline void b3Swap64(unsigned char *ptr)
{
unsigned char val;
// Swap 1st and 8th bytes
val = *(ptr);
*(ptr) = *(ptr + 7);
*(ptr + 7) = val;
// Swap 2nd and 7th bytes
ptr += 1;
val = *(ptr);
*(ptr) = *(ptr + 5);
*(ptr + 5) = val;
// Swap 3rd and 6th bytes
ptr += 1;
val = *(ptr);
*(ptr) = *(ptr + 3);
*(ptr + 3) = val;
// Swap 4th and 5th bytes
ptr += 1;
val = *(ptr);
*(ptr) = *(ptr + 1);
*(ptr + 1) = val;
}
#endif //B3_SWAP_UTILS_H

View File

@@ -0,0 +1,277 @@
// b3WriteWavFile is copied from Stk::FileWvOut/FileWrite
// See also https://github.com/thestk/stk
// by Perry R. Cook and Gary P. Scavone, 1995--2014.
#include "b3WriteWavFile.h"
#include "Bullet3Common/b3AlignedObjectArray.h"
#include "b3SwapUtils.h"
#define B3_FLOAT32 32
#define B3_FLOAT64 64
// WAV header structure. See
// http://www-mmsp.ece.mcgill.ca/documents/audioformats/WAVE/Docs/rfc2361.txt
// for information regarding format codes.
struct b3WaveHeader
{
char riff[4]; // "RIFF"
int fileSize; // in bytes
char wave[4]; // "WAVE"
char fmt[4]; // "fmt "
int chunkSize; // in bytes (16 for PCM)
union {
signed short formatCode; // 1=PCM, 2=ADPCM, 3=IEEE float, 6=A-Law, 7=Mu-Law
unsigned short uformatCode;
};
signed short nChannels; // 1=mono, 2=stereo
int sampleRate;
int bytesPerSecond;
signed short bytesPerSample; // 2=16-bit mono, 4=16-bit stereo
signed short bitsPerSample;
signed short cbSize; // size of extension
signed short validBits; // valid bits per sample
int channelMask; // speaker position mask
char subformat[16]; // format code and GUID
char fact[4]; // "fact"
int factSize; // fact chunk size
int frames; // sample frames
};
struct b3WriteWavFileInternalData
{
FILE *m_file;
int m_numChannels;
int m_sampleRate;
int m_dataType; // single precision 32bit float, 64bit double
bool m_byteswap;
int m_frameCounter;
int m_bufferIndex;
int m_bufferSize;
bool m_clipped;
bool m_isMachineLittleEndian;
b3AlignedObjectArray<float> m_floatBuffer;
b3AlignedObjectArray<double> m_doubleBuffer;
b3WriteWavFileInternalData()
: m_file(0),
m_numChannels(0),
m_dataType(B3_FLOAT32),
m_byteswap(false),
m_frameCounter(0),
m_bufferIndex(0),
m_bufferSize(1024),
m_clipped(false)
{
m_floatBuffer.reserve(m_bufferSize);
m_doubleBuffer.reserve(m_bufferSize);
m_isMachineLittleEndian = b3MachineIsLittleEndian();
}
};
b3WriteWavFile::b3WriteWavFile()
{
m_data = new b3WriteWavFileInternalData();
}
b3WriteWavFile::~b3WriteWavFile()
{
closeWavFile();
delete m_data;
}
bool b3WriteWavFile::setWavFile(std::string fileName, int sampleRate, int numChannels, bool useDoublePrecision)
{
m_data->m_numChannels = numChannels;
m_data->m_sampleRate = sampleRate;
if (useDoublePrecision)
{
m_data->m_dataType = B3_FLOAT64;
}
else
{
m_data->m_dataType = B3_FLOAT32;
}
if (fileName.find(".wav") == std::string::npos)
fileName += ".wav";
m_data->m_file = fopen(fileName.c_str(), "wb");
if (!m_data->m_file)
{
return false;
}
struct b3WaveHeader hdr = {{'R', 'I', 'F', 'F'}, 44, {'W', 'A', 'V', 'E'}, {'f', 'm', 't', ' '}, 16, 1, 1, sampleRate, 0, 2, 16, 0, 0, 0, {'\x01', '\x00', '\x00', '\x00', '\x00', '\x00', '\x10', '\x00', '\x80', '\x00', '\x00', '\xAA', '\x00', '\x38', '\x9B', '\x71'}, {'f', 'a', 'c', 't'}, 4, 0};
hdr.nChannels = (signed short)m_data->m_numChannels;
if (m_data->m_dataType == B3_FLOAT32)
{
hdr.formatCode = 3;
hdr.bitsPerSample = 32;
}
else if (m_data->m_dataType == B3_FLOAT64)
{
hdr.formatCode = 3;
hdr.bitsPerSample = 64;
}
hdr.bytesPerSample = (signed short)(m_data->m_numChannels * hdr.bitsPerSample / 8);
hdr.bytesPerSecond = (int)(hdr.sampleRate * hdr.bytesPerSample);
unsigned int bytesToWrite = 36;
if (m_data->m_numChannels > 2 || hdr.bitsPerSample > 16)
{ // use extensible format
bytesToWrite = 72;
hdr.chunkSize += 24;
hdr.uformatCode = 0xFFFE;
hdr.cbSize = 22;
hdr.validBits = hdr.bitsPerSample;
signed short *subFormat = (signed short *)&hdr.subformat[0];
if (m_data->m_dataType == B3_FLOAT32 || m_data->m_dataType == B3_FLOAT64)
*subFormat = 3;
else
*subFormat = 1;
}
m_data->m_byteswap = false;
if (!m_data->m_isMachineLittleEndian)
{
m_data->m_byteswap = true;
b3Swap32((unsigned char *)&hdr.chunkSize);
b3Swap16((unsigned char *)&hdr.formatCode);
b3Swap16((unsigned char *)&hdr.nChannels);
b3Swap32((unsigned char *)&hdr.sampleRate);
b3Swap32((unsigned char *)&hdr.bytesPerSecond);
b3Swap16((unsigned char *)&hdr.bytesPerSample);
b3Swap16((unsigned char *)&hdr.bitsPerSample);
b3Swap16((unsigned char *)&hdr.cbSize);
b3Swap16((unsigned char *)&hdr.validBits);
b3Swap16((unsigned char *)&hdr.subformat[0]);
b3Swap32((unsigned char *)&hdr.factSize);
}
char data[4] = {'d', 'a', 't', 'a'};
int dataSize = 0;
if (fwrite(&hdr, 1, bytesToWrite, m_data->m_file) != bytesToWrite)
return false;
if (fwrite(&data, 4, 1, m_data->m_file) != 1)
return false;
if (fwrite(&dataSize, 4, 1, m_data->m_file) != 1)
return false;
return true;
}
void b3WriteWavFile::closeWavFile()
{
if (m_data->m_file == 0)
return;
flushData(1);
int bytesPerSample = 1;
if (m_data->m_dataType == B3_FLOAT32)
bytesPerSample = 4;
else if (m_data->m_dataType == B3_FLOAT64)
bytesPerSample = 8;
bool useExtensible = false;
int dataLocation = 40;
if (bytesPerSample > 2 || m_data->m_numChannels > 2)
{
useExtensible = true;
dataLocation = 76;
}
int bytes = (int)(m_data->m_frameCounter * m_data->m_numChannels * bytesPerSample);
if (bytes % 2)
{ // pad extra byte if odd
signed char sample = 0;
fwrite(&sample, 1, 1, m_data->m_file);
}
#ifndef __LITTLE_ENDIAN__
b3Swap32((unsigned char *)&bytes);
#endif
fseek(m_data->m_file, dataLocation, SEEK_SET); // jump to data length
fwrite(&bytes, 4, 1, m_data->m_file);
bytes = (int)(m_data->m_frameCounter * m_data->m_numChannels * bytesPerSample + 44);
if (useExtensible) bytes += 36;
#ifndef __LITTLE_ENDIAN__
b3Swap32((unsigned char *)&bytes);
#endif
fseek(m_data->m_file, 4, SEEK_SET); // jump to file size
fwrite(&bytes, 4, 1, m_data->m_file);
if (useExtensible)
{ // fill in the "fact" chunk frames value
bytes = (int)m_data->m_frameCounter;
#ifndef __LITTLE_ENDIAN__
b3Swap32((unsigned char *)&bytes);
#endif
fseek(m_data->m_file, 68, SEEK_SET);
fwrite(&bytes, 4, 1, m_data->m_file);
}
fclose(m_data->m_file);
m_data->m_file = 0;
}
void b3WriteWavFile::tick(double *frames, int numFrames)
{
int iFrames = 0;
int j, nChannels = m_data->m_numChannels;
for (int i = 0; i < numFrames; i++)
{
for (j = 0; j < nChannels; j++)
{
double sample = frames[iFrames++];
if (sample < -1.)
{
sample = -1.;
m_data->m_clipped = true;
}
if (sample > 1)
{
sample = 1.;
m_data->m_clipped = true;
}
if (m_data->m_dataType == B3_FLOAT32)
{
m_data->m_floatBuffer.push_back((float)sample);
}
else
{
m_data->m_doubleBuffer.push_back(sample);
}
flushData(m_data->m_bufferSize);
}
m_data->m_frameCounter++;
}
}
void b3WriteWavFile::flushData(int bufferSize)
{
if (m_data->m_dataType == B3_FLOAT32)
{
if (m_data->m_floatBuffer.size() >= bufferSize)
{
fwrite(&m_data->m_floatBuffer[0], sizeof(float), m_data->m_floatBuffer.size(), m_data->m_file);
m_data->m_floatBuffer.resize(0);
}
}
else
{
if (m_data->m_doubleBuffer.size() >= bufferSize)
{
fwrite(&m_data->m_doubleBuffer[0], sizeof(double), m_data->m_doubleBuffer.size(), m_data->m_file);
m_data->m_doubleBuffer.resize(0);
}
}
}

View File

@@ -0,0 +1,32 @@
#ifndef B3_WRITE_WAV_FILE_H
#define B3_WRITE_WAV_FILE_H
// b3WriteWavFile is copied from Stk::FileWvOut/FileWrite
// See also https://github.com/thestk/stk
// by Perry R. Cook and Gary P. Scavone, 1995--2014.
#include <string>
class b3WriteWavFile
{
void incrementFrame( void );
void flush();
struct b3WriteWavFileInternalData* m_data;
void flushData(int bufferSize);
public:
b3WriteWavFile();
virtual ~b3WriteWavFile();
bool setWavFile(std::string fileName, int sampleRate, int numChannels, bool useDoublePrecision=true);
void closeWavFile();
void tick( double* values, int numValues );
};
#endif //B3_WRITE_WAV_FILE_H

View File

@@ -15,16 +15,19 @@
"**.cpp",
"**.h",
"../StandaloneMain/main_console_single_example.cpp",
"../Utils/b3ResourcePath.cpp"
}
links {"Bullet3Common"}
if os.is("Windows") then
links {"winmm","Wsock32","dsound"}
defines {"WIN32","__WINDOWS_MM__","__LITTLE_ENDIAN__","__WINDOWS_DS__"}
defines {"WIN32","__WINDOWS_MM__","__WINDOWS_DS__"}
end
if os.is("Linux") then initX11()
defines {"__OS_LINUX__","__LINUX_ALSA__","__LITTLE_ENDIAN__"}
defines {"__OS_LINUX__","__LINUX_ALSA__"}
links {"asound","pthread"}
end
@@ -33,6 +36,6 @@ if os.is("MacOSX") then
links{"Cocoa.framework"}
links{"CoreAudio.framework", "coreMIDI.framework", "Cocoa.framework"}
defines {"__OS_MACOSX__","__LITTLE_ENDIAN__"}
defines {"__OS_MACOSX__", "__MACOSX_CORE__"}
end

View File

@@ -19,10 +19,13 @@ subject to the following restrictions:
#include "b3AlignedObjectArray.h"
#include <string>
///very basic hashable string implementation, compatible with b3HashMap
struct b3HashString
{
const char* m_string;
std::string m_string;
unsigned int m_hash;
B3_FORCE_INLINE unsigned int getHash()const
@@ -30,9 +33,11 @@ struct b3HashString
return m_hash;
}
b3HashString(const char* name)
:m_string(name)
{
/* magic numbers from http://www.isthe.com/chongo/tech/comp/fnv/ */
static const unsigned int InitialFNV = 2166136261u;
static const unsigned int FNVMultiple = 16777619u;
@@ -65,13 +70,12 @@ struct b3HashString
bool equals(const b3HashString& other) const
{
return (m_string == other.m_string) ||
(0==portableStringCompare(m_string,other.m_string));
return (m_string == other.m_string);
}
};
const int B3_HASH_NULL=0xffffffff;

View File

@@ -140,6 +140,7 @@ public:
CF_HAS_CONTACT_STIFFNESS_DAMPING = 128,
CF_HAS_CUSTOM_DEBUG_RENDERING_COLOR = 256,
CF_HAS_FRICTION_ANCHOR = 512,
CF_HAS_COLLISION_SOUND_TRIGGER = 1024
};
enum CollisionObjectTypes

View File

@@ -79,6 +79,11 @@ class btHashInt
{
int m_uid;
public:
btHashInt()
{
}
btHashInt(int uid) :m_uid(uid)
{
}