From 22263928dcc43115634a9243fe4c4be554153594 Mon Sep 17 00:00:00 2001 From: Pierre Rouanet Date: Tue, 17 Mar 2015 14:41:51 +0100 Subject: [PATCH] Update vrep.py so it's compatible with python 3 --- pypot/_version.py | 2 +- pypot/vrep/remoteApiBindings/vrep.py | 214 +++++++++++++++++++++------ 2 files changed, 171 insertions(+), 45 deletions(-) diff --git a/pypot/_version.py b/pypot/_version.py index f1edb192..05633ca0 100644 --- a/pypot/_version.py +++ b/pypot/_version.py @@ -1 +1 @@ -__version__ = '2.2.2' +__version__ = '2.2.3' diff --git a/pypot/vrep/remoteApiBindings/vrep.py b/pypot/vrep/remoteApiBindings/vrep.py index e8bb4d00..b60474f3 100755 --- a/pypot/vrep/remoteApiBindings/vrep.py +++ b/pypot/vrep/remoteApiBindings/vrep.py @@ -1,25 +1,25 @@ # This file is part of the REMOTE API -# -# Copyright 2006-2014 Coppelia Robotics GmbH. All rights reserved. +# +# Copyright 2006-2014 Coppelia Robotics GmbH. All rights reserved. # marc@coppeliarobotics.com # www.coppeliarobotics.com -# +# # The REMOTE API is licensed under the terms of GNU GPL: -# +# # ------------------------------------------------------------------- # The REMOTE API is free software: you can redistribute it and/or modify # it under the terms of the GNU General Public License as published by # the Free Software Foundation, either version 3 of the License, or # (at your option) any later version. -# +# # THE REMOTE API IS DISTRIBUTED "AS IS", WITHOUT ANY EXPRESS OR IMPLIED # WARRANTY. THE USER WILL USE IT AT HIS/HER OWN RISK. THE ORIGINAL # AUTHORS AND COPPELIA ROBOTICS GMBH WILL NOT BE LIABLE FOR DATA LOSS, # DAMAGES, LOSS OF PROFITS OR ANY OTHER KIND OF LOSS WHILE USING OR # MISUSING THIS SOFTWARE. -# +# # See the GNU General Public License for more details. -# +# # You should have received a copy of the GNU General Public License # along with the REMOTE API. If not, see . # ------------------------------------------------------------------- @@ -49,7 +49,7 @@ libsimx = CDLL(dyn_lib) -#ctypes wrapper prototypes +#ctypes wrapper prototypes c_GetJointPosition = CFUNCTYPE(c_int32,c_int32, c_int32, POINTER(c_float), c_int32)(("simxGetJointPosition", libsimx)) c_SetJointPosition = CFUNCTYPE(c_int32,c_int32, c_int32, c_float, c_int32)(("simxSetJointPosition", libsimx)) c_GetJointMatrix = CFUNCTYPE(c_int32,c_int32, c_int32, POINTER(c_float), c_int32)(("simxGetJointMatrix", libsimx)) @@ -155,8 +155,27 @@ c_GetObjectGroupData = CFUNCTYPE(c_int32,c_int32, c_int32, c_int32, POINTER(c_int32), POINTER(POINTER(c_int32)), POINTER(c_int32), POINTER(POINTER(c_int32)), POINTER(c_int32), POINTER(POINTER(c_float)), POINTER(c_int32), POINTER(POINTER(c_char)), c_int32)(("simxGetObjectGroupData", libsimx)) c_GetObjectVelocity = CFUNCTYPE(c_int32,c_int32, c_int32, POINTER(c_float), POINTER(c_float), c_int32)(("simxGetObjectVelocity", libsimx)) +import sys +p3 = sys.version_info >= (3,0) + +def tbs(str): + return bytes(str, 'ascii') + + +def py3compatible(f): + if p3: + def wrapped_f(*args, **kwargs): + args = [tbs(a) if isinstance(a, str) else a for a in args] + kwargs = {k: tbs(v) if isinstance(v, str) else v for k, v in kwargs.items()} + + return f(*args, **kwargs) + + return wrapped_f + else: + return f #API functions +@py3compatible def simxGetJointPosition(clientID, jointHandle, operationMode): ''' Please have a look at the function description/documentation in the V-REP user manual @@ -164,6 +183,7 @@ def simxGetJointPosition(clientID, jointHandle, operationMode): position = c_float() return c_GetJointPosition(clientID, jointHandle, byref(position), operationMode), position.value +@py3compatible def simxSetJointPosition(clientID, jointHandle, position, operationMode): ''' Please have a look at the function description/documentation in the V-REP user manual @@ -171,17 +191,19 @@ def simxSetJointPosition(clientID, jointHandle, position, operationMode): return c_SetJointPosition(clientID, jointHandle, position, operationMode) +@py3compatible def simxGetJointMatrix(clientID, jointHandle, operationMode): ''' Please have a look at the function description/documentation in the V-REP user manual ''' matrix = (c_float*12)() - ret = c_GetJointMatrix(clientID, jointHandle, matrix, operationMode) + ret = c_GetJointMatrix(clientID, jointHandle, matrix, operationMode) arr = [] for i in range(12): - arr.append(matrix[i]) + arr.append(matrix[i]) return ret, arr +@py3compatible def simxSetSphericalJointMatrix(clientID, jointHandle, matrix, operationMode): ''' Please have a look at the function description/documentation in the V-REP user manual @@ -189,6 +211,7 @@ def simxSetSphericalJointMatrix(clientID, jointHandle, matrix, operationMode): matrix = (c_float*12)(*matrix) return c_SetSphericalJointMatrix(clientID, jointHandle, matrix, operationMode) +@py3compatible def simxSetJointTargetVelocity(clientID, jointHandle, targetVelocity, operationMode): ''' Please have a look at the function description/documentation in the V-REP user manual @@ -196,6 +219,7 @@ def simxSetJointTargetVelocity(clientID, jointHandle, targetVelocity, operationM return c_SetJointTargetVelocity(clientID, jointHandle, targetVelocity, operationMode) +@py3compatible def simxSetJointTargetPosition(clientID, jointHandle, targetPosition, operationMode): ''' Please have a look at the function description/documentation in the V-REP user manual @@ -203,6 +227,7 @@ def simxSetJointTargetPosition(clientID, jointHandle, targetPosition, operationM return c_SetJointTargetPosition(clientID, jointHandle, targetPosition, operationMode) +@py3compatible def simxJointGetForce(clientID, jointHandle, operationMode): ''' Please have a look at the function description/documentation in the V-REP user manual @@ -210,6 +235,7 @@ def simxJointGetForce(clientID, jointHandle, operationMode): force = c_float() return c_GetJointForce(clientID, jointHandle, byref(force), operationMode), force.value +@py3compatible def simxGetJointForce(clientID, jointHandle, operationMode): ''' Please have a look at the function description/documentation in the V-REP user manual @@ -217,12 +243,14 @@ def simxGetJointForce(clientID, jointHandle, operationMode): force = c_float() return c_GetJointForce(clientID, jointHandle, byref(force), operationMode), force.value +@py3compatible def simxSetJointForce(clientID, jointHandle, force, operationMode): ''' Please have a look at the function description/documentation in the V-REP user manual ''' return c_SetJointForce(clientID, jointHandle, force, operationMode) +@py3compatible def simxReadForceSensor(clientID, forceSensorHandle, operationMode): ''' Please have a look at the function description/documentation in the V-REP user manual @@ -233,18 +261,20 @@ def simxReadForceSensor(clientID, forceSensorHandle, operationMode): ret = c_ReadForceSensor(clientID, forceSensorHandle, byref(state), forceVector, torqueVector, operationMode) arr1 = [] for i in range(3): - arr1.append(forceVector[i]) + arr1.append(forceVector[i]) arr2 = [] for i in range(3): - arr2.append(torqueVector[i]) - return ret, ord(state.value), arr1, arr2 + arr2.append(torqueVector[i]) + return ret, ord(state.value), arr1, arr2 +@py3compatible def simxBreakForceSensor(clientID, forceSensorHandle, operationMode): ''' Please have a look at the function description/documentation in the V-REP user manual ''' return c_BreakForceSensor(clientID, forceSensorHandle, operationMode) +@py3compatible def simxReadVisionSensor(clientID, sensorHandle, operationMode): ''' Please have a look at the function description/documentation in the V-REP user manual @@ -254,7 +284,7 @@ def simxReadVisionSensor(clientID, sensorHandle, operationMode): auxValues = pointer(c_float()) auxValuesCount = pointer(c_int()) ret = c_ReadVisionSensor(clientID, sensorHandle, byref(detectionState), byref(auxValues), byref(auxValuesCount), operationMode) - + auxValues2 = [] if ret == 0: s = 0 @@ -266,8 +296,9 @@ def simxReadVisionSensor(clientID, sensorHandle, operationMode): c_ReleaseBuffer(auxValues) c_ReleaseBuffer(auxValuesCount) - return ret, bool(detectionState.value!=0), auxValues2 + return ret, bool(detectionState.value!=0), auxValues2 +@py3compatible def simxGetObjectHandle(clientID, objectName, operationMode): ''' Please have a look at the function description/documentation in the V-REP user manual @@ -275,6 +306,7 @@ def simxGetObjectHandle(clientID, objectName, operationMode): handle = c_int() return c_GetObjectHandle(clientID, objectName, byref(handle), operationMode), handle.value +@py3compatible def simxGetVisionSensorImage(clientID, sensorHandle, options, operationMode): ''' Please have a look at the function description/documentation in the V-REP user manual @@ -284,12 +316,12 @@ def simxGetVisionSensorImage(clientID, sensorHandle, options, operationMode): c_image = pointer(c_byte()) bytesPerPixel = 3 if (options and 1) != 0: - bytesPerPixel = 1 + bytesPerPixel = 1 ret = c_GetVisionSensorImage(clientID, sensorHandle, resolution, byref(c_image), options, operationMode) reso = [] image = [] - if (ret == 0): + if (ret == 0): image = [None]*resolution[0]*resolution[1]*bytesPerPixel for i in range(resolution[0] * resolution[1] * bytesPerPixel): image[i] = c_image[i] @@ -297,6 +329,7 @@ def simxGetVisionSensorImage(clientID, sensorHandle, options, operationMode): reso.append(resolution[i]) return ret, reso, image +@py3compatible def simxSetVisionSensorImage(clientID, sensorHandle, image, options, operationMode): ''' Please have a look at the function description/documentation in the V-REP user manual @@ -305,6 +338,7 @@ def simxSetVisionSensorImage(clientID, sensorHandle, image, options, operationMo image_bytes = (c_byte*size)(*image) return c_SetVisionSensorImage(clientID, sensorHandle, image_bytes, size, options, operationMode) +@py3compatible def simxGetVisionSensorDepthBuffer(clientID, sensorHandle, operationMode): ''' Please have a look at the function description/documentation in the V-REP user manual @@ -314,7 +348,7 @@ def simxGetVisionSensorDepthBuffer(clientID, sensorHandle, operationMode): ret = c_GetVisionSensorDepthBuffer(clientID, sensorHandle, resolution, byref(c_buffer), operationMode) reso = [] buffer = [] - if (ret == 0): + if (ret == 0): buffer = [None]*resolution[0]*resolution[1] for i in range(resolution[0] * resolution[1]): buffer[i] = c_buffer[i] @@ -322,6 +356,7 @@ def simxGetVisionSensorDepthBuffer(clientID, sensorHandle, operationMode): reso.append(resolution[i]) return ret, reso, buffer +@py3compatible def simxGetObjectChild(clientID, parentObjectHandle, childIndex, operationMode): ''' Please have a look at the function description/documentation in the V-REP user manual @@ -329,6 +364,7 @@ def simxGetObjectChild(clientID, parentObjectHandle, childIndex, operationMode): childObjectHandle = c_int() return c_GetObjectChild(clientID, parentObjectHandle, childIndex, byref(childObjectHandle), operationMode), childObjectHandle.value +@py3compatible def simxGetObjectParent(clientID, childObjectHandle, operationMode): ''' Please have a look at the function description/documentation in the V-REP user manual @@ -337,6 +373,7 @@ def simxGetObjectParent(clientID, childObjectHandle, operationMode): parentObjectHandle = c_int() return c_GetObjectParent(clientID, childObjectHandle, byref(parentObjectHandle), operationMode), parentObjectHandle.value +@py3compatible def simxReadProximitySensor(clientID, sensorHandle, operationMode): ''' Please have a look at the function description/documentation in the V-REP user manual @@ -349,12 +386,13 @@ def simxReadProximitySensor(clientID, sensorHandle, operationMode): ret = c_ReadProximitySensor(clientID, sensorHandle, byref(detectionState), detectedPoint, byref(detectedObjectHandle), detectedSurfaceNormalVector, operationMode) arr1 = [] for i in range(3): - arr1.append(detectedPoint[i]) + arr1.append(detectedPoint[i]) arr2 = [] for i in range(3): - arr2.append(detectedSurfaceNormalVector[i]) + arr2.append(detectedSurfaceNormalVector[i]) return ret, bool(detectionState.value!=0), arr1, detectedObjectHandle.value, arr2 +@py3compatible def simxLoadModel(clientID, modelPathAndName, options, operationMode): ''' Please have a look at the function description/documentation in the V-REP user manual @@ -362,6 +400,7 @@ def simxLoadModel(clientID, modelPathAndName, options, operationMode): baseHandle = c_int() return c_LoadModel(clientID, modelPathAndName, options, byref(baseHandle), operationMode), baseHandle.value +@py3compatible def simxLoadUI(clientID, uiPathAndName, options, operationMode): ''' Please have a look at the function description/documentation in the V-REP user manual @@ -370,7 +409,7 @@ def simxLoadUI(clientID, uiPathAndName, options, operationMode): count = c_int() uiHandles = pointer(c_int()) ret = c_LoadUI(clientID, uiPathAndName, options, byref(count), byref(uiHandles), operationMode) - + handles = [] if ret == 0: for i in range(count.value): @@ -380,6 +419,7 @@ def simxLoadUI(clientID, uiPathAndName, options, operationMode): return ret, handles +@py3compatible def simxLoadScene(clientID, scenePathAndName, options, operationMode): ''' Please have a look at the function description/documentation in the V-REP user manual @@ -387,6 +427,7 @@ def simxLoadScene(clientID, scenePathAndName, options, operationMode): return c_LoadScene(clientID, scenePathAndName, options, operationMode) +@py3compatible def simxStartSimulation(clientID, operationMode): ''' Please have a look at the function description/documentation in the V-REP user manual @@ -394,6 +435,7 @@ def simxStartSimulation(clientID, operationMode): return c_StartSimulation(clientID, operationMode) +@py3compatible def simxPauseSimulation(clientID, operationMode): ''' Please have a look at the function description/documentation in the V-REP user manual @@ -401,6 +443,7 @@ def simxPauseSimulation(clientID, operationMode): return c_PauseSimulation(clientID, operationMode) +@py3compatible def simxStopSimulation(clientID, operationMode): ''' Please have a look at the function description/documentation in the V-REP user manual @@ -408,6 +451,7 @@ def simxStopSimulation(clientID, operationMode): return c_StopSimulation(clientID, operationMode) +@py3compatible def simxGetUIHandle(clientID, uiName, operationMode): ''' Please have a look at the function description/documentation in the V-REP user manual @@ -416,6 +460,7 @@ def simxGetUIHandle(clientID, uiName, operationMode): handle = c_int() return c_GetUIHandle(clientID, uiName, byref(handle), operationMode), handle.value +@py3compatible def simxGetUISlider(clientID, uiHandle, uiButtonID, operationMode): ''' Please have a look at the function description/documentation in the V-REP user manual @@ -424,6 +469,7 @@ def simxGetUISlider(clientID, uiHandle, uiButtonID, operationMode): position = c_int() return c_GetUISlider(clientID, uiHandle, uiButtonID, byref(position), operationMode), position.value +@py3compatible def simxSetUISlider(clientID, uiHandle, uiButtonID, position, operationMode): ''' Please have a look at the function description/documentation in the V-REP user manual @@ -431,6 +477,7 @@ def simxSetUISlider(clientID, uiHandle, uiButtonID, position, operationMode): return c_SetUISlider(clientID, uiHandle, uiButtonID, position, operationMode) +@py3compatible def simxGetUIEventButton(clientID, uiHandle, operationMode): ''' Please have a look at the function description/documentation in the V-REP user manual @@ -441,9 +488,10 @@ def simxGetUIEventButton(clientID, uiHandle, operationMode): ret = c_GetUIEventButton(clientID, uiHandle, byref(uiEventButtonID), auxValues, operationMode) arr = [] for i in range(2): - arr.append(auxValues[i]) + arr.append(auxValues[i]) return ret, uiEventButtonID.value, arr +@py3compatible def simxGetUIButtonProperty(clientID, uiHandle, uiButtonID, operationMode): ''' Please have a look at the function description/documentation in the V-REP user manual @@ -452,13 +500,15 @@ def simxGetUIButtonProperty(clientID, uiHandle, uiButtonID, operationMode): prop = c_int() return c_GetUIButtonProperty(clientID, uiHandle, uiButtonID, byref(prop), operationMode), prop.value +@py3compatible def simxSetUIButtonProperty(clientID, uiHandle, uiButtonID, prop, operationMode): ''' Please have a look at the function description/documentation in the V-REP user manual ''' - + return c_SetUIButtonProperty(clientID, uiHandle, uiButtonID, prop, operationMode) +@py3compatible def simxAddStatusbarMessage(clientID, message, operationMode): ''' Please have a look at the function description/documentation in the V-REP user manual @@ -466,6 +516,7 @@ def simxAddStatusbarMessage(clientID, message, operationMode): return c_AddStatusbarMessage(clientID, message, operationMode) +@py3compatible def simxAuxiliaryConsoleOpen(clientID, title, maxLines, mode, position, size, textColor, backgroundColor, operationMode): ''' Please have a look at the function description/documentation in the V-REP user manual @@ -490,6 +541,7 @@ def simxAuxiliaryConsoleOpen(clientID, title, maxLines, mode, position, size, te c_backgroundColor = None return c_AuxiliaryConsoleOpen(clientID, title, maxLines, mode, c_position, c_size, c_textColor, c_backgroundColor, byref(consoleHandle), operationMode), consoleHandle.value +@py3compatible def simxAuxiliaryConsoleClose(clientID, consoleHandle, operationMode): ''' Please have a look at the function description/documentation in the V-REP user manual @@ -497,6 +549,7 @@ def simxAuxiliaryConsoleClose(clientID, consoleHandle, operationMode): return c_AuxiliaryConsoleClose(clientID, consoleHandle, operationMode) +@py3compatible def simxAuxiliaryConsolePrint(clientID, consoleHandle, txt, operationMode): ''' Please have a look at the function description/documentation in the V-REP user manual @@ -504,6 +557,7 @@ def simxAuxiliaryConsolePrint(clientID, consoleHandle, txt, operationMode): return c_AuxiliaryConsolePrint(clientID, consoleHandle, txt, operationMode) +@py3compatible def simxAuxiliaryConsoleShow(clientID, consoleHandle, showState, operationMode): ''' Please have a look at the function description/documentation in the V-REP user manual @@ -511,6 +565,7 @@ def simxAuxiliaryConsoleShow(clientID, consoleHandle, showState, operationMode): return c_AuxiliaryConsoleShow(clientID, consoleHandle, showState, operationMode) +@py3compatible def simxGetObjectOrientation(clientID, objectHandle, relativeToObjectHandle, operationMode): ''' Please have a look at the function description/documentation in the V-REP user manual @@ -519,9 +574,10 @@ def simxGetObjectOrientation(clientID, objectHandle, relativeToObjectHandle, ope ret = c_GetObjectOrientation(clientID, objectHandle, relativeToObjectHandle, eulerAngles, operationMode) arr = [] for i in range(3): - arr.append(eulerAngles[i]) + arr.append(eulerAngles[i]) return ret, arr +@py3compatible def simxGetObjectPosition(clientID, objectHandle, relativeToObjectHandle, operationMode): ''' Please have a look at the function description/documentation in the V-REP user manual @@ -530,9 +586,10 @@ def simxGetObjectPosition(clientID, objectHandle, relativeToObjectHandle, operat ret = c_GetObjectPosition(clientID, objectHandle, relativeToObjectHandle, position, operationMode) arr = [] for i in range(3): - arr.append(position[i]) + arr.append(position[i]) return ret, arr +@py3compatible def simxSetObjectOrientation(clientID, objectHandle, relativeToObjectHandle, eulerAngles, operationMode): ''' Please have a look at the function description/documentation in the V-REP user manual @@ -541,6 +598,7 @@ def simxSetObjectOrientation(clientID, objectHandle, relativeToObjectHandle, eul angles = (c_float*3)(*eulerAngles) return c_SetObjectOrientation(clientID, objectHandle, relativeToObjectHandle, angles, operationMode) +@py3compatible def simxSetObjectPosition(clientID, objectHandle, relativeToObjectHandle, position, operationMode): ''' Please have a look at the function description/documentation in the V-REP user manual @@ -549,6 +607,7 @@ def simxSetObjectPosition(clientID, objectHandle, relativeToObjectHandle, positi c_position = (c_float*3)(*position) return c_SetObjectPosition(clientID, objectHandle, relativeToObjectHandle, c_position, operationMode) +@py3compatible def simxSetObjectParent(clientID, objectHandle, parentObject, keepInPlace, operationMode): ''' Please have a look at the function description/documentation in the V-REP user manual @@ -556,6 +615,7 @@ def simxSetObjectParent(clientID, objectHandle, parentObject, keepInPlace, opera return c_SetObjectParent(clientID, objectHandle, parentObject, keepInPlace, operationMode) +@py3compatible def simxSetUIButtonLabel(clientID, uiHandle, uiButtonID, upStateLabel, downStateLabel, operationMode): ''' Please have a look at the function description/documentation in the V-REP user manual @@ -563,6 +623,7 @@ def simxSetUIButtonLabel(clientID, uiHandle, uiButtonID, upStateLabel, downState return c_SetUIButtonLabel(clientID, uiHandle, uiButtonID, upStateLabel, downStateLabel, operationMode) +@py3compatible def simxGetLastErrors(clientID, operationMode): ''' Please have a look at the function description/documentation in the V-REP user manual @@ -571,7 +632,7 @@ def simxGetLastErrors(clientID, operationMode): errorCnt = c_int() errorStrings = pointer(c_char()) ret = c_GetLastErrors(clientID, byref(errorCnt), byref(errorStrings), operationMode) - + if ret == 0: s = 0 for i in range(errorCnt.value): @@ -579,12 +640,13 @@ def simxGetLastErrors(clientID, operationMode): while errorStrings[s] != '\0': a.append(errorStrings[s]) s += 1 - + s += 1 #skip null errors.append(str(a)) return ret, errors +@py3compatible def simxGetArrayParameter(clientID, paramIdentifier, operationMode): ''' Please have a look at the function description/documentation in the V-REP user manual @@ -593,9 +655,10 @@ def simxGetArrayParameter(clientID, paramIdentifier, operationMode): ret = c_GetArrayParameter(clientID, paramIdentifier, paramValues, operationMode) arr = [] for i in range(3): - arr.append(paramValues[i]) + arr.append(paramValues[i]) return ret, arr +@py3compatible def simxSetArrayParameter(clientID, paramIdentifier, paramValues, operationMode): ''' Please have a look at the function description/documentation in the V-REP user manual @@ -604,6 +667,7 @@ def simxSetArrayParameter(clientID, paramIdentifier, paramValues, operationMode) c_paramValues = (c_float*3)(*paramValues) return c_SetArrayParameter(clientID, paramIdentifier, c_paramValues, operationMode) +@py3compatible def simxGetBooleanParameter(clientID, paramIdentifier, operationMode): ''' Please have a look at the function description/documentation in the V-REP user manual @@ -612,6 +676,7 @@ def simxGetBooleanParameter(clientID, paramIdentifier, operationMode): paramValue = c_ubyte() return c_GetBooleanParameter(clientID, paramIdentifier, byref(paramValue), operationMode), bool(paramValue.value!=0) +@py3compatible def simxSetBooleanParameter(clientID, paramIdentifier, paramValue, operationMode): ''' Please have a look at the function description/documentation in the V-REP user manual @@ -619,6 +684,7 @@ def simxSetBooleanParameter(clientID, paramIdentifier, paramValue, operationMode return c_SetBooleanParameter(clientID, paramIdentifier, paramValue, operationMode) +@py3compatible def simxGetIntegerParameter(clientID, paramIdentifier, operationMode): ''' Please have a look at the function description/documentation in the V-REP user manual @@ -627,6 +693,7 @@ def simxGetIntegerParameter(clientID, paramIdentifier, operationMode): paramValue = c_int() return c_GetIntegerParameter(clientID, paramIdentifier, byref(paramValue), operationMode), paramValue.value +@py3compatible def simxSetIntegerParameter(clientID, paramIdentifier, paramValue, operationMode): ''' Please have a look at the function description/documentation in the V-REP user manual @@ -634,6 +701,7 @@ def simxSetIntegerParameter(clientID, paramIdentifier, paramValue, operationMode return c_SetIntegerParameter(clientID, paramIdentifier, paramValue, operationMode) +@py3compatible def simxGetFloatingParameter(clientID, paramIdentifier, operationMode): ''' Please have a look at the function description/documentation in the V-REP user manual @@ -642,6 +710,7 @@ def simxGetFloatingParameter(clientID, paramIdentifier, operationMode): paramValue = c_float() return c_GetFloatingParameter(clientID, paramIdentifier, byref(paramValue), operationMode), paramValue.value +@py3compatible def simxSetFloatingParameter(clientID, paramIdentifier, paramValue, operationMode): ''' Please have a look at the function description/documentation in the V-REP user manual @@ -649,13 +718,14 @@ def simxSetFloatingParameter(clientID, paramIdentifier, paramValue, operationMod return c_SetFloatingParameter(clientID, paramIdentifier, paramValue, operationMode) +@py3compatible def simxGetStringParameter(clientID, paramIdentifier, operationMode): ''' Please have a look at the function description/documentation in the V-REP user manual ''' paramValue = pointer(c_char()) ret = c_GetStringParameter(clientID, paramIdentifier, byref(paramValue), operationMode) - + a = bytearray() if ret == 0: i = 0 @@ -665,6 +735,7 @@ def simxGetStringParameter(clientID, paramIdentifier, operationMode): return ret, str(a) +@py3compatible def simxGetCollisionHandle(clientID, collisionObjectName, operationMode): ''' Please have a look at the function description/documentation in the V-REP user manual @@ -673,6 +744,7 @@ def simxGetCollisionHandle(clientID, collisionObjectName, operationMode): handle = c_int() return c_GetCollisionHandle(clientID, collisionObjectName, byref(handle), operationMode), handle.value +@py3compatible def simxGetDistanceHandle(clientID, distanceObjectName, operationMode): ''' Please have a look at the function description/documentation in the V-REP user manual @@ -681,6 +753,7 @@ def simxGetDistanceHandle(clientID, distanceObjectName, operationMode): handle = c_int() return c_GetDistanceHandle(clientID, distanceObjectName, byref(handle), operationMode), handle.value +@py3compatible def simxReadCollision(clientID, collisionObjectHandle, operationMode): ''' Please have a look at the function description/documentation in the V-REP user manual @@ -688,6 +761,7 @@ def simxReadCollision(clientID, collisionObjectHandle, operationMode): collisionState = c_ubyte() return c_ReadCollision(clientID, collisionObjectHandle, byref(collisionState), operationMode), bool(collisionState.value!=0) +@py3compatible def simxReadDistance(clientID, distanceObjectHandle, operationMode): ''' Please have a look at the function description/documentation in the V-REP user manual @@ -696,6 +770,7 @@ def simxReadDistance(clientID, distanceObjectHandle, operationMode): minimumDistance = c_float() return c_ReadDistance(clientID, distanceObjectHandle, byref(minimumDistance), operationMode), minimumDistance.value +@py3compatible def simxRemoveObject(clientID, objectHandle, operationMode): ''' Please have a look at the function description/documentation in the V-REP user manual @@ -703,6 +778,7 @@ def simxRemoveObject(clientID, objectHandle, operationMode): return c_RemoveObject(clientID, objectHandle, operationMode) +@py3compatible def simxRemoveModel(clientID, objectHandle, operationMode): ''' Please have a look at the function description/documentation in the V-REP user manual @@ -710,6 +786,7 @@ def simxRemoveModel(clientID, objectHandle, operationMode): return c_RemoveModel(clientID, objectHandle, operationMode) +@py3compatible def simxRemoveUI(clientID, uiHandle, operationMode): ''' Please have a look at the function description/documentation in the V-REP user manual @@ -717,6 +794,7 @@ def simxRemoveUI(clientID, uiHandle, operationMode): return c_RemoveUI(clientID, uiHandle, operationMode) +@py3compatible def simxCloseScene(clientID, operationMode): ''' Please have a look at the function description/documentation in the V-REP user manual @@ -724,6 +802,7 @@ def simxCloseScene(clientID, operationMode): return c_CloseScene(clientID, operationMode) +@py3compatible def simxGetObjects(clientID, objectType, operationMode): ''' Please have a look at the function description/documentation in the V-REP user manual @@ -741,6 +820,7 @@ def simxGetObjects(clientID, objectType, operationMode): return ret, handles +@py3compatible def simxDisplayDialog(clientID, titleText, mainText, dialogType, initialText, titleColors, dialogColors, operationMode): ''' Please have a look at the function description/documentation in the V-REP user manual @@ -758,6 +838,7 @@ def simxDisplayDialog(clientID, titleText, mainText, dialogType, initialText, ti c_uiHandle = c_int() return c_DisplayDialog(clientID, titleText, mainText, dialogType, initialText, c_titleColors, c_dialogColors, byref(c_dialogHandle), byref(c_uiHandle), operationMode), c_dialogHandle.value, c_uiHandle.value +@py3compatible def simxEndDialog(clientID, dialogHandle, operationMode): ''' Please have a look at the function description/documentation in the V-REP user manual @@ -765,23 +846,25 @@ def simxEndDialog(clientID, dialogHandle, operationMode): return c_EndDialog(clientID, dialogHandle, operationMode) +@py3compatible def simxGetDialogInput(clientID, dialogHandle, operationMode): ''' Please have a look at the function description/documentation in the V-REP user manual ''' inputText = pointer(c_char()) ret = c_GetDialogInput(clientID, dialogHandle, byref(inputText), operationMode) - + a = bytearray() if ret == 0: i = 0 while inputText[i] != '\0': a.append(inputText[i]) i = i+1 - + return ret, str(a) +@py3compatible def simxGetDialogResult(clientID, dialogHandle, operationMode): ''' Please have a look at the function description/documentation in the V-REP user manual @@ -789,6 +872,7 @@ def simxGetDialogResult(clientID, dialogHandle, operationMode): result = c_int() return c_GetDialogResult(clientID, dialogHandle, byref(result), operationMode), result.value +@py3compatible def simxCopyPasteObjects(clientID, objectHandles, operationMode): ''' Please have a look at the function description/documentation in the V-REP user manual @@ -806,6 +890,7 @@ def simxCopyPasteObjects(clientID, objectHandles, operationMode): return ret, newobj +@py3compatible def simxGetObjectSelection(clientID, operationMode): ''' Please have a look at the function description/documentation in the V-REP user manual @@ -823,6 +908,7 @@ def simxGetObjectSelection(clientID, operationMode): +@py3compatible def simxSetObjectSelection(clientID, objectHandles, operationMode): ''' Please have a look at the function description/documentation in the V-REP user manual @@ -831,6 +917,7 @@ def simxSetObjectSelection(clientID, objectHandles, operationMode): c_objectHandles = (c_int*len(objectHandles))(*objectHandles) return c_SetObjectSelection(clientID, c_objectHandles, len(objectHandles), operationMode) +@py3compatible def simxClearFloatSignal(clientID, signalName, operationMode): ''' Please have a look at the function description/documentation in the V-REP user manual @@ -838,6 +925,7 @@ def simxClearFloatSignal(clientID, signalName, operationMode): return c_ClearFloatSignal(clientID, signalName, operationMode) +@py3compatible def simxClearIntegerSignal(clientID, signalName, operationMode): ''' Please have a look at the function description/documentation in the V-REP user manual @@ -845,6 +933,7 @@ def simxClearIntegerSignal(clientID, signalName, operationMode): return c_ClearIntegerSignal(clientID, signalName, operationMode) +@py3compatible def simxClearStringSignal(clientID, signalName, operationMode): ''' Please have a look at the function description/documentation in the V-REP user manual @@ -852,6 +941,7 @@ def simxClearStringSignal(clientID, signalName, operationMode): return c_ClearStringSignal(clientID, signalName, operationMode) +@py3compatible def simxGetFloatSignal(clientID, signalName, operationMode): ''' Please have a look at the function description/documentation in the V-REP user manual @@ -860,6 +950,7 @@ def simxGetFloatSignal(clientID, signalName, operationMode): signalValue = c_float() return c_GetFloatSignal(clientID, signalName, byref(signalValue), operationMode), signalValue.value +@py3compatible def simxGetIntegerSignal(clientID, signalName, operationMode): ''' Please have a look at the function description/documentation in the V-REP user manual @@ -868,6 +959,7 @@ def simxGetIntegerSignal(clientID, signalName, operationMode): signalValue = c_int() return c_GetIntegerSignal(clientID, signalName, byref(signalValue), operationMode), signalValue.value +@py3compatible def simxGetStringSignal(clientID, signalName, operationMode): ''' Please have a look at the function description/documentation in the V-REP user manual @@ -883,7 +975,8 @@ def simxGetStringSignal(clientID, signalName, operationMode): a.append(signalValue[i]) return ret, str(a) - + +@py3compatible def simxGetAndClearStringSignal(clientID, signalName, operationMode): ''' Please have a look at the function description/documentation in the V-REP user manual @@ -899,7 +992,8 @@ def simxGetAndClearStringSignal(clientID, signalName, operationMode): a.append(signalValue[i]) return ret, str(a) - + +@py3compatible def simxReadStringStream(clientID, signalName, operationMode): ''' Please have a look at the function description/documentation in the V-REP user manual @@ -915,7 +1009,8 @@ def simxReadStringStream(clientID, signalName, operationMode): a.append(signalValue[i]) return ret, str(a) - + +@py3compatible def simxSetFloatSignal(clientID, signalName, signalValue, operationMode): ''' Please have a look at the function description/documentation in the V-REP user manual @@ -923,6 +1018,7 @@ def simxSetFloatSignal(clientID, signalName, signalValue, operationMode): return c_SetFloatSignal(clientID, signalName, signalValue, operationMode) +@py3compatible def simxSetIntegerSignal(clientID, signalName, signalValue, operationMode): ''' Please have a look at the function description/documentation in the V-REP user manual @@ -930,6 +1026,7 @@ def simxSetIntegerSignal(clientID, signalName, signalValue, operationMode): return c_SetIntegerSignal(clientID, signalName, signalValue, operationMode) +@py3compatible def simxSetStringSignal(clientID, signalName, signalValue, operationMode): ''' Please have a look at the function description/documentation in the V-REP user manual @@ -937,6 +1034,7 @@ def simxSetStringSignal(clientID, signalName, signalValue, operationMode): return c_SetStringSignal(clientID, signalName, signalValue, len(signalValue), operationMode) +@py3compatible def simxAppendStringSignal(clientID, signalName, signalValue, operationMode): ''' Please have a look at the function description/documentation in the V-REP user manual @@ -944,6 +1042,7 @@ def simxAppendStringSignal(clientID, signalName, signalValue, operationMode): return c_AppendStringSignal(clientID, signalName, signalValue, len(signalValue), operationMode) +@py3compatible def simxWriteStringStream(clientID, signalName, signalValue, operationMode): ''' Please have a look at the function description/documentation in the V-REP user manual @@ -951,14 +1050,16 @@ def simxWriteStringStream(clientID, signalName, signalValue, operationMode): return c_WriteStringStream(clientID, signalName, signalValue, len(signalValue), operationMode) +@py3compatible def simxGetObjectFloatParameter(clientID, objectHandle, parameterID, operationMode): ''' Please have a look at the function description/documentation in the V-REP user manual ''' - + parameterValue = c_float() - return c_GetObjectFloatParameter(clientID, objectHandle, parameterID, byref(parameterValue), operationMode), parameterValue.value + return c_GetObjectFloatParameter(clientID, objectHandle, parameterID, byref(parameterValue), operationMode), parameterValue.value +@py3compatible def simxSetObjectFloatParameter(clientID, objectHandle, parameterID, parameterValue, operationMode): ''' Please have a look at the function description/documentation in the V-REP user manual @@ -966,14 +1067,16 @@ def simxSetObjectFloatParameter(clientID, objectHandle, parameterID, parameterVa return c_SetObjectFloatParameter(clientID, objectHandle, parameterID, parameterValue, operationMode) +@py3compatible def simxGetObjectIntParameter(clientID, objectHandle, parameterID, operationMode): ''' Please have a look at the function description/documentation in the V-REP user manual ''' - parameterValue = c_int() + parameterValue = c_int() return c_GetObjectIntParameter(clientID, objectHandle, parameterID, byref(parameterValue), operationMode), parameterValue.value +@py3compatible def simxSetObjectIntParameter(clientID, objectHandle, parameterID, parameterValue, operationMode): ''' Please have a look at the function description/documentation in the V-REP user manual @@ -981,6 +1084,7 @@ def simxSetObjectIntParameter(clientID, objectHandle, parameterID, parameterValu return c_SetObjectIntParameter(clientID, objectHandle, parameterID, parameterValue, operationMode) +@py3compatible def simxGetModelProperty(clientID, objectHandle, operationMode): ''' Please have a look at the function description/documentation in the V-REP user manual @@ -988,6 +1092,7 @@ def simxGetModelProperty(clientID, objectHandle, operationMode): prop = c_int() return c_GetModelProperty(clientID, objectHandle, byref(prop), operationMode), prop.value +@py3compatible def simxSetModelProperty(clientID, objectHandle, prop, operationMode): ''' Please have a look at the function description/documentation in the V-REP user manual @@ -995,6 +1100,7 @@ def simxSetModelProperty(clientID, objectHandle, prop, operationMode): return c_SetModelProperty(clientID, objectHandle, prop, operationMode) +@py3compatible def simxStart(connectionAddress, connectionPort, waitUntilConnected, doNotReconnectOnceDisconnected, timeOutInMs, commThreadCycleInMs): ''' Please have a look at the function description/documentation in the V-REP user manual @@ -1002,6 +1108,7 @@ def simxStart(connectionAddress, connectionPort, waitUntilConnected, doNotReconn return c_Start(connectionAddress, connectionPort, waitUntilConnected, doNotReconnectOnceDisconnected, timeOutInMs, commThreadCycleInMs) +@py3compatible def simxFinish(clientID): ''' Please have a look at the function description/documentation in the V-REP user manual @@ -1009,6 +1116,7 @@ def simxFinish(clientID): return c_Finish(clientID) +@py3compatible def simxGetPingTime(clientID): ''' Please have a look at the function description/documentation in the V-REP user manual @@ -1016,6 +1124,7 @@ def simxGetPingTime(clientID): pingTime = c_int() return c_GetPingTime(clientID, byref(pingTime)), pingTime.value +@py3compatible def simxGetLastCmdTime(clientID): ''' Please have a look at the function description/documentation in the V-REP user manual @@ -1030,6 +1139,7 @@ def simxSynchronousTrigger(clientID): return c_SynchronousTrigger(clientID) +@py3compatible def simxSynchronous(clientID, enable): ''' Please have a look at the function description/documentation in the V-REP user manual @@ -1037,6 +1147,7 @@ def simxSynchronous(clientID, enable): return c_Synchronous(clientID, enable) +@py3compatible def simxPauseCommunication(clientID, enable): ''' Please have a look at the function description/documentation in the V-REP user manual @@ -1044,6 +1155,7 @@ def simxPauseCommunication(clientID, enable): return c_PauseCommunication(clientID, enable) +@py3compatible def simxGetInMessageInfo(clientID, infoType): ''' Please have a look at the function description/documentation in the V-REP user manual @@ -1051,6 +1163,7 @@ def simxGetInMessageInfo(clientID, infoType): info = c_int() return c_GetInMessageInfo(clientID, infoType, byref(info)), info.value +@py3compatible def simxGetOutMessageInfo(clientID, infoType): ''' Please have a look at the function description/documentation in the V-REP user manual @@ -1058,6 +1171,7 @@ def simxGetOutMessageInfo(clientID, infoType): info = c_int() return c_GetOutMessageInfo(clientID, infoType, byref(info)), info.value +@py3compatible def simxGetConnectionId(clientID): ''' Please have a look at the function description/documentation in the V-REP user manual @@ -1065,6 +1179,7 @@ def simxGetConnectionId(clientID): return c_GetConnectionId(clientID) +@py3compatible def simxCreateBuffer(bufferSize): ''' Please have a look at the function description/documentation in the V-REP user manual @@ -1072,6 +1187,7 @@ def simxCreateBuffer(bufferSize): return c_CreateBuffer(bufferSize) +@py3compatible def simxReleaseBuffer(buffer): ''' Please have a look at the function description/documentation in the V-REP user manual @@ -1079,6 +1195,7 @@ def simxReleaseBuffer(buffer): return c_ReleaseBuffer(buffer) +@py3compatible def simxTransferFile(clientID, filePathAndName, fileName_serverSide, timeOut, operationMode): ''' Please have a look at the function description/documentation in the V-REP user manual @@ -1086,6 +1203,7 @@ def simxTransferFile(clientID, filePathAndName, fileName_serverSide, timeOut, op return c_TransferFile(clientID, filePathAndName, fileName_serverSide, timeOut, operationMode) +@py3compatible def simxEraseFile(clientID, fileName_serverSide, operationMode): ''' Please have a look at the function description/documentation in the V-REP user manual @@ -1093,6 +1211,7 @@ def simxEraseFile(clientID, fileName_serverSide, operationMode): return c_EraseFile(clientID, fileName_serverSide, operationMode) +@py3compatible def simxCreateDummy(clientID, size, color, operationMode): ''' Please have a look at the function description/documentation in the V-REP user manual @@ -1105,6 +1224,7 @@ def simxCreateDummy(clientID, size, color, operationMode): c_color = None return c_CreateDummy(clientID, size, c_color, byref(handle), operationMode), handle.value +@py3compatible def simxQuery(clientID, signalName, signalValue, retSignalName, timeOutInMs): ''' Please have a look at the function description/documentation in the V-REP user manual @@ -1122,6 +1242,7 @@ def simxQuery(clientID, signalName, signalValue, retSignalName, timeOutInMs): return ret, str(a) +@py3compatible def simxGetObjectGroupData(clientID, objectType, dataType, operationMode): ''' Please have a look at the function description/documentation in the V-REP user manual @@ -1140,7 +1261,7 @@ def simxGetObjectGroupData(clientID, objectType, dataType, operationMode): stringDataC = c_int() stringDataP = pointer(c_char()) ret = c_GetObjectGroupData(clientID, objectType, dataType, byref(handlesC), byref(handlesP), byref(intDataC), byref(intDataP), byref(floatDataC), byref(floatDataP), byref(stringDataC), byref(stringDataP), operationMode) - + if ret == 0: for i in range(handlesC.value): handles.append(handlesP[i]) @@ -1156,9 +1277,10 @@ def simxGetObjectGroupData(clientID, objectType, dataType, operationMode): s += 1 s += 1 #skip null stringData.append(str(a)) - + return ret, handles, intData, floatData, stringData +@py3compatible def simxGetObjectVelocity(clientID, objectHandle, operationMode): ''' Please have a look at the function description/documentation in the V-REP user manual @@ -1168,12 +1290,13 @@ def simxGetObjectVelocity(clientID, objectHandle, operationMode): ret = c_GetObjectVelocity(clientID, objectHandle, linearVel, angularVel, operationMode) arr1 = [] for i in range(3): - arr1.append(linearVel[i]) + arr1.append(linearVel[i]) arr2 = [] for i in range(3): - arr2.append(angularVel[i]) - return ret, arr1, arr2 + arr2.append(angularVel[i]) + return ret, arr1, arr2 +@py3compatible def simxPackInts(intList): ''' Please have a look at the function description/documentation in the V-REP user manual @@ -1183,15 +1306,17 @@ def simxPackInts(intList): s+=struct.pack('