mirror of
https://github.com/bulletphysics/bullet3
synced 2025-01-19 05:20:06 +00:00
Merge branch 'master' of github.com:erwincoumans/bullet3
This commit is contained in:
commit
5b4cf02e70
@ -95,7 +95,7 @@ IF(MSVC)
|
||||
ENDIF (NOT USE_MSVC_INCREMENTAL_LINKING)
|
||||
|
||||
IF (NOT USE_MSVC_RUNTIME_LIBRARY_DLL)
|
||||
#We statically link to reduce dependancies
|
||||
#We statically link to reduce dependencies
|
||||
FOREACH(flag_var CMAKE_CXX_FLAGS CMAKE_CXX_FLAGS_DEBUG CMAKE_CXX_FLAGS_RELEASE CMAKE_CXX_FLAGS_MINSIZEREL CMAKE_CXX_FLAGS_RELWITHDEBINFO CMAKE_C_FLAGS CMAKE_C_FLAGS_DEBUG CMAKE_C_FLAGS_RELEASE CMAKE_C_FLAGS_MINSIZEREL CMAKE_C_FLAGS_RELWITHDEBINFO )
|
||||
IF(${flag_var} MATCHES "/MD")
|
||||
STRING(REGEX REPLACE "/MD" "/MT" ${flag_var} "${${flag_var}}")
|
||||
|
@ -566,8 +566,10 @@ void X11OpenGLWindow::enableOpenGL()
|
||||
//Access pthreads as a workaround for a bug in Linux/Ubuntu
|
||||
//See https://bugs.launchpad.net/ubuntu/+source/nvidia-graphics-drivers-319/+bug/1248642
|
||||
|
||||
#if !defined(__NetBSD__)
|
||||
int i = pthread_getconcurrency();
|
||||
printf("pthread_getconcurrency()=%d\n", i);
|
||||
#endif
|
||||
|
||||
// const GLubyte* ext = glGetString(GL_EXTENSIONS);
|
||||
// printf("GL_EXTENSIONS=%s\n", ext);
|
||||
|
@ -20,6 +20,7 @@
|
||||
|
||||
#include <stdio.h>
|
||||
#include "zlib.h"
|
||||
#include <unistd.h>
|
||||
#ifdef STDC
|
||||
#include <string.h>
|
||||
#include <stdlib.h>
|
||||
|
@ -23,7 +23,6 @@ from pybullet_envs.deep_mimic.env.pybullet_deep_mimic_env import PyBulletDeepMim
|
||||
from pybullet_utils.arg_parser import ArgParser
|
||||
from pybullet_utils.logger import Logger
|
||||
|
||||
from typing import Optional
|
||||
|
||||
logger = logging.getLogger(__name__)
|
||||
|
||||
@ -51,9 +50,9 @@ class HumanoidDeepBulletEnv(gym.Env):
|
||||
Logger.print2(arg_file)
|
||||
assert succ, Logger.print2('Failed to load args from: ' + arg_file)
|
||||
|
||||
self._p: Optional[BulletClient] = None
|
||||
self._p = None
|
||||
self._time_step = time_step
|
||||
self._internal_env: Optional[PyBulletDeepMimicEnv] = None
|
||||
self._internal_env = None
|
||||
self._renders = renders
|
||||
self._discrete_actions = False
|
||||
self._arg_file = arg_file
|
||||
|
2
setup.py
2
setup.py
@ -501,7 +501,7 @@ if 'BT_USE_EGL' in EGL_CXX_FLAGS:
|
||||
|
||||
setup(
|
||||
name='pybullet',
|
||||
version='2.8.7',
|
||||
version='2.9.0',
|
||||
description=
|
||||
'Official Python Interface for the Bullet Physics SDK specialized for Robotics Simulation and Reinforcement Learning',
|
||||
long_description=
|
||||
|
@ -356,12 +356,12 @@ public:
|
||||
}
|
||||
}
|
||||
|
||||
btVector3 getPushVelocity()
|
||||
btVector3 getPushVelocity() const
|
||||
{
|
||||
return m_pushVelocity;
|
||||
}
|
||||
|
||||
btVector3 getTurnVelocity()
|
||||
btVector3 getTurnVelocity() const
|
||||
{
|
||||
return m_turnVelocity;
|
||||
}
|
||||
|
@ -2673,6 +2673,7 @@ btScalar btConvexHullComputer::compute(const void* coords, bool doubleCoords, in
|
||||
}
|
||||
|
||||
vertices.resize(0);
|
||||
original_vertex_index.resize(0);
|
||||
edges.resize(0);
|
||||
faces.resize(0);
|
||||
|
||||
@ -2683,6 +2684,7 @@ btScalar btConvexHullComputer::compute(const void* coords, bool doubleCoords, in
|
||||
{
|
||||
btConvexHullInternal::Vertex* v = oldVertices[copied];
|
||||
vertices.push_back(hull.getCoordinates(v));
|
||||
original_vertex_index.push_back(v->point.index);
|
||||
btConvexHullInternal::Edge* firstEdge = v->edges;
|
||||
if (firstEdge)
|
||||
{
|
||||
|
@ -66,6 +66,9 @@ public:
|
||||
// Vertices of the output hull
|
||||
btAlignedObjectArray<btVector3> vertices;
|
||||
|
||||
// The original vertex index in the input coords array
|
||||
btAlignedObjectArray<int> original_vertex_index;
|
||||
|
||||
// Edges of the output hull
|
||||
btAlignedObjectArray<Edge> edges;
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user