From 127982ab88bfbd9eba276390e3b41481436ace27 Mon Sep 17 00:00:00 2001 From: Erwin Coumans Date: Fri, 6 Oct 2017 16:00:33 -0700 Subject: [PATCH] fix more bugs, introduced in previous recent commits --- examples/pybullet/pybullet.c | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/examples/pybullet/pybullet.c b/examples/pybullet/pybullet.c index af6f463b0..4032fcb69 100644 --- a/examples/pybullet/pybullet.c +++ b/examples/pybullet/pybullet.c @@ -2902,7 +2902,7 @@ static PyObject* pybullet_getJointInfo(PyObject* self, PyObject* args, PyObject* // info.m_jointFriction); PyTuple_SetItem(pyListJointInfo, 0, PyInt_FromLong(info.m_jointIndex)); - if (info.m_jointName) + if (info.m_jointName[0]) { PyTuple_SetItem(pyListJointInfo, 1, PyString_FromString(info.m_jointName)); @@ -2928,7 +2928,7 @@ static PyObject* pybullet_getJointInfo(PyObject* self, PyObject* args, PyObject* PyFloat_FromDouble(info.m_jointMaxForce)); PyTuple_SetItem(pyListJointInfo, 11, PyFloat_FromDouble(info.m_jointMaxVelocity)); - if (info.m_linkName) + if (info.m_linkName[0]) { PyTuple_SetItem(pyListJointInfo, 12,