fix pybullet.addUserDebugText borders around letters

bump up pybullet version
In a few pybullet examples, first connect to SHARED_MEMORY, if not connected use GUI mode
This commit is contained in:
erwincoumans
2017-10-10 22:11:32 -07:00
parent c155e105a5
commit de44e4811a
6 changed files with 22 additions and 13 deletions

View File

@@ -8246,9 +8246,9 @@ bool PhysicsServerCommandProcessor::processCommand(const struct SharedMemoryComm
int optionFlags = clientCmd.m_userDebugDrawArgs.m_optionFlags;
if (clientCmd.m_updateFlags & USER_DEBUG_HAS_TEXT_ORIENTATION)
if ((clientCmd.m_updateFlags & USER_DEBUG_HAS_TEXT_ORIENTATION)==0)
{
optionFlags |= DEB_DEBUG_TEXT_USE_ORIENTATION;
optionFlags |= DEB_DEBUG_TEXT_ALWAYS_FACE_CAMERA;
}

View File

@@ -2441,20 +2441,24 @@ void PhysicsServerExample::drawUserDebugLines()
for (int i = 0; i<m_multiThreadedHelper->m_userDebugText.size(); i++)
{
// int optionFlag = CommonGraphicsApp::eDrawText3D_OrtogonalFaceCamera|CommonGraphicsApp::eDrawText3D_TrueType;
//int optionFlag = 0;//CommonGraphicsApp::eDrawText3D_OrtogonalFaceCamera|CommonGraphicsApp::eDrawText3D_TrueType;
//int optionFlag = CommonGraphicsApp::eDrawText3D_TrueType;
float orientation[4] = {0,0,0,1};
//int optionFlag = CommonGraphicsApp::eDrawText3D_OrtogonalFaceCamera;
int optionFlag = 0;
float orientation[4] = {0,0,0,1};
if (m_multiThreadedHelper->m_userDebugText[i].m_optionFlags&CommonGraphicsApp::eDrawText3D_OrtogonalFaceCamera)
{
optionFlag |= CommonGraphicsApp::eDrawText3D_OrtogonalFaceCamera;
} else
{
orientation[0] = m_multiThreadedHelper->m_userDebugText[i].m_textOrientation[0];
orientation[1] = m_multiThreadedHelper->m_userDebugText[i].m_textOrientation[1];
orientation[2] = m_multiThreadedHelper->m_userDebugText[i].m_textOrientation[2];
orientation[3] = m_multiThreadedHelper->m_userDebugText[i].m_textOrientation[3];
optionFlag |= CommonGraphicsApp::eDrawText3D_TrueType;
} else
{
optionFlag |= CommonGraphicsApp::eDrawText3D_OrtogonalFaceCamera;
}
float colorRGBA[4] = {
@@ -2526,7 +2530,6 @@ void PhysicsServerExample::renderScene()
B3_PROFILE("PhysicsServerExample::RenderScene");
drawUserDebugLines();
if (m_physicsServer.isRealTimeSimulationEnabled())
{
@@ -2679,6 +2682,7 @@ void PhysicsServerExample::renderScene()
}
}
drawUserDebugLines();
//m_args[0].m_cs->unlock();

View File

@@ -583,7 +583,7 @@ enum b3ConfigureDebugVisualizerEnum
enum b3AddUserDebugItemEnum
{
DEB_DEBUG_TEXT_USE_ORIENTATION=1,
DEB_DEBUG_TEXT_ALWAYS_FACE_CAMERA=1,
DEB_DEBUG_TEXT_USE_TRUE_TYPE_FONTS=2,
DEB_DEBUG_TEXT_HAS_TRACKING_OBJECT=4,
};

View File

@@ -20,7 +20,9 @@ def getRayFromTo(mouseX,mouseY):
rayFrom[2]+rayForward[2] - 0.5 * horizon[2] + 0.5 * vertical[2]+float(mouseX)*dHor[2]-float(mouseY)*dVer[2]]
return rayFrom,rayTo
p.connect(p.GUI)
cid = p.connect(p.SHARED_MEMORY)
if (cid<0):
p.connect(p.GUI)
p.setPhysicsEngineParameter(numSolverIterations=10)
p.setTimeStep(1./120.)
logId = p.startStateLogging(p.STATE_LOGGING_PROFILE_TIMINGS, "visualShapeBench.json")

View File

@@ -1,6 +1,9 @@
import pybullet as p
import time
p.connect(p.GUI)
cid = p.connect(p.SHARED_MEMORY)
if (cid<0):
p.connect(p.GUI)
p.loadURDF("plane.urdf")
kuka = p.loadURDF("kuka_iiwa/model.urdf")
p.addUserDebugText("tip", [0,0,0.1],textColorRGB=[1,0,0],textSize=1.5,parentObjectUniqueId=kuka, parentLinkIndex=6)

View File

@@ -441,7 +441,7 @@ print("-----")
setup(
name = 'pybullet',
version='1.5.6',
version='1.5.7',
description='Official Python Interface for the Bullet Physics SDK specialized for Robotics Simulation and Reinforcement Learning',
long_description='pybullet is an easy to use Python module for physics simulation, robotics and deep reinforcement learning based on the Bullet Physics SDK. With pybullet you can load articulated bodies from URDF, SDF and other file formats. pybullet provides forward dynamics simulation, inverse dynamics computation, forward and inverse kinematics and collision detection and ray intersection queries. Aside from physics simulation, pybullet supports to rendering, with a CPU renderer and OpenGL visualization and support for virtual reality headsets.',
url='https://github.com/bulletphysics/bullet3',