From 10020baa71d9f63251c26395c60b8e0459659789 Mon Sep 17 00:00:00 2001 From: Erwin Coumans Date: Fri, 15 Jan 2021 14:38:48 -0800 Subject: [PATCH] fix memory leak in calculateInverseKinematics2, reported here: https://github.com/bulletphysics/bullet3/issues/3228 Thanks jcoholich for the report and repro case! --- examples/pybullet/pybullet.c | 13 ++++++++++++- 1 file changed, 12 insertions(+), 1 deletion(-) diff --git a/examples/pybullet/pybullet.c b/examples/pybullet/pybullet.c index 025dd1ca7..b67dea40a 100644 --- a/examples/pybullet/pybullet.c +++ b/examples/pybullet/pybullet.c @@ -1,4 +1,4 @@ -//#include "D:/dev/visual leak detector/include/vld.h" +#include "D:/dev/visual leak detector/include/vld.h" #include "../SharedMemory/PhysicsClientC_API.h" #include "../SharedMemory/PhysicsDirectC_API.h" @@ -11642,6 +11642,8 @@ static PyObject* pybullet_calculateInverseKinematics2(PyObject* self, free(upperLimits); free(jointRanges); free(restPoses); + free(positions); + free(indices); return NULL; } else @@ -11762,12 +11764,16 @@ static PyObject* pybullet_calculateInverseKinematics2(PyObject* self, } free(ikOutPutJointPos); + free(positions); + free(indices); return pylist; } else { PyErr_SetString(SpamError, "Error in calculateInverseKinematics"); + free(positions); + free(indices); return NULL; } } @@ -11775,8 +11781,13 @@ static PyObject* pybullet_calculateInverseKinematics2(PyObject* self, { PyErr_SetString(SpamError, "calculateInverseKinematics couldn't extract position vector3"); + free(positions); + free(indices); return NULL; } + + free(positions); + free(indices); } }