Skip to content

Commit

Permalink
Fix sim.h version mismatch.
Browse files Browse the repository at this point in the history
  • Loading branch information
stepjam committed Nov 2, 2020
1 parent d40faba commit c9ebaa4
Show file tree
Hide file tree
Showing 3 changed files with 85 additions and 99 deletions.
2 changes: 1 addition & 1 deletion .travis.yml
Original file line number Diff line number Diff line change
Expand Up @@ -19,7 +19,7 @@ install:
- export LD_LIBRARY_PATH=$LD_LIBRARY_PATH:$COPPELIASIM_ROOT:$COPPELIASIM_ROOT/platforms
- export QT_QPA_PLATFORM_PLUGIN_PATH=$COPPELIASIM_ROOT
- pip3 install -r requirements.txt
- python3 setup.py install
- pip3 install .
# command to run tests
script:
- pip3 install mypy
Expand Down
92 changes: 42 additions & 50 deletions cffi_build/cffi_build.py
Original file line number Diff line number Diff line change
Expand Up @@ -14,7 +14,6 @@
ffibuilder = FFI()

ffibuilder.cdef("""
// ==============
// simTypes.h
// ==============
Expand Down Expand Up @@ -143,6 +142,9 @@
simInt simSetJointTargetPosition(simInt objectHandle,simFloat targetPosition);
simInt simGetJointTargetPosition(simInt objectHandle,simFloat* targetPosition);
simInt simSetJointMaxForce(simInt objectHandle,simFloat forceOrTorque);
simInt simGetPathPosition(simInt objectHandle,simFloat* position);
simInt simSetPathPosition(simInt objectHandle,simFloat position);
simInt simGetPathLength(simInt objectHandle,simFloat* length);
simInt simGetJointMatrix(simInt objectHandle,simFloat* matrix);
simInt simSetSphericalJointMatrix(simInt objectHandle,const simFloat* matrix);
simInt simGetJointInterval(simInt objectHandle,simBool* cyclic,simFloat* interval);
Expand Down Expand Up @@ -189,6 +191,8 @@
simInt simReadDistance(simInt distanceObjectHandle,simFloat* smallestDistance);
simInt simHandleProximitySensor(simInt sensorHandle,simFloat* detectedPoint,simInt* detectedObjectHandle,simFloat* normalVector);
simInt simReadProximitySensor(simInt sensorHandle,simFloat* detectedPoint,simInt* detectedObjectHandle,simFloat* normalVector);
simInt simHandleIkGroup(simInt ikGroupHandle);
simInt simCheckIkGroup(simInt ikGroupHandle,simInt jointCnt,const simInt* jointHandles,simFloat* jointValues,const simInt* jointOptions);
simInt simHandleDynamics(simFloat deltaTime);
simInt simGetScriptHandle(const simChar* scriptName);
simInt simSetScriptText(simInt scriptHandle,const simChar* scriptText);
Expand All @@ -207,6 +211,7 @@
simInt simRefreshDialogs(simInt refreshDegree);
simInt simGetCollisionHandle(const simChar* collisionObjectName);
simInt simGetDistanceHandle(const simChar* distanceObjectName);
simInt simGetIkGroupHandle(const simChar* ikGroupName);
simInt simResetCollision(simInt collisionObjectHandle);
simInt simResetDistance(simInt distanceObjectHandle);
simInt simResetProximitySensor(simInt sensorHandle);
Expand Down Expand Up @@ -261,6 +266,8 @@
simInt simScaleObjects(const simInt* objectHandles,simInt objectCount,simFloat scalingFactor,simBool scalePositionsToo);
simInt simDeleteSelectedObjects();
simInt simGetObjectUniqueIdentifier(simInt objectHandle,simInt* uniqueIdentifier);
simInt simSendData(simInt targetID,simInt dataHeader,const simChar* dataName,const simChar* data,simInt dataLength,simInt antennaHandle,simFloat actionRadius,simFloat emissionAngle1,simFloat emissionAngle2,simFloat persistence);
simChar* simReceiveData(simInt dataHeader,const simChar* dataName,simInt antennaHandle,simInt index,simInt* dataLength,simInt* senderID,simInt* dataHeaderR,simChar** dataNameR);
simInt simSetGraphUserData(simInt graphHandle,const simChar* dataStreamName,simFloat data);
simInt simAddDrawingObject(simInt objectType,simFloat size,simFloat duplicateTolerance,simInt parentObjectHandle,simInt maxItemCount,const simFloat* ambient_diffuse,const simFloat* setToNULL,const simFloat* specular,const simFloat* emission);
simInt simRemoveDrawingObject(simInt objectHandle);
Expand All @@ -287,6 +294,10 @@
simInt simGetObjectProperty(simInt objectHandle);
simInt simSetObjectSpecialProperty(simInt objectHandle,simInt prop);
simInt simGetObjectSpecialProperty(simInt objectHandle);
simInt simGetPositionOnPath(simInt pathHandle,simFloat relativeDistance,simFloat* position);
simInt simGetDataOnPath(simInt pathHandle,simFloat relativeDistance,simInt dataType,simInt* intData,simFloat* floatData);
simInt simGetOrientationOnPath(simInt pathHandle,simFloat relativeDistance,simFloat* eulerAngles);
simInt simGetClosestPositionOnPath(simInt pathHandle,simFloat* absolutePosition,simFloat* pathPosition);
simInt simReadForceSensor(simInt objectHandle,simFloat* forceVector,simFloat* torqueVector);
simInt simBreakForceSensor(simInt objectHandle);
simInt simGetShapeVertex(simInt shapeHandle,simInt groupElementIndex,simInt vertexIndex,simFloat* relativePosition);
Expand Down Expand Up @@ -314,6 +325,12 @@
simInt simSerialRead(simInt portHandle,simChar* buffer,simInt dataLengthToRead);
simInt simSerialCheck(simInt portHandle);
simInt simGetContactInfo(simInt dynamicPass,simInt objectHandle,simInt index,simInt* objectHandles,simFloat* contactInfo);
simInt simSetThreadIsFree(simBool freeMode);
simInt simTubeOpen(simInt dataHeader,const simChar* dataName,simInt readBufferSize,simBool notUsedButKeepZero);
simInt simTubeClose(simInt tubeHandle);
simInt simTubeWrite(simInt tubeHandle,const simChar* data,simInt dataLength);
simChar* simTubeRead(simInt tubeHandle,simInt* dataLength);
simInt simTubeStatus(simInt tubeHandle,simInt* readPacketsCount,simInt* writePacketsCount);
simInt simAuxiliaryConsoleOpen(const simChar* title,simInt maxLines,simInt mode,const simInt* position,const simInt* size,const simFloat* textColor,const simFloat* backgroundColor);
simInt simAuxiliaryConsoleClose(simInt consoleHandle);
simInt simAuxiliaryConsoleShow(simInt consoleHandle,simBool showState);
Expand All @@ -335,14 +352,16 @@
simInt simGetObjectFloatParameter(simInt objectHandle,simInt parameterID,simFloat* parameter);
simInt simSetObjectFloatParameter(simInt objectHandle,simInt parameterID,simFloat parameter);
simChar* simGetObjectStringParameter(simInt objectHandle,simInt parameterID,simInt* parameterLength);
simInt simSetObjectStringParameter(simInt objectHandle,simInt parameterID,const simChar* parameter,simInt parameterLength);
simInt simSetObjectStringParameter(simInt objectHandle,simInt parameterID,simChar* parameter,simInt parameterLength);
simInt simSetSimulationPassesPerRenderingPass(simInt p);
simInt simGetRotationAxis(const simFloat* matrixStart,const simFloat* matrixGoal,simFloat* axis,simFloat* angle);
simInt simRotateAroundAxis(const simFloat* matrixIn,const simFloat* axis,const simFloat* axisPos,simFloat angle,simFloat* matrixOut);
simInt simGetJointForce(simInt jointHandle,simFloat* forceOrTorque);
simInt simGetJointMaxForce(simInt jointHandle,simFloat* forceOrTorque);
simInt simSetArrayParameter(simInt parameter,const simVoid* arrayOfValues);
simInt simGetArrayParameter(simInt parameter,simVoid* arrayOfValues);
simInt simSetIkGroupProperties(simInt ikGroupHandle,simInt resolutionMethod,simInt maxIterations,simFloat damping,void* reserved);
simInt simSetIkElementProperties(simInt ikGroupHandle,simInt tipDummyHandle,simInt constraints,const simFloat* precision,const simFloat* weight,void* reserved);
simInt simCameraFitToView(simInt viewHandleOrIndex,simInt objectCount,const simInt* objectHandles,simInt options,simFloat scaling);
simInt simPersistentDataWrite(const simChar* dataName,const simChar* dataValue,simInt dataLength,simInt options);
simChar* simPersistentDataRead(const simChar* dataName,simInt* dataLength);
Expand All @@ -355,9 +374,9 @@
simInt simGetVisionSensorResolution(simInt visionSensorHandle,simInt* resolution);
simFloat* simGetVisionSensorImage(simInt visionSensorHandle);
simUChar* simGetVisionSensorCharImage(simInt visionSensorHandle,simInt* resolutionX,simInt* resolutionY);
simFloat* simGetVisionSensorDepthBuffer(simInt visionSensorHandle);
simInt simSetVisionSensorImage(simInt visionSensorHandle,const simFloat* image);
simInt simSetVisionSensorCharImage(simInt visionSensorHandle,const simUChar* image);
int simSetVisionSensorDepthBuffer(simInt visionSensorHandle,const float* depthBuffer);
simInt simRMLPosition(simInt dofs,simDouble timeStep,simInt flags,const simDouble* currentPosVelAccel,const simDouble* maxVelAccelJerk,const simBool* selection,const simDouble* targetPosVel,simDouble* newPosVelAccel,simVoid* auxData);
simInt simRMLVelocity(simInt dofs,simDouble timeStep,simInt flags,const simDouble* currentPosVelAccel,const simDouble* maxAccelJerk,const simBool* selection,const simDouble* targetVel,simDouble* newPosVelAccel,simVoid* auxData);
simInt simRMLPos(simInt dofs,simDouble smallestTimeStep,simInt flags,const simDouble* currentPosVelAccel,const simDouble* maxVelAccelJerk,const simBool* selection,const simDouble* targetPosVel,simVoid* auxData);
Expand All @@ -367,15 +386,24 @@
simChar* simFileDialog(simInt mode,const simChar* title,const simChar* startPath,const simChar* initName,const simChar* extName,const simChar* ext);
simInt simMsgBox(simInt dlgType,simInt buttons,const simChar* title,const simChar* message);
simInt simCreateDummy(simFloat size,const simFloat* color);
simInt simSetShapeMassAndInertia(simInt shapeHandle,simFloat mass,const simFloat* inertiaMatrix,const simFloat* centerOfMass,const simFloat* transformation);
simInt simGetShapeMassAndInertia(simInt shapeHandle,simFloat* mass,simFloat* inertiaMatrix,simFloat* centerOfMass,const simFloat* transformation);
simInt simGroupShapes(const simInt* shapeHandles,simInt shapeCount);
simInt* simUngroupShape(simInt shapeHandle,simInt* shapeCount);
simInt simCreateProximitySensor(simInt sensorType,simInt subType,simInt options,const simInt* intParams,const simFloat* floatParams,const simFloat* color);
simInt simCreateForceSensor(simInt options,const simInt* intParams,const simFloat* floatParams,const simFloat* color);
simInt simCreateVisionSensor(simInt options,const simInt* intParams,const simFloat* floatParams,const simFloat* color);
simInt simConvexDecompose(simInt shapeHandle,simInt options,const simInt* intParams,const simFloat* floatParams);
simInt simCreatePath(simInt attributes,const simInt* intParams,const simFloat* floatParams,const simFloat* color);
simInt simInsertPathCtrlPoints(simInt pathHandle,simInt options,simInt startIndex,simInt ptCnt,const simVoid* ptData);
simInt simCutPathCtrlPoints(simInt pathHandle,simInt startIndex,simInt ptCnt);
simFloat* simGetIkGroupMatrix(simInt ikGroupHandle,simInt options,simInt* matrixSize);
simInt simAddGhost(simInt ghostGroup,simInt objectHandle,simInt options,simFloat startTime,simFloat endTime,const simFloat* color);
simInt simModifyGhost(simInt ghostGroup,simInt ghostId,simInt operation,simFloat floatValue,simInt options,simInt optionsMask,const simFloat* colorOrTransformation);
simVoid simQuitSimulator(simBool ignoredArgument);
simInt simGetThreadId();
simInt simLockResources(simInt lockType,simInt reserved);
simInt simUnlockResources(simInt lockHandle);
simInt simEnableEventCallback(simInt eventCallbackType,const simChar* plugin,simInt reserved);
simInt simSetShapeMaterial(simInt shapeHandle,simInt materialIdOrShapeHandle);
simInt simGetTextureId(const simChar* textureName,simInt* resolution);
Expand All @@ -398,6 +426,10 @@
simInt simSetScriptAttribute(simInt scriptHandle,simInt attributeID,simFloat floatVal,simInt intOrBoolVal);
simInt simGetScriptAttribute(simInt scriptHandle,simInt attributeID,simFloat* floatVal,simInt* intOrBoolVal);
simInt simReorientShapeBoundingBox(simInt shapeHandle,simInt relativeToHandle,simInt reservedSetToZero);
simInt simSwitchThread();
simInt simCreateIkGroup(simInt options,const simInt* intParams,const simFloat* floatParams,const simVoid* reserved);
simInt simRemoveIkGroup(simInt ikGroupHandle);
simInt simCreateIkElement(simInt ikGroupHandle,simInt options,const simInt* intParams,const simFloat* floatParams,const simVoid* reserved);
simInt simCreateCollection(const simChar* collectionName,simInt options);
simInt simAddObjectToCollection(simInt collectionHandle,simInt objectHandle,simInt what,simInt options);
simInt simSaveImage(const simUChar* image,const simInt* resolution,simInt options,const simChar* filename,simInt quality,simVoid* reserved);
Expand All @@ -406,7 +438,11 @@
simInt simTransformImage(simUChar* image,const simInt* resolution,simInt options,const simFloat* floatParams,const simInt* intParams,simVoid* reserved);
simInt simGetQHull(const simFloat* inVertices,simInt inVerticesL,simFloat** verticesOut,simInt* verticesOutL,simInt** indicesOut,simInt* indicesOutL,simInt reserved1,const simFloat* reserved2);
simInt simGetDecimatedMesh(const simFloat* inVertices,simInt inVerticesL,const simInt* inIndices,simInt inIndicesL,simFloat** verticesOut,simInt* verticesOutL,simInt** indicesOut,simInt* indicesOutL,simFloat decimationPercent,simInt reserved1,const simFloat* reserved2);
simInt simExportIk(const simChar* pathAndFilename,simInt reserved1,simVoid* reserved2);
simInt simCallScriptFunctionEx(simInt scriptHandleOrType,const simChar* functionNameAtScriptName,simInt stackId);
simInt simComputeJacobian(simInt ikGroupHandle,simInt options,simVoid* reserved);
simInt simGetConfigForTipPose(simInt ikGroupHandle,simInt jointCnt,const simInt* jointHandles,simFloat thresholdDist,simInt maxTimeInMs,simFloat* retConfig,const simFloat* metric,simInt collisionPairCnt,const simInt* collisionPairs,const simInt* jointOptions,const simFloat* lowLimits,const simFloat* ranges,simVoid* reserved);
simFloat* simGenerateIkPath(simInt ikGroupHandle,simInt jointCnt,const simInt* jointHandles,simInt ptCnt,simInt collisionPairCnt,const simInt* collisionPairs,const simInt* jointOptions,simVoid* reserved);
simChar* simGetExtensionString(simInt objectHandle,simInt index,const char* key);
simInt simComputeMassAndInertia(simInt shapeHandle,simFloat density);
simInt simCreateStack();
Expand Down Expand Up @@ -478,16 +514,12 @@
simChar* simGetPersistentDataTags(simInt* tagCount);
simInt simEventNotification(const simChar* event);
simInt simApplyTexture(simInt shapeHandle,const simFloat* textureCoordinates,simInt textCoordSize,const simUChar* texture,const simInt* textureResolution,simInt options);
simInt simSetJointDependency(simInt jointHandle,simInt masterJointHandle,simFloat offset,simFloat multCoeff);
simInt simGetJointDependency(simInt jointHandle,simInt* masterJointHandle,simFloat* offset,simFloat* multCoeff);
simInt simSetJointDependency(simInt jointHandle,simInt masterJointHandle,simFloat offset,simFloat coeff);
simInt simSetStringNamedParam(const simChar* paramName,const simChar* stringParam,simInt paramLength);
simChar* simGetStringNamedParam(const simChar* paramName,simInt* paramLength);
simChar* simGetUserParameter(simInt objectHandle,const simChar* parameterName,simInt* parameterLength);
simInt simSetUserParameter(simInt objectHandle,const simChar* parameterName,const simChar* parameterValue,simInt parameterLength);
simInt simAddLog(const simChar* pluginName,simInt verbosityLevel,const simChar* logMsg);
simInt simGetShapeMass(simInt shapeHandle,simFloat* mass);
simInt simSetShapeMass(simInt shapeHandle,simFloat mass);
simInt simGetShapeInertia(simInt shapeHandle,simFloat* inertiaMatrix,simFloat* transformationMatrix);
simInt simSetShapeInertia(simInt shapeHandle,const simFloat* inertiaMatrix,const simFloat* transformationMatrix);
simInt simIsDynamicallyEnabled(simInt objectHandle);
Expand Down Expand Up @@ -692,46 +724,6 @@
simChar* simGetScriptRawBuffer(simInt scriptHandle,simInt bufferHandle);
simInt simSetScriptRawBuffer(simInt scriptHandle,const simChar* buffer,simInt bufferSize);
simInt simReleaseScriptRawBuffer(simInt scriptHandle,simInt bufferHandle);
simInt simSetShapeMassAndInertia(simInt shapeHandle,simFloat mass,const simFloat* inertiaMatrix,const simFloat* centerOfMass,const simFloat* transformation);
simInt simGetShapeMassAndInertia(simInt shapeHandle,simFloat* mass,simFloat* inertiaMatrix,simFloat* centerOfMass,const simFloat* transformation);
simInt simCheckIkGroup(simInt ikGroupHandle,simInt jointCnt,const simInt* jointHandles,simFloat* jointValues,const simInt* jointOptions);
simInt simCreateIkGroup(simInt options,const simInt* intParams,const simFloat* floatParams,const simVoid* reserved);
simInt simRemoveIkGroup(simInt ikGroupHandle);
simInt simCreateIkElement(simInt ikGroupHandle,simInt options,const simInt* intParams,const simFloat* floatParams,const simVoid* reserved);
simInt simExportIk(const simChar* pathAndFilename,simInt reserved1,simVoid* reserved2);
simInt simComputeJacobian(simInt ikGroupHandle,simInt options,simVoid* reserved);
simInt simGetConfigForTipPose(simInt ikGroupHandle,simInt jointCnt,const simInt* jointHandles,simFloat thresholdDist,simInt maxTimeInMs,simFloat* retConfig,const simFloat* metric,simInt collisionPairCnt,const simInt* collisionPairs,const simInt* jointOptions,const simFloat* lowLimits,const simFloat* ranges,simVoid* reserved);
simFloat* simGenerateIkPath(simInt ikGroupHandle,simInt jointCnt,const simInt* jointHandles,simInt ptCnt,simInt collisionPairCnt,const simInt* collisionPairs,const simInt* jointOptions,simVoid* reserved);
simInt simGetIkGroupHandle(const simChar* ikGroupName);
simFloat* simGetIkGroupMatrix(simInt ikGroupHandle,simInt options,simInt* matrixSize);
simInt simHandleIkGroup(simInt ikGroupHandle);
simInt simSetIkGroupProperties(simInt ikGroupHandle,simInt resolutionMethod,simInt maxIterations,simFloat damping,void* reserved);
simInt simSetIkElementProperties(simInt ikGroupHandle,simInt tipDummyHandle,simInt constraints,const simFloat* precision,const simFloat* weight,void* reserved);
simInt simSetThreadIsFree(simBool freeMode);
simInt simTubeOpen(simInt dataHeader,const simChar* dataName,simInt readBufferSize,simBool notUsedButKeepZero);
simInt simTubeClose(simInt tubeHandle);
simInt simTubeWrite(simInt tubeHandle,const simChar* data,simInt dataLength);
simChar* simTubeRead(simInt tubeHandle,simInt* dataLength);
simInt simTubeStatus(simInt tubeHandle,simInt* readPacketsCount,simInt* writePacketsCount);
simInt simSendData(simInt targetID,simInt dataHeader,const simChar* dataName,const simChar* data,simInt dataLength,simInt antennaHandle,simFloat actionRadius,simFloat emissionAngle1,simFloat emissionAngle2,simFloat persistence);
simChar* simReceiveData(simInt dataHeader,const simChar* dataName,simInt antennaHandle,simInt index,simInt* dataLength,simInt* senderID,simInt* dataHeaderR,simChar** dataNameR);
simInt simGetPositionOnPath(simInt pathHandle,simFloat relativeDistance,simFloat* position);
simInt simGetDataOnPath(simInt pathHandle,simFloat relativeDistance,simInt dataType,simInt* intData,simFloat* floatData);
simInt simGetOrientationOnPath(simInt pathHandle,simFloat relativeDistance,simFloat* eulerAngles);
simInt simGetClosestPositionOnPath(simInt pathHandle,simFloat* absolutePosition,simFloat* pathPosition);
simInt simGetPathPosition(simInt objectHandle,simFloat* position);
simInt simSetPathPosition(simInt objectHandle,simFloat position);
simInt simGetPathLength(simInt objectHandle,simFloat* length);
simInt simCreatePath(simInt attributes,const simInt* intParams,const simFloat* floatParams,const simFloat* color);
simInt simInsertPathCtrlPoints(simInt pathHandle,simInt options,simInt startIndex,simInt ptCnt,const simVoid* ptData);
simInt simCutPathCtrlPoints(simInt pathHandle,simInt startIndex,simInt ptCnt);
simInt simGetThreadId();
simInt simSwitchThread();
simInt simLockResources(simInt lockType,simInt reserved);
simInt simUnlockResources(simInt lockHandle);
simChar* simGetUserParameter(simInt objectHandle,const simChar* parameterName,simInt* parameterLength);
simInt simSetUserParameter(simInt objectHandle,const simChar* parameterName,const simChar* parameterValue,simInt parameterLength);
// Deprecated end
""")

Expand Down
Loading

0 comments on commit c9ebaa4

Please sign in to comment.