diff options
author | erwincoumans <erwincoumans@google.com> | 2020-07-14 19:16:53 -0700 |
---|---|---|
committer | GitHub <noreply@github.com> | 2020-07-14 19:16:53 -0700 |
commit | 89328def0f22cf2cb74977a2b8af5d17899597f8 (patch) | |
tree | 552ec8ac847ebe0e45e73b0b3f54b349f5b8093b | |
parent | 6b6cfa6f03a54de484e15520f0a86ea81c9831ae (diff) | |
parent | c9ca9cb6c65eaf511787d344ab3f65f49965941e (diff) | |
download | bullet3-89328def0f22cf2cb74977a2b8af5d17899597f8.tar.gz |
Merge pull request #2930 from erwincoumans/master
Fixes in TinyAudio, revert CoMreward to false for deep_mimic env
4 files changed, 6 insertions, 5 deletions
diff --git a/examples/SharedMemory/PhysicsServerCommandProcessor.cpp b/examples/SharedMemory/PhysicsServerCommandProcessor.cpp index 17f164775..5760c1e5b 100644 --- a/examples/SharedMemory/PhysicsServerCommandProcessor.cpp +++ b/examples/SharedMemory/PhysicsServerCommandProcessor.cpp @@ -3236,15 +3236,15 @@ bool PhysicsServerCommandProcessor::processImportedObjects(const char* fileName, #ifdef B3_ENABLE_TINY_AUDIO { SDFAudioSource audioSource; - int urdfLinkIndex = creation.m_mb2urdfLink[link]; + int urdfLinkIndex = creation.m_mb2urdfLink[i]; if (u2b.getLinkAudioSource(urdfLinkIndex, audioSource)) { - int flags = mb->getLink(link).m_collider->getCollisionFlags(); + int flags = mb->getLink(i).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); + bodyHandle->m_audioSources.insert(i, audioSource); } } } diff --git a/examples/TinyAudio/b3AudioListener.cpp b/examples/TinyAudio/b3AudioListener.cpp index 184b169ec..4e2022ffa 100644 --- a/examples/TinyAudio/b3AudioListener.cpp +++ b/examples/TinyAudio/b3AudioListener.cpp @@ -2,6 +2,7 @@ #include "b3SoundSource.h" #include "Bullet3Common/b3Logging.h" #include "b3WriteWavFile.h" +#include <math.h> template <class T> inline const T& MyMin(const T& a, const T& b) diff --git a/examples/TinyAudio/b3SoundEngine.cpp b/examples/TinyAudio/b3SoundEngine.cpp index e683bf19a..6e36b0d9c 100644 --- a/examples/TinyAudio/b3SoundEngine.cpp +++ b/examples/TinyAudio/b3SoundEngine.cpp @@ -164,7 +164,7 @@ int b3SoundEngine::loadWavFile(const char* fileName) } char resourcePath[1024]; - if (b3ResourcePath::findResourcePath(fileName, resourcePath, 1024)) + if (b3ResourcePath::findResourcePath(fileName, resourcePath, 1024, 0)) { b3ReadWavFile* wavFile = new b3ReadWavFile(); wavFile->getWavInfo(resourcePath); diff --git a/examples/pybullet/gym/pybullet_envs/deep_mimic/env/humanoid_stable_pd.py b/examples/pybullet/gym/pybullet_envs/deep_mimic/env/humanoid_stable_pd.py index 30d607734..fcbf2154b 100644 --- a/examples/pybullet/gym/pybullet_envs/deep_mimic/env/humanoid_stable_pd.py +++ b/examples/pybullet/gym/pybullet_envs/deep_mimic/env/humanoid_stable_pd.py @@ -21,7 +21,7 @@ jointFrictionForce = 0 class HumanoidStablePD(object): def __init__( self, pybullet_client, mocap_data, timeStep, - useFixedBase=True, arg_parser=None, useComReward=True): + useFixedBase=True, arg_parser=None, useComReward=False): self._pybullet_client = pybullet_client self._mocap_data = mocap_data self._arg_parser = arg_parser |