Merge remote-tracking branch 'bp/master'

This commit is contained in:
Erwin Coumans
2018-02-05 09:59:25 -08:00
39 changed files with 4032 additions and 1463 deletions

View File

@@ -120,6 +120,10 @@ ELSE(WIN32)
IF(BUILD_CLSOCKET)
ADD_DEFINITIONS(${OSDEF})
ENDIF(BUILD_CLSOCKET)
IF(NOT APPLE)
LINK_LIBRARIES( pthread ${DL} )
ENDIF(APPLE)
ENDIF(WIN32)
IF(BUILD_ENET)

View File

@@ -175,6 +175,8 @@ SET(BulletExampleBrowser_SRCS
../SharedMemory/b3PluginManager.cpp
../RobotSimulator/b3RobotSimulatorClientAPI.cpp
../RobotSimulator/b3RobotSimulatorClientAPI.h
../RobotSimulator/b3RobotSimulatorClientAPI_NoGUI.cpp
../RobotSimulator/b3RobotSimulatorClientAPI_NoGUI.h
../BasicDemo/BasicExample.cpp
../BasicDemo/BasicExample.h
../InverseDynamics/InverseDynamicsExample.cpp

View File

@@ -122,6 +122,8 @@ project "App_BulletExampleBrowser"
"../InverseDynamics/InverseDynamicsExample.h",
"../RobotSimulator/b3RobotSimulatorClientAPI.cpp",
"../RobotSimulator/b3RobotSimulatorClientAPI.h",
"../RobotSimulator/b3RobotSimulatorClientAPI_NoGUI.cpp",
"../RobotSimulator/b3RobotSimulatorClientAPI_NoGUI.h",
"../BasicDemo/BasicExample.*",
"../Tutorial/*",
"../ExtendedTutorials/*",

View File

@@ -2085,13 +2085,14 @@ void GLInstancingRenderer::renderSceneInternal(int orgRenderMode)
b3CreateOrtho(-shadowMapWorldSize,shadowMapWorldSize,-shadowMapWorldSize,shadowMapWorldSize,1,300,depthProjectionMatrix);//-14,14,-14,14,1,200, depthProjectionMatrix);
float depthViewMatrix[4][4];
b3Vector3 center = b3MakeVector3(0,0,0);
m_data->m_activeCamera->getCameraTargetPosition(center);
//float upf[3];
//m_data->m_activeCamera->getCameraUpVector(upf);
b3Vector3 up, lightFwd;
b3Vector3 lightDir = m_data->m_lightPos.normalized();
b3PlaneSpace1(lightDir,up,lightFwd);
// b3Vector3 up = b3MakeVector3(upf[0],upf[1],upf[2]);
b3CreateLookAt(m_data->m_lightPos,center,up,&depthViewMatrix[0][0]);
b3CreateLookAt(m_data->m_lightPos+center,center,up,&depthViewMatrix[0][0]);
//b3CreateLookAt(lightPos,m_data->m_cameraTargetPosition,b3Vector3(0,1,0),(float*)depthModelViewMatrix2);
GLfloat depthModelMatrix[4][4];

View File

@@ -1,4 +1,3 @@
INCLUDE_DIRECTORIES(
${BULLET_PHYSICS_SOURCE_DIR}/src
${BULLET_PHYSICS_SOURCE_DIR}/examples
@@ -9,77 +8,20 @@ INCLUDE_DIRECTORIES(
SET(RobotSimulator_SRCS
RobotSimulatorMain.cpp
b3RobotSimulatorClientAPI.cpp
b3RobotSimulatorClientAPI.h
MinitaurSetup.cpp
MinitaurSetup.h
../../examples/SharedMemory/IKTrajectoryHelper.cpp
../../examples/SharedMemory/IKTrajectoryHelper.h
../../examples/ExampleBrowser/InProcessExampleBrowser.cpp
../../examples/SharedMemory/plugins/tinyRendererPlugin/tinyRendererPlugin.cpp
../../examples/SharedMemory/plugins/tinyRendererPlugin/TinyRendererVisualShapeConverter.cpp
../../examples/OpenGLWindow/SimpleCamera.cpp
../../examples/OpenGLWindow/SimpleCamera.h
../../examples/TinyRenderer/geometry.cpp
../../examples/TinyRenderer/model.cpp
../../examples/TinyRenderer/tgaimage.cpp
../../examples/TinyRenderer/our_gl.cpp
../../examples/TinyRenderer/TinyRenderer.cpp
../../examples/SharedMemory/InProcessMemory.cpp
../../examples/SharedMemory/PhysicsClient.cpp
../../examples/SharedMemory/PhysicsClient.h
../../examples/SharedMemory/PhysicsServer.cpp
../../examples/SharedMemory/PhysicsServer.h
../../examples/SharedMemory/PhysicsServerExample.cpp
../../examples/SharedMemory/PhysicsServerExampleBullet2.cpp
../../examples/SharedMemory/SharedMemoryInProcessPhysicsC_API.cpp
../../examples/SharedMemory/PhysicsServerSharedMemory.cpp
../../examples/SharedMemory/PhysicsServerSharedMemory.h
../../examples/SharedMemory/PhysicsDirect.cpp
../../examples/SharedMemory/PhysicsDirect.h
../../examples/SharedMemory/PhysicsDirectC_API.cpp
../../examples/SharedMemory/PhysicsDirectC_API.h
../../examples/SharedMemory/PhysicsServerCommandProcessor.cpp
../../examples/SharedMemory/PhysicsServerCommandProcessor.h
../../examples/SharedMemory/b3PluginManager.cpp
../../examples/SharedMemory/PhysicsClientSharedMemory.cpp
../../examples/SharedMemory/PhysicsClientSharedMemory.h
../../examples/SharedMemory/PhysicsClientSharedMemory_C_API.cpp
../../examples/SharedMemory/PhysicsClientSharedMemory_C_API.h
../../examples/SharedMemory/PhysicsClientC_API.cpp
../../examples/SharedMemory/PhysicsClientC_API.h
../../examples/SharedMemory/Win32SharedMemory.cpp
../../examples/SharedMemory/Win32SharedMemory.h
../../examples/SharedMemory/PosixSharedMemory.cpp
../../examples/SharedMemory/PosixSharedMemory.h
../../examples/Utils/b3ResourcePath.cpp
../../examples/Utils/b3ResourcePath.h
../../examples/Utils/RobotLoggingUtil.cpp
../../examples/Utils/RobotLoggingUtil.h
../../examples/ThirdPartyLibs/tinyxml/tinystr.cpp
../../examples/ThirdPartyLibs/tinyxml/tinyxml.cpp
../../examples/ThirdPartyLibs/tinyxml/tinyxmlerror.cpp
../../examples/ThirdPartyLibs/tinyxml/tinyxmlparser.cpp
../../examples/ThirdPartyLibs/Wavefront/tiny_obj_loader.cpp
../../examples/ThirdPartyLibs/Wavefront/tiny_obj_loader.h
../../examples/ThirdPartyLibs/stb_image/stb_image.cpp
../../examples/Importers/ImportColladaDemo/LoadMeshFromCollada.cpp
../../examples/Importers/ImportObjDemo/LoadMeshFromObj.cpp
../../examples/Importers/ImportObjDemo/Wavefront2GLInstanceGraphicsShape.cpp
../../examples/Importers/ImportMJCFDemo/BulletMJCFImporter.cpp
../../examples/Importers/ImportURDFDemo/BulletUrdfImporter.cpp
../../examples/Importers/ImportURDFDemo/MyMultiBodyCreator.cpp
../../examples/Importers/ImportURDFDemo/URDF2Bullet.cpp
../../examples/Importers/ImportURDFDemo/UrdfParser.cpp
../../examples/Importers/ImportURDFDemo/urdfStringSplit.cpp
../../examples/Importers/ImportMeshUtility/b3ImportMeshUtility.cpp
../../examples/MultiThreading/b3PosixThreadSupport.cpp
../../examples/MultiThreading/b3Win32ThreadSupport.cpp
../../examples/MultiThreading/b3ThreadSupportInterface.cpp
)
RobotSimulatorMain.cpp
b3RobotSimulatorClientAPI.cpp
b3RobotSimulatorClientAPI.h
b3RobotSimulatorClientAPI_NoGUI.cpp
b3RobotSimulatorClientAPI_NoGUI.h
MinitaurSetup.cpp
MinitaurSetup.h
../../examples/ExampleBrowser/InProcessExampleBrowser.cpp
../../examples/SharedMemory/PhysicsServerExample.cpp
../../examples/SharedMemory/PhysicsServerExampleBullet2.cpp
../../examples/SharedMemory/SharedMemoryInProcessPhysicsC_API.cpp
)
IF(BUILD_CLSOCKET)
ADD_DEFINITIONS(-DBT_ENABLE_CLSOCKET)
@@ -89,54 +31,9 @@ IF(WIN32)
LINK_LIBRARIES(
${OPENGL_gl_LIBRARY} ${OPENGL_glu_LIBRARY}
)
IF(BUILD_ENET)
ADD_DEFINITIONS(-DWIN32 -DBT_ENABLE_ENET)
ENDIF(BUILD_ENET)
IF(BUILD_CLSOCKET)
ADD_DEFINITIONS(-DWIN32)
ENDIF(BUILD_CLSOCKET)
ELSE(WIN32)
IF(BUILD_ENET)
ADD_DEFINITIONS(-DHAS_SOCKLEN_T -DBT_ENABLE_ENET)
ENDIF(BUILD_ENET)
IF(BUILD_CLSOCKET)
ADD_DEFINITIONS(${OSDEF})
ENDIF(BUILD_CLSOCKET)
ENDIF(WIN32)
IF(BUILD_ENET)
set(RobotSimulator_SRCS ${RobotSimulator_SRCS}
../../examples/SharedMemory/PhysicsClientUDP.cpp
../../examples/SharedMemory/PhysicsClientUDP_C_API.cpp
../../examples/SharedMemory/PhysicsClientUDP.h
../../examples/SharedMemory/PhysicsClientUDP_C_API.h
../../examples/ThirdPartyLibs/enet/win32.c
../../examples/ThirdPartyLibs/enet/unix.c
../../examples/ThirdPartyLibs/enet/callbacks.c
../../examples/ThirdPartyLibs/enet/compress.c
../../examples/ThirdPartyLibs/enet/host.c
../../examples/ThirdPartyLibs/enet/list.c
../../examples/ThirdPartyLibs/enet/packet.c
../../examples/ThirdPartyLibs/enet/peer.c
../../examples/ThirdPartyLibs/enet/protocol.c
)
ENDIF(BUILD_ENET)
IF(BUILD_CLSOCKET)
set(RobotSimulator_SRCS ${RobotSimulator_SRCS}
../../examples/SharedMemory/PhysicsClientTCP.cpp
../../examples/SharedMemory/PhysicsClientTCP.h
../../examples/SharedMemory/PhysicsClientTCP_C_API.cpp
../../examples/SharedMemory/PhysicsClientTCP_C_API.h
../../examples/ThirdPartyLibs/clsocket/src/SimpleSocket.cpp
../../examples/ThirdPartyLibs/clsocket/src/ActiveSocket.cpp
../../examples/ThirdPartyLibs/clsocket/src/PassiveSocket.cpp
)
ENDIF()
#some code to support OpenGL and Glew cross platform
IF (WIN32)
@@ -168,6 +65,8 @@ ADD_EXECUTABLE(App_RobotSimulator ${RobotSimulator_SRCS})
SET_TARGET_PROPERTIES(App_RobotSimulator PROPERTIES VERSION ${BULLET_VERSION})
SET_TARGET_PROPERTIES(App_RobotSimulator PROPERTIES DEBUG_POSTFIX "_d")
SET_TARGET_PROPERTIES(App_RobotSimulator PROPERTIES COMPILE_DEFINITIONS "B3_USE_ROBOTSIM_GUI")
IF(WIN32)
@@ -176,8 +75,56 @@ IF(WIN32)
ENDIF(BUILD_ENET OR BUILD_CLSOCKET)
ENDIF(WIN32)
TARGET_LINK_LIBRARIES(App_RobotSimulator BulletRobotics BulletExampleBrowserLib BulletFileLoader BulletWorldImporter BulletSoftBody BulletDynamics BulletCollision BulletInverseDynamicsUtils BulletInverseDynamics LinearMath OpenGLWindow gwen Bullet3Common)
INCLUDE_DIRECTORIES(
${BULLET_PHYSICS_SOURCE_DIR}/src
${BULLET_PHYSICS_SOURCE_DIR}/examples
${BULLET_PHYSICS_SOURCE_DIR}/examples/ThirdPartyLibs
${BULLET_PHYSICS_SOURCE_DIR}/examples/ThirdPartyLibs/enet/include
${BULLET_PHYSICS_SOURCE_DIR}/examples/ThirdPartyLibs/clsocket/src
)
SET(RobotSimulator_NoGUI_SRCS
RobotSimulatorMain.cpp
b3RobotSimulatorClientAPI_NoGUI.cpp
b3RobotSimulatorClientAPI_NoGUI.h
MinitaurSetup.cpp
MinitaurSetup.h
)
ADD_EXECUTABLE(App_RobotSimulator_NoGUI ${RobotSimulator_NoGUI_SRCS})
SET_TARGET_PROPERTIES(App_RobotSimulator_NoGUI PROPERTIES VERSION ${BULLET_VERSION})
SET_TARGET_PROPERTIES(App_RobotSimulator_NoGUI PROPERTIES DEBUG_POSTFIX "_d")
IF(WIN32)
IF(BUILD_ENET OR BUILD_CLSOCKET)
TARGET_LINK_LIBRARIES(App_RobotSimulator_NoGUI ws2_32 )
ENDIF(BUILD_ENET OR BUILD_CLSOCKET)
ELSE()
IF(APPLE)
ELSE(APPLE)
TARGET_LINK_LIBRARIES( App_RobotSimulator_NoGUI pthread ${DL} )
ENDIF(APPLE)
ENDIF(WIN32)
TARGET_LINK_LIBRARIES(App_RobotSimulator_NoGUI BulletRobotics BulletFileLoader BulletWorldImporter BulletSoftBody BulletDynamics BulletCollision BulletInverseDynamicsUtils BulletInverseDynamics LinearMath Bullet3Common)
TARGET_LINK_LIBRARIES(App_RobotSimulator BulletExampleBrowserLib BulletFileLoader BulletWorldImporter BulletSoftBody BulletDynamics BulletCollision BulletInverseDynamicsUtils BulletInverseDynamics LinearMath OpenGLWindow gwen BussIK Bullet3Common)

View File

@@ -1,5 +1,5 @@
#include "MinitaurSetup.h"
#include "b3RobotSimulatorClientAPI.h"
#include "b3RobotSimulatorClientAPI_NoGUI.h"
#include "Bullet3Common/b3HashMap.h"
@@ -27,7 +27,7 @@ MinitaurSetup::~MinitaurSetup()
delete m_data;
}
void MinitaurSetup::setDesiredMotorAngle(class b3RobotSimulatorClientAPI* sim, const char* motorName, double desiredAngle, double maxTorque, double kp, double kd)
void MinitaurSetup::setDesiredMotorAngle(class b3RobotSimulatorClientAPI_NoGUI* sim, const char* motorName, double desiredAngle, double maxTorque, double kp, double kd)
{
b3RobotSimulatorJointMotorArgs controlArgs(CONTROL_MODE_POSITION_VELOCITY_PD);
controlArgs.m_maxTorqueValue = maxTorque;
@@ -158,7 +158,7 @@ static const char* minitaurURDF="quadruped/minitaur_rainbow_dash_v1.urdf";
#endif
void MinitaurSetup::resetPose(class b3RobotSimulatorClientAPI* sim)
void MinitaurSetup::resetPose(class b3RobotSimulatorClientAPI_NoGUI* sim)
{
//release all motors
int numJoints = sim->getNumJoints(m_data->m_quadrupedUniqueId);
@@ -255,7 +255,7 @@ void MinitaurSetup::resetPose(class b3RobotSimulatorClientAPI* sim)
}
int MinitaurSetup::setupMinitaur(class b3RobotSimulatorClientAPI* sim, const b3Vector3& startPos, const b3Quaternion& startOrn)
int MinitaurSetup::setupMinitaur(class b3RobotSimulatorClientAPI_NoGUI* sim, const b3Vector3& startPos, const b3Quaternion& startOrn)
{
b3RobotSimulatorLoadUrdfFileArgs args;

View File

@@ -6,15 +6,15 @@
class MinitaurSetup
{
struct MinitaurSetupInternalData* m_data;
void resetPose(class b3RobotSimulatorClientAPI* sim);
void resetPose(class b3RobotSimulatorClientAPI_NoGUI* sim);
public:
MinitaurSetup();
virtual ~MinitaurSetup();
int setupMinitaur(class b3RobotSimulatorClientAPI* sim, const class b3Vector3& startPos=b3MakeVector3(0,0,0), const class b3Quaternion& startOrn = b3Quaternion(0,0,0,1));
int setupMinitaur(class b3RobotSimulatorClientAPI_NoGUI* sim, const class b3Vector3& startPos=b3MakeVector3(0,0,0), const class b3Quaternion& startOrn = b3Quaternion(0,0,0,1));
void setDesiredMotorAngle(class b3RobotSimulatorClientAPI* sim, const char* motorName, double desiredAngle, double maxTorque=3,double kp=0.1, double kd=0.9);
void setDesiredMotorAngle(class b3RobotSimulatorClientAPI_NoGUI* sim, const char* motorName, double desiredAngle, double maxTorque=3,double kp=0.1, double kd=0.9);
};
#endif //MINITAUR_SIMULATION_SETUP_H

View File

@@ -1,5 +1,11 @@
#include "b3RobotSimulatorClientAPI.h"
#ifdef B3_USE_ROBOTSIM_GUI
#include "b3RobotSimulatorClientAPI.h"
#else
#include "b3RobotSimulatorClientAPI_NoGUI.h"
#endif
#include "../Utils/b3Clock.h"
#include <string.h>
@@ -7,11 +13,23 @@
#include <assert.h>
#define ASSERT_EQ(a,b) assert((a)==(b));
#include "MinitaurSetup.h"
int main(int argc, char* argv[])
{
#ifdef B3_USE_ROBOTSIM_GUI
b3RobotSimulatorClientAPI* sim = new b3RobotSimulatorClientAPI();
sim->connect(eCONNECT_GUI);
bool isConnected = sim->connect(eCONNECT_GUI);
#else
b3RobotSimulatorClientAPI_NoGUI* sim = new b3RobotSimulatorClientAPI_NoGUI();
bool isConnected = sim->connect(eCONNECT_DIRECT);
#endif
if (!isConnected)
{
printf("Cannot connect\n");
return -1;
}
//Can also use eCONNECT_DIRECT,eCONNECT_SHARED_MEMORY,eCONNECT_UDP,eCONNECT_TCP, for example:
//sim->connect(eCONNECT_UDP, "localhost", 1234);
sim->configureDebugVisualizer( COV_ENABLE_GUI, 0);

File diff suppressed because it is too large Load Diff

View File

@@ -1,246 +1,32 @@
#ifndef B3_ROBOT_SIMULATOR_CLIENT_API_H
#define B3_ROBOT_SIMULATOR_CLIENT_API_H
#ifndef B3_ROBOT_SIMULATOR_CLIENT_API_GUI_H
#define B3_ROBOT_SIMULATOR_CLIENT_API_GUI_H
#include "../SharedMemory/SharedMemoryPublic.h"
#include "Bullet3Common/b3Vector3.h"
#include "Bullet3Common/b3Quaternion.h"
#include "Bullet3Common/b3Transform.h"
#include "Bullet3Common/b3AlignedObjectArray.h"
#include "b3RobotSimulatorClientAPI_NoGUI.h"
#include <string>
struct b3RobotSimulatorLoadUrdfFileArgs
{
b3Vector3 m_startPosition;
b3Quaternion m_startOrientation;
bool m_forceOverrideFixedBase;
bool m_useMultiBody;
int m_flags;
b3RobotSimulatorLoadUrdfFileArgs(const b3Vector3& startPos, const b3Quaternion& startOrn)
: m_startPosition(startPos),
m_startOrientation(startOrn),
m_forceOverrideFixedBase(false),
m_useMultiBody(true),
m_flags(0)
{
}
b3RobotSimulatorLoadUrdfFileArgs()
: m_startPosition(b3MakeVector3(0, 0, 0)),
m_startOrientation(b3Quaternion(0, 0, 0, 1)),
m_forceOverrideFixedBase(false),
m_useMultiBody(true),
m_flags(0)
{
}
};
struct b3RobotSimulatorLoadSdfFileArgs
{
bool m_forceOverrideFixedBase;
bool m_useMultiBody;
b3RobotSimulatorLoadSdfFileArgs()
: m_forceOverrideFixedBase(false),
m_useMultiBody(true)
{
}
};
struct b3RobotSimulatorLoadFileResults
{
b3AlignedObjectArray<int> m_uniqueObjectIds;
b3RobotSimulatorLoadFileResults()
{
}
};
struct b3RobotSimulatorJointMotorArgs
{
int m_controlMode;
double m_targetPosition;
double m_kp;
double m_targetVelocity;
double m_kd;
double m_maxTorqueValue;
b3RobotSimulatorJointMotorArgs(int controlMode)
: m_controlMode(controlMode),
m_targetPosition(0),
m_kp(0.1),
m_targetVelocity(0),
m_kd(0.9),
m_maxTorqueValue(1000)
{
}
};
enum b3RobotSimulatorInverseKinematicsFlags
{
B3_HAS_IK_TARGET_ORIENTATION = 1,
B3_HAS_NULL_SPACE_VELOCITY = 2,
B3_HAS_JOINT_DAMPING = 4,
};
struct b3RobotSimulatorInverseKinematicArgs
{
int m_bodyUniqueId;
// double* m_currentJointPositions;
// int m_numPositions;
double m_endEffectorTargetPosition[3];
double m_endEffectorTargetOrientation[4];
int m_endEffectorLinkIndex;
int m_flags;
int m_numDegreeOfFreedom;
b3AlignedObjectArray<double> m_lowerLimits;
b3AlignedObjectArray<double> m_upperLimits;
b3AlignedObjectArray<double> m_jointRanges;
b3AlignedObjectArray<double> m_restPoses;
b3AlignedObjectArray<double> m_jointDamping;
b3RobotSimulatorInverseKinematicArgs()
: m_bodyUniqueId(-1),
m_endEffectorLinkIndex(-1),
m_flags(0)
{
m_endEffectorTargetPosition[0] = 0;
m_endEffectorTargetPosition[1] = 0;
m_endEffectorTargetPosition[2] = 0;
m_endEffectorTargetOrientation[0] = 0;
m_endEffectorTargetOrientation[1] = 0;
m_endEffectorTargetOrientation[2] = 0;
m_endEffectorTargetOrientation[3] = 1;
}
};
struct b3RobotSimulatorInverseKinematicsResults
{
int m_bodyUniqueId;
b3AlignedObjectArray<double> m_calculatedJointPositions;
};
struct b3JointStates2
{
int m_bodyUniqueId;
int m_numDegreeOfFreedomQ;
int m_numDegreeOfFreedomU;
b3Transform m_rootLocalInertialFrame;
b3AlignedObjectArray<double> m_actualStateQ;
b3AlignedObjectArray<double> m_actualStateQdot;
b3AlignedObjectArray<double> m_jointReactionForces;
};
///The b3RobotSimulatorClientAPI is pretty much the C++ version of pybullet
///The b3RobotSimulatorClientAPI_GUI is pretty much the C++ version of pybullet
///as documented in the pybullet Quickstart Guide
///https://docs.google.com/document/d/10sXEhzFRSnvFcl3XxNGhnD4N2SedqwdAvK3dsihxVUA
class b3RobotSimulatorClientAPI
class b3RobotSimulatorClientAPI : public b3RobotSimulatorClientAPI_NoGUI
{
struct b3RobotSimulatorClientAPI_InternalData* m_data;
public:
b3RobotSimulatorClientAPI();
virtual ~b3RobotSimulatorClientAPI();
bool connect(int mode, const std::string& hostName = "localhost", int portOrKey = -1);
void disconnect();
bool isConnected() const;
void setTimeOut(double timeOutInSec);
void syncBodies();
void resetSimulation();
b3Quaternion getQuaternionFromEuler(const b3Vector3& rollPitchYaw);
b3Vector3 getEulerFromQuaternion(const b3Quaternion& quat);
int loadURDF(const std::string& fileName, const struct b3RobotSimulatorLoadUrdfFileArgs& args = b3RobotSimulatorLoadUrdfFileArgs());
bool loadSDF(const std::string& fileName, b3RobotSimulatorLoadFileResults& results, const struct b3RobotSimulatorLoadSdfFileArgs& args = b3RobotSimulatorLoadSdfFileArgs());
bool loadMJCF(const std::string& fileName, b3RobotSimulatorLoadFileResults& results);
bool loadBullet(const std::string& fileName, b3RobotSimulatorLoadFileResults& results);
bool getBodyInfo(int bodyUniqueId, struct b3BodyInfo* bodyInfo);
bool getBasePositionAndOrientation(int bodyUniqueId, b3Vector3& basePosition, b3Quaternion& baseOrientation) const;
bool resetBasePositionAndOrientation(int bodyUniqueId, b3Vector3& basePosition, b3Quaternion& baseOrientation);
bool getBaseVelocity(int bodyUniqueId, b3Vector3& baseLinearVelocity, b3Vector3& baseAngularVelocity) const;
bool resetBaseVelocity(int bodyUniqueId, const b3Vector3& linearVelocity, const b3Vector3& angularVelocity) const;
int getNumJoints(int bodyUniqueId) const;
bool getJointInfo(int bodyUniqueId, int jointIndex, b3JointInfo* jointInfo);
int createConstraint(int parentBodyIndex, int parentJointIndex, int childBodyIndex, int childJointIndex, b3JointInfo* jointInfo);
int changeConstraint(int constraintId, b3JointInfo* jointInfo);
void removeConstraint(int constraintId);
bool getJointState(int bodyUniqueId, int jointIndex, struct b3JointSensorState* state);
bool getJointStates(int bodyUniqueId, b3JointStates2& state);
bool resetJointState(int bodyUniqueId, int jointIndex, double targetValue);
void setJointMotorControl(int bodyUniqueId, int jointIndex, const struct b3RobotSimulatorJointMotorArgs& args);
void stepSimulation();
bool canSubmitCommand() const;
void setRealTimeSimulation(bool enableRealTimeSimulation);
void setInternalSimFlags(int flags);
void setGravity(const b3Vector3& gravityAcceleration);
void setTimeStep(double timeStepInSeconds);
void setNumSimulationSubSteps(int numSubSteps);
void setNumSolverIterations(int numIterations);
void setContactBreakingThreshold(double threshold);
bool calculateInverseKinematics(const struct b3RobotSimulatorInverseKinematicArgs& args, struct b3RobotSimulatorInverseKinematicsResults& results);
bool getBodyJacobian(int bodyUniqueId, int linkIndex, const double* localPosition, const double* jointPositions, const double* jointVelocities, const double* jointAccelerations, double* linearJacobian, double* angularJacobian);
bool getLinkState(int bodyUniqueId, int linkIndex, b3LinkState* linkState);
void configureDebugVisualizer(enum b3ConfigureDebugVisualizerEnum flag, int enable);
void resetDebugVisualizerCamera(double cameraDistance, double cameraPitch, double cameraYaw, const b3Vector3& targetPos);
int startStateLogging(b3StateLoggingType loggingType, const std::string& fileName, const b3AlignedObjectArray<int>& objectUniqueIds=b3AlignedObjectArray<int>(), int maxLogDof = -1);
void stopStateLogging(int stateLoggerUniqueId);
void getVREvents(b3VREventsData* vrEventsData, int deviceTypeFilter);
void getKeyboardEvents(b3KeyboardEventsData* keyboardEventsData);
void submitProfileTiming(const std::string& profileName, int durationInMicroSeconds=1);
//////////////// INTERNAL
void loadSoftBody(const std::string& fileName, double scale, double mass, double collisionMargin);
//setGuiHelper is only used when embedded in existing example browser
void setGuiHelper(struct GUIHelperInterface* guiHelper);
//renderScene is only used when embedded in existing example browser
virtual bool connect(int mode, const std::string& hostName = "localhost", int portOrKey = -1);
virtual void renderScene();
//debugDraw is only used when embedded in existing example browser
virtual void debugDraw(int debugDrawMode);
virtual bool mouseMoveCallback(float x,float y);
virtual bool mouseButtonCallback(int button, int state, float x, float y);
////////////////INTERNAL
};
#endif //B3_ROBOT_SIMULATOR_CLIENT_API_H

View File

@@ -0,0 +1,18 @@
#ifndef B3_ROBOT_SIMULATOR_CLIENT_API_INTERNAL_DATA_H
#define B3_ROBOT_SIMULATOR_CLIENT_API_INTERNAL_DATA_H
#include "../SharedMemory/PhysicsClientC_API.h"
struct b3RobotSimulatorClientAPI_InternalData
{
b3PhysicsClientHandle m_physicsClientHandle;
struct GUIHelperInterface* m_guiHelper;
b3RobotSimulatorClientAPI_InternalData()
: m_physicsClientHandle(0),
m_guiHelper(0)
{
}
};
#endif //B3_ROBOT_SIMULATOR_CLIENT_API_INTERNAL_DATA_H

File diff suppressed because it is too large Load Diff

View File

@@ -0,0 +1,572 @@
#ifndef B3_ROBOT_SIMULATOR_CLIENT_API_H
#define B3_ROBOT_SIMULATOR_CLIENT_API_H
#include "../SharedMemory/SharedMemoryPublic.h"
#include "Bullet3Common/b3Vector3.h"
#include "Bullet3Common/b3Quaternion.h"
#include "Bullet3Common/b3Transform.h"
#include "Bullet3Common/b3AlignedObjectArray.h"
#include <string>
struct b3RobotSimulatorLoadUrdfFileArgs
{
b3Vector3 m_startPosition;
b3Quaternion m_startOrientation;
bool m_forceOverrideFixedBase;
bool m_useMultiBody;
int m_flags;
b3RobotSimulatorLoadUrdfFileArgs(const b3Vector3& startPos, const b3Quaternion& startOrn)
: m_startPosition(startPos),
m_startOrientation(startOrn),
m_forceOverrideFixedBase(false),
m_useMultiBody(true),
m_flags(0)
{
}
b3RobotSimulatorLoadUrdfFileArgs()
: m_startPosition(b3MakeVector3(0, 0, 0)),
m_startOrientation(b3Quaternion(0, 0, 0, 1)),
m_forceOverrideFixedBase(false),
m_useMultiBody(true),
m_flags(0)
{
}
};
struct b3RobotSimulatorLoadSdfFileArgs
{
bool m_forceOverrideFixedBase;
bool m_useMultiBody;
b3RobotSimulatorLoadSdfFileArgs()
: m_forceOverrideFixedBase(false),
m_useMultiBody(true)
{
}
};
struct b3RobotSimulatorLoadFileResults
{
b3AlignedObjectArray<int> m_uniqueObjectIds;
b3RobotSimulatorLoadFileResults()
{
}
};
struct b3RobotSimulatorJointMotorArgs
{
int m_controlMode;
double m_targetPosition;
double m_kp;
double m_targetVelocity;
double m_kd;
double m_maxTorqueValue;
b3RobotSimulatorJointMotorArgs(int controlMode)
: m_controlMode(controlMode),
m_targetPosition(0),
m_kp(0.1),
m_targetVelocity(0),
m_kd(0.9),
m_maxTorqueValue(1000)
{
}
};
enum b3RobotSimulatorInverseKinematicsFlags
{
B3_HAS_IK_TARGET_ORIENTATION = 1,
B3_HAS_NULL_SPACE_VELOCITY = 2,
B3_HAS_JOINT_DAMPING = 4,
};
struct b3RobotSimulatorInverseKinematicArgs
{
int m_bodyUniqueId;
// double* m_currentJointPositions;
// int m_numPositions;
double m_endEffectorTargetPosition[3];
double m_endEffectorTargetOrientation[4];
int m_endEffectorLinkIndex;
int m_flags;
int m_numDegreeOfFreedom;
b3AlignedObjectArray<double> m_lowerLimits;
b3AlignedObjectArray<double> m_upperLimits;
b3AlignedObjectArray<double> m_jointRanges;
b3AlignedObjectArray<double> m_restPoses;
b3AlignedObjectArray<double> m_jointDamping;
b3RobotSimulatorInverseKinematicArgs()
: m_bodyUniqueId(-1),
m_endEffectorLinkIndex(-1),
m_flags(0)
{
m_endEffectorTargetPosition[0] = 0;
m_endEffectorTargetPosition[1] = 0;
m_endEffectorTargetPosition[2] = 0;
m_endEffectorTargetOrientation[0] = 0;
m_endEffectorTargetOrientation[1] = 0;
m_endEffectorTargetOrientation[2] = 0;
m_endEffectorTargetOrientation[3] = 1;
}
};
struct b3RobotSimulatorInverseKinematicsResults
{
int m_bodyUniqueId;
b3AlignedObjectArray<double> m_calculatedJointPositions;
};
struct b3JointStates2
{
int m_bodyUniqueId;
int m_numDegreeOfFreedomQ;
int m_numDegreeOfFreedomU;
b3Transform m_rootLocalInertialFrame;
b3AlignedObjectArray<double> m_actualStateQ;
b3AlignedObjectArray<double> m_actualStateQdot;
b3AlignedObjectArray<double> m_jointReactionForces;
};
struct b3RobotSimulatorJointMotorArrayArgs
{
int m_controlMode;
int m_numControlledDofs;
int *m_jointIndices;
double *m_targetPositions;
double *m_kps;
double *m_targetVelocities;
double *m_kds;
double *m_forces;
b3RobotSimulatorJointMotorArrayArgs(int controlMode, int numControlledDofs)
: m_controlMode(controlMode), m_numControlledDofs(numControlledDofs)
{
}
};
struct b3RobotSimulatorGetCameraImageArgs
{
int m_width;
int m_height;
float *m_viewMatrix;
float *m_projectionMatrix;
float *m_lightDirection;
float *m_lightColor;
float m_lightDistance;
int m_hasShadow;
float m_lightAmbientCoeff;
float m_lightDiffuseCoeff;
float m_lightSpecularCoeff;
int m_renderer;
b3RobotSimulatorGetCameraImageArgs(int width, int height)
: m_width(width),
m_height(height),
m_viewMatrix(NULL),
m_projectionMatrix(NULL),
m_lightDirection(NULL),
m_lightColor(NULL),
m_lightDistance(-1),
m_hasShadow(-1),
m_lightAmbientCoeff(-1),
m_lightDiffuseCoeff(-1),
m_lightSpecularCoeff(-1),
m_renderer(-1)
{
}
};
struct b3RobotSimulatorSetPhysicsEngineParameters
{
double m_fixedTimeStep;
int m_numSolverIterations;
int m_useSplitImpulse;
double m_splitImpulsePenetrationThreshold;
int m_numSubSteps;
int m_collisionFilterMode;
double m_contactBreakingThreshold;
int m_maxNumCmdPer1ms;
int m_enableFileCaching;
double m_restitutionVelocityThreshold;
double m_erp;
double m_contactERP;
double m_frictionERP;
b3RobotSimulatorSetPhysicsEngineParameters()
: m_fixedTimeStep(-1),
m_numSolverIterations(-1),
m_useSplitImpulse(-1),
m_splitImpulsePenetrationThreshold(-1),
m_numSubSteps(-1),
m_collisionFilterMode(-1),
m_contactBreakingThreshold(-1),
m_maxNumCmdPer1ms(-1),
m_enableFileCaching(-1),
m_restitutionVelocityThreshold(-1),
m_erp(-1),
m_contactERP(-1),
m_frictionERP(-1)
{}
};
struct b3RobotSimulatorChangeDynamicsArgs
{
double m_mass;
double m_lateralFriction;
double m_spinningFriction;
double m_rollingFriction;
double m_restitution;
double m_linearDamping;
double m_angularDamping;
double m_contactStiffness;
double m_contactDamping;
int m_frictionAnchor;
b3RobotSimulatorChangeDynamicsArgs()
: m_mass(-1),
m_lateralFriction(-1),
m_spinningFriction(-1),
m_rollingFriction(-1),
m_restitution(-1),
m_linearDamping(-1),
m_angularDamping(-1),
m_contactStiffness(-1),
m_contactDamping(-1),
m_frictionAnchor(-1)
{}
};
struct b3RobotSimulatorAddUserDebugLineArgs
{
double m_colorRGB[3];
double m_lineWidth;
double m_lifeTime;
int m_parentObjectUniqueId;
int m_parentLinkIndex;
b3RobotSimulatorAddUserDebugLineArgs()
:
m_lineWidth(1),
m_lifeTime(0),
m_parentObjectUniqueId(-1),
m_parentLinkIndex(-1)
{
m_colorRGB[0] = 1;
m_colorRGB[1] = 1;
m_colorRGB[2] = 1;
}
};
enum b3AddUserDebugTextFlags {
DEBUG_TEXT_HAS_ORIENTATION = 1
};
struct b3RobotSimulatorAddUserDebugTextArgs
{
double m_colorRGB[3];
double m_size;
double m_lifeTime;
double m_textOrientation[4];
int m_parentObjectUniqueId;
int m_parentLinkIndex;
int m_flags;
b3RobotSimulatorAddUserDebugTextArgs()
: m_size(1),
m_lifeTime(0),
m_parentObjectUniqueId(-1),
m_parentLinkIndex(-1),
m_flags(0)
{
m_colorRGB[0] = 1;
m_colorRGB[1] = 1;
m_colorRGB[2] = 1;
m_textOrientation[0] = 0;
m_textOrientation[1] = 0;
m_textOrientation[2] = 0;
m_textOrientation[3] = 1;
}
};
struct b3RobotSimulatorGetContactPointsArgs
{
int m_bodyUniqueIdA;
int m_bodyUniqueIdB;
int m_linkIndexA;
int m_linkIndexB;
b3RobotSimulatorGetContactPointsArgs()
: m_bodyUniqueIdA(-1),
m_bodyUniqueIdB(-1),
m_linkIndexA(-2),
m_linkIndexB(-2)
{}
};
struct b3RobotSimulatorCreateCollisionShapeArgs
{
int m_shapeType;
double m_radius;
b3Vector3 m_halfExtents;
double m_height;
char* m_fileName;
b3Vector3 m_meshScale;
b3Vector3 m_planeNormal;
int m_flags;
b3RobotSimulatorCreateCollisionShapeArgs()
: m_shapeType(-1),
m_radius(0.5),
m_height(1),
m_fileName(NULL),
m_flags(0)
{
m_halfExtents.m_floats[0] = 1;
m_halfExtents.m_floats[1] = 1;
m_halfExtents.m_floats[2] = 1;
m_meshScale.m_floats[0] = 1;
m_meshScale.m_floats[1] = 1;
m_meshScale.m_floats[2] = 1;
m_planeNormal.m_floats[0] = 0;
m_planeNormal.m_floats[1] = 0;
m_planeNormal.m_floats[2] = 1;
}
};
struct b3RobotSimulatorCreateMultiBodyArgs
{
double m_baseMass;
int m_baseCollisionShapeIndex;
int m_baseVisualShapeIndex;
b3Vector3 m_basePosition;
b3Quaternion m_baseOrientation;
b3Vector3 m_baseInertialFramePosition;
b3Quaternion m_baseInertialFrameOrientation;
int m_numLinks;
double *m_linkMasses;
int *m_linkCollisionShapeIndices;
int *m_linkVisualShapeIndices;
b3Vector3 *m_linkPositions;
b3Quaternion *m_linkOrientations;
b3Vector3 *m_linkInertialFramePositions;
b3Quaternion *m_linkInertialFrameOrientations;
int *m_linkParentIndices;
int *m_linkJointTypes;
b3Vector3 *m_linkJointAxes;
int m_useMaximalCoordinates;
b3RobotSimulatorCreateMultiBodyArgs()
: m_numLinks(0), m_baseMass(0), m_baseCollisionShapeIndex(-1), m_baseVisualShapeIndex(-1), m_useMaximalCoordinates(0),
m_linkMasses(NULL),
m_linkCollisionShapeIndices(NULL),
m_linkVisualShapeIndices(NULL),
m_linkPositions(NULL),
m_linkOrientations(NULL),
m_linkInertialFramePositions(NULL),
m_linkInertialFrameOrientations(NULL),
m_linkParentIndices(NULL),
m_linkJointTypes(NULL),
m_linkJointAxes(NULL)
{
m_basePosition.setValue(0,0,0);
m_baseOrientation.setValue(0,0,0,1);
m_baseInertialFramePosition.setValue(0,0,0);
m_baseInertialFrameOrientation.setValue(0,0,0,1);
}
};
///The b3RobotSimulatorClientAPI is pretty much the C++ version of pybullet
///as documented in the pybullet Quickstart Guide
///https://docs.google.com/document/d/10sXEhzFRSnvFcl3XxNGhnD4N2SedqwdAvK3dsihxVUA
class b3RobotSimulatorClientAPI_NoGUI
{
protected:
struct b3RobotSimulatorClientAPI_InternalData* m_data;
public:
b3RobotSimulatorClientAPI_NoGUI();
virtual ~b3RobotSimulatorClientAPI_NoGUI();
bool connect(int mode, const std::string& hostName = "localhost", int portOrKey = -1);
void disconnect();
bool isConnected() const;
void setTimeOut(double timeOutInSec);
void syncBodies();
void resetSimulation();
b3Quaternion getQuaternionFromEuler(const b3Vector3& rollPitchYaw);
b3Vector3 getEulerFromQuaternion(const b3Quaternion& quat);
int loadURDF(const std::string& fileName, const struct b3RobotSimulatorLoadUrdfFileArgs& args = b3RobotSimulatorLoadUrdfFileArgs());
bool loadSDF(const std::string& fileName, b3RobotSimulatorLoadFileResults& results, const struct b3RobotSimulatorLoadSdfFileArgs& args = b3RobotSimulatorLoadSdfFileArgs());
bool loadMJCF(const std::string& fileName, b3RobotSimulatorLoadFileResults& results);
bool loadBullet(const std::string& fileName, b3RobotSimulatorLoadFileResults& results);
bool getBodyInfo(int bodyUniqueId, struct b3BodyInfo* bodyInfo);
bool getBasePositionAndOrientation(int bodyUniqueId, b3Vector3& basePosition, b3Quaternion& baseOrientation) const;
bool resetBasePositionAndOrientation(int bodyUniqueId, b3Vector3& basePosition, b3Quaternion& baseOrientation);
bool getBaseVelocity(int bodyUniqueId, b3Vector3& baseLinearVelocity, b3Vector3& baseAngularVelocity) const;
bool resetBaseVelocity(int bodyUniqueId, const b3Vector3& linearVelocity, const b3Vector3& angularVelocity) const;
int getNumJoints(int bodyUniqueId) const;
bool getJointInfo(int bodyUniqueId, int jointIndex, b3JointInfo* jointInfo);
int createConstraint(int parentBodyIndex, int parentJointIndex, int childBodyIndex, int childJointIndex, b3JointInfo* jointInfo);
int changeConstraint(int constraintId, b3JointInfo* jointInfo);
void removeConstraint(int constraintId);
bool getJointState(int bodyUniqueId, int jointIndex, struct b3JointSensorState* state);
bool getJointStates(int bodyUniqueId, b3JointStates2& state);
bool resetJointState(int bodyUniqueId, int jointIndex, double targetValue);
void setJointMotorControl(int bodyUniqueId, int jointIndex, const struct b3RobotSimulatorJointMotorArgs& args);
bool setJointMotorControlArray(int bodyUniqueId, int controlMode, int numControlledDofs,
int *jointIndices, double *targetVelocities, double *targetPositions,
double *forces, double *kps, double *kds);
void stepSimulation();
bool canSubmitCommand() const;
void setRealTimeSimulation(bool enableRealTimeSimulation);
void setInternalSimFlags(int flags);
void setGravity(const b3Vector3& gravityAcceleration);
void setTimeStep(double timeStepInSeconds);
void setNumSimulationSubSteps(int numSubSteps);
void setNumSolverIterations(int numIterations);
void setContactBreakingThreshold(double threshold);
bool calculateInverseKinematics(const struct b3RobotSimulatorInverseKinematicArgs& args, struct b3RobotSimulatorInverseKinematicsResults& results);
bool getBodyJacobian(int bodyUniqueId, int linkIndex, const double* localPosition, const double* jointPositions, const double* jointVelocities, const double* jointAccelerations, double* linearJacobian, double* angularJacobian);
bool getLinkState(int bodyUniqueId, int linkIndex, b3LinkState* linkState);
void configureDebugVisualizer(enum b3ConfigureDebugVisualizerEnum flag, int enable);
void resetDebugVisualizerCamera(double cameraDistance, double cameraPitch, double cameraYaw, const b3Vector3& targetPos);
int startStateLogging(b3StateLoggingType loggingType, const std::string& fileName, const b3AlignedObjectArray<int>& objectUniqueIds=b3AlignedObjectArray<int>(), int maxLogDof = -1);
void stopStateLogging(int stateLoggerUniqueId);
void getVREvents(b3VREventsData* vrEventsData, int deviceTypeFilter);
void getKeyboardEvents(b3KeyboardEventsData* keyboardEventsData);
void submitProfileTiming(const std::string& profileName, int durationInMicroSeconds=1);
// JFC: added these 24 methods
void getMouseEvents(b3MouseEventsData* mouseEventsData);
bool getLinkState(int bodyUniqueId, int linkIndex, int computeLinkVelocity, int computeInverseKinematics, b3LinkState* linkState);
bool getCameraImage(int width, int height, struct b3RobotSimulatorGetCameraImageArgs args, b3CameraImageData &imageData);
bool calculateInverseDynamics(int bodyUniqueId, double *jointPositions, double *jointVelocities, double *jointAccelerations, double *jointForcesOutput);
int getNumBodies() const;
int getBodyUniqueId(int bodyId) const;
bool removeBody(int bodyUniqueId);
bool getDynamicsInfo(int bodyUniqueId, int linkIndex, b3DynamicsInfo *dynamicsInfo);
bool changeDynamics(int bodyUniqueId, int linkIndex, struct b3RobotSimulatorChangeDynamicsArgs &args);
int addUserDebugParameter(char *paramName, double rangeMin, double rangeMax, double startValue);
double readUserDebugParameter(int itemUniqueId);
bool removeUserDebugItem(int itemUniqueId);
int addUserDebugText(char *text, double *textPosition, struct b3RobotSimulatorAddUserDebugTextArgs &args);
int addUserDebugText(char *text, b3Vector3 &textPosition, struct b3RobotSimulatorAddUserDebugTextArgs &args);
int addUserDebugLine(double *fromXYZ, double *toXYZ, struct b3RobotSimulatorAddUserDebugLineArgs &args);
int addUserDebugLine(b3Vector3 &fromXYZ, b3Vector3 &toXYZ, struct b3RobotSimulatorAddUserDebugLineArgs &args);
bool setJointMotorControlArray(int bodyUniqueId, struct b3RobotSimulatorJointMotorArrayArgs &args);
bool setPhysicsEngineParameter(struct b3RobotSimulatorSetPhysicsEngineParameters &args);
bool applyExternalForce(int objectUniqueId, int linkIndex, double *force, double *position, int flags);
bool applyExternalForce(int objectUniqueId, int linkIndex, b3Vector3 &force, b3Vector3 &position, int flags);
bool applyExternalTorque(int objectUniqueId, int linkIndex, double *torque, int flags);
bool applyExternalTorque(int objectUniqueId, int linkIndex, b3Vector3 &torque, int flags);
bool enableJointForceTorqueSensor(int bodyUniqueId, int linkIndex, bool enable);
bool getDebugVisualizerCamera(struct b3OpenGLVisualizerCameraInfo *cameraInfo);
bool getContactPoints(struct b3RobotSimulatorGetContactPointsArgs &args, struct b3ContactInformation *contactInfo);
bool getClosestPoints(struct b3RobotSimulatorGetContactPointsArgs &args, double distance, struct b3ContactInformation *contactInfo);
bool getOverlappingObjects(double *aabbMin, double *aabbMax, struct b3AABBOverlapData *overlapData);
bool getOverlappingObjects(b3Vector3 &aabbMin, b3Vector3 &aabbMax, struct b3AABBOverlapData *overlapData);
bool getAABB(int bodyUniqueId, int linkIndex, double *aabbMin, double *aabbMax);
bool getAABB(int bodyUniqueId, int linkIndex, b3Vector3 &aabbMin, b3Vector3 &aabbMax);
int createCollisionShape(int shapeType, struct b3RobotSimulatorCreateCollisionShapeArgs &args);
int createMultiBody(struct b3RobotSimulatorCreateMultiBodyArgs &args);
int getNumConstraints() const;
int getConstraintUniqueId(int serialIndex);
void loadSoftBody(const std::string& fileName, double scale, double mass, double collisionMargin);
virtual void setGuiHelper(struct GUIHelperInterface* guiHelper);
virtual struct GUIHelperInterface* getGuiHelper();
};
#endif //B3_ROBOT_SIMULATOR_CLIENT_API_H

View File

@@ -193,6 +193,8 @@ if not _OPTIONS["no-enet"] then
"RobotSimulatorMain.cpp",
"b3RobotSimulatorClientAPI.cpp",
"b3RobotSimulatorClientAPI.h",
"b3RobotSimulatorClientAPI_NoGUI.cpp",
"b3RobotSimulatorClientAPI_NoGUI.h",
"MinitaurSetup.cpp",
"MinitaurSetup.h",
myfiles
@@ -283,6 +285,8 @@ project ("App_VRGloveHandSimulator")
"VRGloveSimulatorMain.cpp",
"b3RobotSimulatorClientAPI.cpp",
"b3RobotSimulatorClientAPI.h",
"b3RobotSimulatorClientAPI_NoGUI.cpp",
"b3RobotSimulatorClientAPI_NoGUI.h",
myfiles
}

View File

@@ -32,7 +32,6 @@ B3_DECLARE_HANDLE(b3SharedMemoryStatusHandle);
#include "PhysicsClientTCP_C_API.h"
#endif
#include "SharedMemoryInProcessPhysicsC_API.h"
#ifdef __cplusplus
extern "C" {

View File

@@ -9,6 +9,7 @@
#include "SharedMemory/PhysicsClientC_API.h"
#include "Bullet3Common/b3Vector3.h"
#include "Bullet3Common/b3Quaternion.h"
#include "SharedMemory/SharedMemoryInProcessPhysicsC_API.h"
extern const int CONTROL_RATE;
const int CONTROL_RATE = 500;

View File

@@ -0,0 +1,362 @@
Functional Bicycle (http://www.thingiverse.com/thing:309158) by thomasgivan is licensed under the Creative Commons - Attribution - Share Alike license.
http://creativecommons.org/licenses/by-sa/3.0/
Creative Commons Legal Code
Attribution-ShareAlike 3.0 Unported
CREATIVE COMMONS CORPORATION IS NOT A LAW FIRM AND DOES NOT PROVIDE
LEGAL SERVICES. DISTRIBUTION OF THIS LICENSE DOES NOT CREATE AN
ATTORNEY-CLIENT RELATIONSHIP. CREATIVE COMMONS PROVIDES THIS
INFORMATION ON AN "AS-IS" BASIS. CREATIVE COMMONS MAKES NO WARRANTIES
REGARDING THE INFORMATION PROVIDED, AND DISCLAIMS LIABILITY FOR
DAMAGES RESULTING FROM ITS USE.
License
THE WORK (AS DEFINED BELOW) IS PROVIDED UNDER THE TERMS OF THIS CREATIVE
COMMONS PUBLIC LICENSE ("CCPL" OR "LICENSE"). THE WORK IS PROTECTED BY
COPYRIGHT AND/OR OTHER APPLICABLE LAW. ANY USE OF THE WORK OTHER THAN AS
AUTHORIZED UNDER THIS LICENSE OR COPYRIGHT LAW IS PROHIBITED.
BY EXERCISING ANY RIGHTS TO THE WORK PROVIDED HERE, YOU ACCEPT AND AGREE
TO BE BOUND BY THE TERMS OF THIS LICENSE. TO THE EXTENT THIS LICENSE MAY
BE CONSIDERED TO BE A CONTRACT, THE LICENSOR GRANTS YOU THE RIGHTS
CONTAINED HERE IN CONSIDERATION OF YOUR ACCEPTANCE OF SUCH TERMS AND
CONDITIONS.
1. Definitions
a. "Adaptation" means a work based upon the Work, or upon the Work and
other pre-existing works, such as a translation, adaptation,
derivative work, arrangement of music or other alterations of a
literary or artistic work, or phonogram or performance and includes
cinematographic adaptations or any other form in which the Work may be
recast, transformed, or adapted including in any form recognizably
derived from the original, except that a work that constitutes a
Collection will not be considered an Adaptation for the purpose of
this License. For the avoidance of doubt, where the Work is a musical
work, performance or phonogram, the synchronization of the Work in
timed-relation with a moving image ("synching") will be considered an
Adaptation for the purpose of this License.
b. "Collection" means a collection of literary or artistic works, such as
encyclopedias and anthologies, or performances, phonograms or
broadcasts, or other works or subject matter other than works listed
in Section 1(f) below, which, by reason of the selection and
arrangement of their contents, constitute intellectual creations, in
which the Work is included in its entirety in unmodified form along
with one or more other contributions, each constituting separate and
independent works in themselves, which together are assembled into a
collective whole. A work that constitutes a Collection will not be
considered an Adaptation (as defined below) for the purposes of this
License.
c. "Creative Commons Compatible License" means a license that is listed
at https://creativecommons.org/compatiblelicenses that has been
approved by Creative Commons as being essentially equivalent to this
License, including, at a minimum, because that license: (i) contains
terms that have the same purpose, meaning and effect as the License
Elements of this License; and, (ii) explicitly permits the relicensing
of adaptations of works made available under that license under this
License or a Creative Commons jurisdiction license with the same
License Elements as this License.
d. "Distribute" means to make available to the public the original and
copies of the Work or Adaptation, as appropriate, through sale or
other transfer of ownership.
e. "License Elements" means the following high-level license attributes
as selected by Licensor and indicated in the title of this License:
Attribution, ShareAlike.
f. "Licensor" means the individual, individuals, entity or entities that
offer(s) the Work under the terms of this License.
g. "Original Author" means, in the case of a literary or artistic work,
the individual, individuals, entity or entities who created the Work
or if no individual or entity can be identified, the publisher; and in
addition (i) in the case of a performance the actors, singers,
musicians, dancers, and other persons who act, sing, deliver, declaim,
play in, interpret or otherwise perform literary or artistic works or
expressions of folklore; (ii) in the case of a phonogram the producer
being the person or legal entity who first fixes the sounds of a
performance or other sounds; and, (iii) in the case of broadcasts, the
organization that transmits the broadcast.
h. "Work" means the literary and/or artistic work offered under the terms
of this License including without limitation any production in the
literary, scientific and artistic domain, whatever may be the mode or
form of its expression including digital form, such as a book,
pamphlet and other writing; a lecture, address, sermon or other work
of the same nature; a dramatic or dramatico-musical work; a
choreographic work or entertainment in dumb show; a musical
composition with or without words; a cinematographic work to which are
assimilated works expressed by a process analogous to cinematography;
a work of drawing, painting, architecture, sculpture, engraving or
lithography; a photographic work to which are assimilated works
expressed by a process analogous to photography; a work of applied
art; an illustration, map, plan, sketch or three-dimensional work
relative to geography, topography, architecture or science; a
performance; a broadcast; a phonogram; a compilation of data to the
extent it is protected as a copyrightable work; or a work performed by
a variety or circus performer to the extent it is not otherwise
considered a literary or artistic work.
i. "You" means an individual or entity exercising rights under this
License who has not previously violated the terms of this License with
respect to the Work, or who has received express permission from the
Licensor to exercise rights under this License despite a previous
violation.
j. "Publicly Perform" means to perform public recitations of the Work and
to communicate to the public those public recitations, by any means or
process, including by wire or wireless means or public digital
performances; to make available to the public Works in such a way that
members of the public may access these Works from a place and at a
place individually chosen by them; to perform the Work to the public
by any means or process and the communication to the public of the
performances of the Work, including by public digital performance; to
broadcast and rebroadcast the Work by any means including signs,
sounds or images.
k. "Reproduce" means to make copies of the Work by any means including
without limitation by sound or visual recordings and the right of
fixation and reproducing fixations of the Work, including storage of a
protected performance or phonogram in digital form or other electronic
medium.
2. Fair Dealing Rights. Nothing in this License is intended to reduce,
limit, or restrict any uses free from copyright or rights arising from
limitations or exceptions that are provided for in connection with the
copyright protection under copyright law or other applicable laws.
3. License Grant. Subject to the terms and conditions of this License,
Licensor hereby grants You a worldwide, royalty-free, non-exclusive,
perpetual (for the duration of the applicable copyright) license to
exercise the rights in the Work as stated below:
a. to Reproduce the Work, to incorporate the Work into one or more
Collections, and to Reproduce the Work as incorporated in the
Collections;
b. to create and Reproduce Adaptations provided that any such Adaptation,
including any translation in any medium, takes reasonable steps to
clearly label, demarcate or otherwise identify that changes were made
to the original Work. For example, a translation could be marked "The
original work was translated from English to Spanish," or a
modification could indicate "The original work has been modified.";
c. to Distribute and Publicly Perform the Work including as incorporated
in Collections; and,
d. to Distribute and Publicly Perform Adaptations.
e. For the avoidance of doubt:
i. Non-waivable Compulsory License Schemes. In those jurisdictions in
which the right to collect royalties through any statutory or
compulsory licensing scheme cannot be waived, the Licensor
reserves the exclusive right to collect such royalties for any
exercise by You of the rights granted under this License;
ii. Waivable Compulsory License Schemes. In those jurisdictions in
which the right to collect royalties through any statutory or
compulsory licensing scheme can be waived, the Licensor waives the
exclusive right to collect such royalties for any exercise by You
of the rights granted under this License; and,
iii. Voluntary License Schemes. The Licensor waives the right to
collect royalties, whether individually or, in the event that the
Licensor is a member of a collecting society that administers
voluntary licensing schemes, via that society, from any exercise
by You of the rights granted under this License.
The above rights may be exercised in all media and formats whether now
known or hereafter devised. The above rights include the right to make
such modifications as are technically necessary to exercise the rights in
other media and formats. Subject to Section 8(f), all rights not expressly
granted by Licensor are hereby reserved.
4. Restrictions. The license granted in Section 3 above is expressly made
subject to and limited by the following restrictions:
a. You may Distribute or Publicly Perform the Work only under the terms
of this License. You must include a copy of, or the Uniform Resource
Identifier (URI) for, this License with every copy of the Work You
Distribute or Publicly Perform. You may not offer or impose any terms
on the Work that restrict the terms of this License or the ability of
the recipient of the Work to exercise the rights granted to that
recipient under the terms of the License. You may not sublicense the
Work. You must keep intact all notices that refer to this License and
to the disclaimer of warranties with every copy of the Work You
Distribute or Publicly Perform. When You Distribute or Publicly
Perform the Work, You may not impose any effective technological
measures on the Work that restrict the ability of a recipient of the
Work from You to exercise the rights granted to that recipient under
the terms of the License. This Section 4(a) applies to the Work as
incorporated in a Collection, but this does not require the Collection
apart from the Work itself to be made subject to the terms of this
License. If You create a Collection, upon notice from any Licensor You
must, to the extent practicable, remove from the Collection any credit
as required by Section 4(c), as requested. If You create an
Adaptation, upon notice from any Licensor You must, to the extent
practicable, remove from the Adaptation any credit as required by
Section 4(c), as requested.
b. You may Distribute or Publicly Perform an Adaptation only under the
terms of: (i) this License; (ii) a later version of this License with
the same License Elements as this License; (iii) a Creative Commons
jurisdiction license (either this or a later license version) that
contains the same License Elements as this License (e.g.,
Attribution-ShareAlike 3.0 US)); (iv) a Creative Commons Compatible
License. If you license the Adaptation under one of the licenses
mentioned in (iv), you must comply with the terms of that license. If
you license the Adaptation under the terms of any of the licenses
mentioned in (i), (ii) or (iii) (the "Applicable License"), you must
comply with the terms of the Applicable License generally and the
following provisions: (I) You must include a copy of, or the URI for,
the Applicable License with every copy of each Adaptation You
Distribute or Publicly Perform; (II) You may not offer or impose any
terms on the Adaptation that restrict the terms of the Applicable
License or the ability of the recipient of the Adaptation to exercise
the rights granted to that recipient under the terms of the Applicable
License; (III) You must keep intact all notices that refer to the
Applicable License and to the disclaimer of warranties with every copy
of the Work as included in the Adaptation You Distribute or Publicly
Perform; (IV) when You Distribute or Publicly Perform the Adaptation,
You may not impose any effective technological measures on the
Adaptation that restrict the ability of a recipient of the Adaptation
from You to exercise the rights granted to that recipient under the
terms of the Applicable License. This Section 4(b) applies to the
Adaptation as incorporated in a Collection, but this does not require
the Collection apart from the Adaptation itself to be made subject to
the terms of the Applicable License.
c. If You Distribute, or Publicly Perform the Work or any Adaptations or
Collections, You must, unless a request has been made pursuant to
Section 4(a), keep intact all copyright notices for the Work and
provide, reasonable to the medium or means You are utilizing: (i) the
name of the Original Author (or pseudonym, if applicable) if supplied,
and/or if the Original Author and/or Licensor designate another party
or parties (e.g., a sponsor institute, publishing entity, journal) for
attribution ("Attribution Parties") in Licensor's copyright notice,
terms of service or by other reasonable means, the name of such party
or parties; (ii) the title of the Work if supplied; (iii) to the
extent reasonably practicable, the URI, if any, that Licensor
specifies to be associated with the Work, unless such URI does not
refer to the copyright notice or licensing information for the Work;
and (iv) , consistent with Ssection 3(b), in the case of an
Adaptation, a credit identifying the use of the Work in the Adaptation
(e.g., "French translation of the Work by Original Author," or
"Screenplay based on original Work by Original Author"). The credit
required by this Section 4(c) may be implemented in any reasonable
manner; provided, however, that in the case of a Adaptation or
Collection, at a minimum such credit will appear, if a credit for all
contributing authors of the Adaptation or Collection appears, then as
part of these credits and in a manner at least as prominent as the
credits for the other contributing authors. For the avoidance of
doubt, You may only use the credit required by this Section for the
purpose of attribution in the manner set out above and, by exercising
Your rights under this License, You may not implicitly or explicitly
assert or imply any connection with, sponsorship or endorsement by the
Original Author, Licensor and/or Attribution Parties, as appropriate,
of You or Your use of the Work, without the separate, express prior
written permission of the Original Author, Licensor and/or Attribution
Parties.
d. Except as otherwise agreed in writing by the Licensor or as may be
otherwise permitted by applicable law, if You Reproduce, Distribute or
Publicly Perform the Work either by itself or as part of any
Adaptations or Collections, You must not distort, mutilate, modify or
take other derogatory action in relation to the Work which would be
prejudicial to the Original Author's honor or reputation. Licensor
agrees that in those jurisdictions (e.g. Japan), in which any exercise
of the right granted in Section 3(b) of this License (the right to
make Adaptations) would be deemed to be a distortion, mutilation,
modification or other derogatory action prejudicial to the Original
Author's honor and reputation, the Licensor will waive or not assert,
as appropriate, this Section, to the fullest extent permitted by the
applicable national law, to enable You to reasonably exercise Your
right under Section 3(b) of this License (right to make Adaptations)
but not otherwise.
5. Representations, Warranties and Disclaimer
UNLESS OTHERWISE MUTUALLY AGREED TO BY THE PARTIES IN WRITING, LICENSOR
OFFERS THE WORK AS-IS AND MAKES NO REPRESENTATIONS OR WARRANTIES OF ANY
KIND CONCERNING THE WORK, EXPRESS, IMPLIED, STATUTORY OR OTHERWISE,
INCLUDING, WITHOUT LIMITATION, WARRANTIES OF TITLE, MERCHANTIBILITY,
FITNESS FOR A PARTICULAR PURPOSE, NONINFRINGEMENT, OR THE ABSENCE OF
LATENT OR OTHER DEFECTS, ACCURACY, OR THE PRESENCE OF ABSENCE OF ERRORS,
WHETHER OR NOT DISCOVERABLE. SOME JURISDICTIONS DO NOT ALLOW THE EXCLUSION
OF IMPLIED WARRANTIES, SO SUCH EXCLUSION MAY NOT APPLY TO YOU.
6. Limitation on Liability. EXCEPT TO THE EXTENT REQUIRED BY APPLICABLE
LAW, IN NO EVENT WILL LICENSOR BE LIABLE TO YOU ON ANY LEGAL THEORY FOR
ANY SPECIAL, INCIDENTAL, CONSEQUENTIAL, PUNITIVE OR EXEMPLARY DAMAGES
ARISING OUT OF THIS LICENSE OR THE USE OF THE WORK, EVEN IF LICENSOR HAS
BEEN ADVISED OF THE POSSIBILITY OF SUCH DAMAGES.
7. Termination
a. This License and the rights granted hereunder will terminate
automatically upon any breach by You of the terms of this License.
Individuals or entities who have received Adaptations or Collections
from You under this License, however, will not have their licenses
terminated provided such individuals or entities remain in full
compliance with those licenses. Sections 1, 2, 5, 6, 7, and 8 will
survive any termination of this License.
b. Subject to the above terms and conditions, the license granted here is
perpetual (for the duration of the applicable copyright in the Work).
Notwithstanding the above, Licensor reserves the right to release the
Work under different license terms or to stop distributing the Work at
any time; provided, however that any such election will not serve to
withdraw this License (or any other license that has been, or is
required to be, granted under the terms of this License), and this
License will continue in full force and effect unless terminated as
stated above.
8. Miscellaneous
a. Each time You Distribute or Publicly Perform the Work or a Collection,
the Licensor offers to the recipient a license to the Work on the same
terms and conditions as the license granted to You under this License.
b. Each time You Distribute or Publicly Perform an Adaptation, Licensor
offers to the recipient a license to the original Work on the same
terms and conditions as the license granted to You under this License.
c. If any provision of this License is invalid or unenforceable under
applicable law, it shall not affect the validity or enforceability of
the remainder of the terms of this License, and without further action
by the parties to this agreement, such provision shall be reformed to
the minimum extent necessary to make such provision valid and
enforceable.
d. No term or provision of this License shall be deemed waived and no
breach consented to unless such waiver or consent shall be in writing
and signed by the party to be charged with such waiver or consent.
e. This License constitutes the entire agreement between the parties with
respect to the Work licensed here. There are no understandings,
agreements or representations with respect to the Work not specified
here. Licensor shall not be bound by any additional provisions that
may appear in any communication from You. This License may not be
modified without the mutual written agreement of the Licensor and You.
f. The rights granted under, and the subject matter referenced, in this
License were drafted utilizing the terminology of the Berne Convention
for the Protection of Literary and Artistic Works (as amended on
September 28, 1979), the Rome Convention of 1961, the WIPO Copyright
Treaty of 1996, the WIPO Performances and Phonograms Treaty of 1996
and the Universal Copyright Convention (as revised on July 24, 1971).
These rights and subject matter take effect in the relevant
jurisdiction in which the License terms are sought to be enforced
according to the corresponding provisions of the implementation of
those treaty provisions in the applicable national law. If the
standard suite of rights granted under applicable copyright law
includes additional rights not granted under this License, such
additional rights are deemed to be included in the License; this
License is not intended to restrict the license of any rights under
applicable law.
Creative Commons Notice
Creative Commons is not a party to this License, and makes no warranty
whatsoever in connection with the Work. Creative Commons will not be
liable to You or any party on any legal theory for any damages
whatsoever, including without limitation any general, special,
incidental or consequential damages arising in connection to this
license. Notwithstanding the foregoing two (2) sentences, if Creative
Commons has expressly identified itself as the Licensor hereunder, it
shall have all rights and obligations of Licensor.
Except for the limited purpose of indicating to the public that the
Work is licensed under the CCPL, Creative Commons does not authorize
the use by either party of the trademark "Creative Commons" or any
related trademark or logo of Creative Commons without the prior
written consent of Creative Commons. Any permitted use will be in
compliance with Creative Commons' then-current trademark usage
guidelines, as may be published on its website or otherwise made
available upon request from time to time. For the avoidance of doubt,
this trademark restriction does not form part of the License.
Creative Commons may be contacted at https://creativecommons.org/.

View File

@@ -0,0 +1,143 @@
<?xml version="0.0" ?>
<robot name="frame">
<link name="frameLink">
<inertial>
<origin rpy="1.57 0 0" xyz="0 0 0"/>
<mass value="5.0"/>
<inertia ixx="0.1" ixy="0" ixz="0" iyy="0.1" iyz="0" izz="0.1"/>
</inertial>
<visual>
<origin rpy="1.57 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="files/frame_scaled_right.stl"/>
</geometry>
<material name="framemat0">
<color rgba="0.9 0.4 0. 1" />
</material>
</visual>
<visual>
<origin rpy="1.57 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="files/frame_scaled_left.stl"/>
</geometry>
<material name="framemat0">
<color rgba="0.9 0.4 0. 1" />
</material>
</visual>
<collision>
<origin rpy="1.57 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="files/frame_scaled_right.stl"/>
</geometry>
</collision>
<collision>
<origin rpy="1.57 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="files/frame_scaled_left.stl"/>
</geometry>
</collision>
</link>
<link name="handlebarLink">
<inertial>
<origin rpy="0 0 0" xyz="0 0 0"/>
<mass value=".5"/>
<inertia ixx="0.1" ixy="0" ixz="0" iyy="0.1" iyz="0" izz="0.1"/>
</inertial>
<visual>
<origin rpy=" -1.5089523943366046 0.017064611667450248 -1.57454489647697 " xyz=" -0.03313875198364258 0.0 -0.23958677053451538"/>
<geometry>
<mesh filename="files/handlebar_scaled.stl"/>
</geometry>
<material name="framemat0">
<color rgba="0.9 0.4 0. 1" />
</material>
</visual>
<collision>
<origin rpy=" -1.5089523943366046 0.017064611667450248 -1.57454489647697 " xyz=" -0.03313875198364258 0.0 -0.23958677053451538"/>
<geometry>
<mesh filename="files/handlebar_scaled.stl"/>
</geometry>
</collision>
</link>
<joint name="frame_to_handlebar" type="continuous">
<axis xyz="0 0 1"/>
<parent link="frameLink"/>
<child link="handlebarLink"/>
<origin rpy="0 -0.261799387799149 0" xyz="0.70 0 0.22"/>
<limit effort="100" velocity="100"/>
<joint_properties damping="0.0" friction="0.0"/>
</joint>
<link name="frontWheelLink">
<inertial>
<origin rpy="1.57 0 0" xyz="0 0 0"/>
<mass value="1.0"/>
<inertia ixx="0.1" ixy="0" ixz="0" iyy="0.1" iyz="0" izz="0.1"/>
</inertial>
<visual>
<origin rpy="1.57 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="files/wheel_scaled.stl"/>
</geometry>
<material name="framemat0">
<color rgba="0.9 0.4 0. 1" />
</material>
</visual>
<collision>
<origin rpy="1.57 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="files/wheel_scaled.stl"/>
</geometry>
</collision>
</link>
<joint name="handlebar_to_frontwheel" type="continuous">
<axis xyz="0 1 0"/>
<parent link="handlebarLink"/>
<child link="frontWheelLink"/>
<origin rpy="0 0 0" xyz="0.07, 0, -0.69"/>
<limit effort="100" velocity="100"/>
<joint_properties damping="0.0" friction="0.0"/>
</joint>
<link name="backWheelLink">
<inertial>
<origin rpy="1.57 0 0" xyz="0 0 0"/>
<mass value="1.0"/>
<inertia ixx="0.1" ixy="0" ixz="0" iyy="0.1" iyz="0" izz="0.1"/>
</inertial>
<visual>
<origin rpy="1.57 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="files/wheel_scaled.stl"/>
</geometry>
<material name="framemat0">
<color rgba="0.9 0.4 0. 1" />
</material>
</visual>
<collision>
<origin rpy="1.57 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="files/wheel_scaled.stl"/>
</geometry>
</collision>
</link>
<joint name="frame_to_backwheel" type="continuous">
<axis xyz="0 1 0"/>
<parent link="frameLink"/>
<child link="backWheelLink"/>
<origin rpy="0 0 0" xyz="-0.69, 0, -0.42"/>
<limit effort="100" velocity="100"/>
<joint_properties damping="0.0" friction="0.0"/>
</joint>
</robot>

View File

@@ -0,0 +1,22 @@
# Blender v2.66 (sub 1) OBJ File: ''
# www.blender.org
mtllib plane.mtl
o Plane
v 100.000000 -100.000000 0.000000
v 100.000000 100.000000 0.000000
v -100.000000 100.000000 0.000000
v -100.000000 -100.000000 0.000000
vt 100.000000 0.000000
vt 100.000000 100.000000
vt 0.000000 100.000000
vt 0.000000 0.000000
usemtl Material
s off
f 1/1 2/2 3/3
f 1/1 3/3 4/4

View File

@@ -0,0 +1,26 @@
<?xml version="0.0" ?>
<robot name="cube.urdf">
<link name="baseLink">
<inertial>
<origin rpy="0 0 0" xyz="0 0 0"/>
<mass value=".0"/>
<inertia ixx="0" ixy="0" ixz="0" iyy="0" iyz="0" izz="0"/>
</inertial>
<visual>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<mesh filename="plane100.obj" scale="1 1 1"/>
</geometry>
<material name="white">
<color rgba="1 1 1 1"/>
</material>
</visual>
<collision>
<origin rpy="0 0 0" xyz="0 0 0"/>
<geometry>
<box size="200 200 0.001"/>
</geometry>
</collision>
</link>
</robot>

View File

@@ -64,10 +64,10 @@ class CartPoleBulletEnv(gym.Env):
# time.sleep(self.timeStep)
self.state = p.getJointState(self.cartpole, 1)[0:2] + p.getJointState(self.cartpole, 0)[0:2]
theta, theta_dot, x, x_dot = self.state
dv = 0.1
deltav = [-10.*dv,-5.*dv, -2.*dv, -0.1*dv, 0, 0.1*dv, 2.*dv,5.*dv, 10.*dv][action]
p.setJointMotorControl2(self.cartpole, 0, p.VELOCITY_CONTROL, targetVelocity=(deltav + self.state[3]))
done = x < -self.x_threshold \
@@ -99,3 +99,8 @@ class CartPoleBulletEnv(gym.Env):
def _render(self, mode='human', close=False):
return
render = _render
reset = _reset
seed = _seed
step = _step

View File

@@ -56,8 +56,8 @@ class KukaCamGymEnv(gym.Env):
observationDim = len(self.getExtendedObservation())
#print("observationDim")
#print(observationDim)
observation_high = np.array([np.finfo(np.float32).max] * observationDim)
observation_high = np.array([np.finfo(np.float32).max] * observationDim)
if (self._isDiscrete):
self.action_space = spaces.Discrete(7)
else:
@@ -74,15 +74,15 @@ class KukaCamGymEnv(gym.Env):
p.setPhysicsEngineParameter(numSolverIterations=150)
p.setTimeStep(self._timeStep)
p.loadURDF(os.path.join(self._urdfRoot,"plane.urdf"),[0,0,-1])
p.loadURDF(os.path.join(self._urdfRoot,"table/table.urdf"), 0.5000000,0.00000,-.820000,0.000000,0.000000,0.0,1.0)
xpos = 0.5 +0.2*random.random()
ypos = 0 +0.25*random.random()
ang = 3.1415925438*random.random()
orn = p.getQuaternionFromEuler([0,0,ang])
self.blockUid =p.loadURDF(os.path.join(self._urdfRoot,"block.urdf"), xpos,ypos,-0.1,orn[0],orn[1],orn[2],orn[3])
p.setGravity(0,0,-10)
self._kuka = kuka.Kuka(urdfRootPath=self._urdfRoot, timeStep=self._timeStep)
self._envStepCounter = 0
@@ -98,7 +98,7 @@ class KukaCamGymEnv(gym.Env):
return [seed]
def getExtendedObservation(self):
#camEyePos = [0.03,0.236,0.54]
#distance = 1.06
#pitch=-56
@@ -118,13 +118,13 @@ class KukaCamGymEnv(gym.Env):
viewMat = [-0.5120397806167603, 0.7171027660369873, -0.47284144163131714, 0.0, -0.8589617609977722, -0.42747554183006287, 0.28186774253845215, 0.0, 0.0, 0.5504802465438843, 0.8348482847213745, 0.0, 0.1925382763147354, -0.24935829639434814, -0.4401884973049164, 1.0]
#projMatrix = camInfo[3]#[0.7499999403953552, 0.0, 0.0, 0.0, 0.0, 1.0, 0.0, 0.0, 0.0, 0.0, -1.0000200271606445, -1.0, 0.0, 0.0, -0.02000020071864128, 0.0]
projMatrix = [0.75, 0.0, 0.0, 0.0, 0.0, 1.0, 0.0, 0.0, 0.0, 0.0, -1.0000200271606445, -1.0, 0.0, 0.0, -0.02000020071864128, 0.0]
img_arr = p.getCameraImage(width=self._width,height=self._height,viewMatrix=viewMat,projectionMatrix=projMatrix)
rgb=img_arr[2]
np_img_arr = np.reshape(rgb, (self._height, self._width, 4))
self._observation = np_img_arr
return self._observation
def _step(self, action):
if (self._isDiscrete):
dv = 0.01
@@ -142,7 +142,7 @@ class KukaCamGymEnv(gym.Env):
realAction = [dx,dy,-0.002,da,f]
return self.step2( realAction)
def step2(self, action):
for i in range(self._actionRepeat):
self._kuka.applyAction(action)
@@ -158,11 +158,11 @@ class KukaCamGymEnv(gym.Env):
#print("self._envStepCounter")
#print(self._envStepCounter)
done = self._termination()
reward = self._reward()
#print("len=%r" % len(self._observation))
return np.array(self._observation), reward, done, {}
def _render(self, mode='human', close=False):
@@ -190,18 +190,18 @@ class KukaCamGymEnv(gym.Env):
#print (self._kuka.endEffectorPos[2])
state = p.getLinkState(self._kuka.kukaUid,self._kuka.kukaEndEffectorIndex)
actualEndEffectorPos = state[0]
#print("self._envStepCounter")
#print(self._envStepCounter)
if (self.terminated or self._envStepCounter>maxSteps):
self._observation = self.getExtendedObservation()
return True
maxDist = 0.005
maxDist = 0.005
closestPoints = p.getClosestPoints(self._kuka.trayUid, self._kuka.kukaUid,maxDist)
if (len(closestPoints)):#(actualEndEffectorPos[2] <= -0.43):
self.terminated = 1
#print("closing gripper, attempting grasp")
#start grasp and terminate
fingerAngle = 0.3
@@ -212,7 +212,7 @@ class KukaCamGymEnv(gym.Env):
fingerAngle = fingerAngle-(0.3/100.)
if (fingerAngle<0):
fingerAngle=0
for i in range (1000):
graspAction = [0,0,0.001,0,fingerAngle]
self._kuka.applyAction(graspAction)
@@ -227,18 +227,18 @@ class KukaCamGymEnv(gym.Env):
if (actualEndEffectorPos[2]>0.5):
break
self._observation = self.getExtendedObservation()
return True
return False
def _reward(self):
#rewards is height of target object
blockPos,blockOrn=p.getBasePositionAndOrientation(self.blockUid)
closestPoints = p.getClosestPoints(self.blockUid,self._kuka.kukaUid,1000, -1, self._kuka.kukaEndEffectorIndex)
closestPoints = p.getClosestPoints(self.blockUid,self._kuka.kukaUid,1000, -1, self._kuka.kukaEndEffectorIndex)
reward = -1000
reward = -1000
numPt = len(closestPoints)
#print(numPt)
if (numPt>0):
@@ -254,3 +254,7 @@ class KukaCamGymEnv(gym.Env):
#print(reward)
return reward
render = _render
reset = _reset
seed = _seed
step = _step

View File

@@ -44,7 +44,7 @@ class KukaGymEnv(gym.Env):
self._maxSteps = maxSteps
self.terminated = 0
self._cam_dist = 1.3
self._cam_yaw = 180
self._cam_yaw = 180
self._cam_pitch = -40
self._p = p
@@ -61,8 +61,8 @@ class KukaGymEnv(gym.Env):
observationDim = len(self.getExtendedObservation())
#print("observationDim")
#print(observationDim)
observation_high = np.array([largeValObservation] * observationDim)
observation_high = np.array([largeValObservation] * observationDim)
if (self._isDiscrete):
self.action_space = spaces.Discrete(7)
else:
@@ -80,15 +80,15 @@ class KukaGymEnv(gym.Env):
p.setPhysicsEngineParameter(numSolverIterations=150)
p.setTimeStep(self._timeStep)
p.loadURDF(os.path.join(self._urdfRoot,"plane.urdf"),[0,0,-1])
p.loadURDF(os.path.join(self._urdfRoot,"table/table.urdf"), 0.5000000,0.00000,-.820000,0.000000,0.000000,0.0,1.0)
xpos = 0.55 +0.12*random.random()
ypos = 0 +0.2*random.random()
ang = 3.14*0.5+3.1415925438*random.random()
orn = p.getQuaternionFromEuler([0,0,ang])
self.blockUid =p.loadURDF(os.path.join(self._urdfRoot,"block.urdf"), xpos,ypos,-0.15,orn[0],orn[1],orn[2],orn[3])
p.setGravity(0,0,-10)
self._kuka = kuka.Kuka(urdfRootPath=self._urdfRoot, timeStep=self._timeStep)
self._envStepCounter = 0
@@ -115,7 +115,7 @@ class KukaGymEnv(gym.Env):
dir0 = [gripperMat[0],gripperMat[3],gripperMat[6]]
dir1 = [gripperMat[1],gripperMat[4],gripperMat[7]]
dir2 = [gripperMat[2],gripperMat[5],gripperMat[8]]
gripperEul = p.getEulerFromQuaternion(gripperOrn)
#print("gripperEul")
#print(gripperEul)
@@ -126,17 +126,17 @@ class KukaGymEnv(gym.Env):
#print(projectedBlockPos2D)
#print("blockEulerInGripper")
#print(blockEulerInGripper)
#we return the relative x,y position and euler angle of block in gripper space
blockInGripperPosXYEulZ =[blockPosInGripper[0],blockPosInGripper[1],blockEulerInGripper[2]]
#p.addUserDebugLine(gripperPos,[gripperPos[0]+dir0[0],gripperPos[1]+dir0[1],gripperPos[2]+dir0[2]],[1,0,0],lifeTime=1)
#p.addUserDebugLine(gripperPos,[gripperPos[0]+dir1[0],gripperPos[1]+dir1[1],gripperPos[2]+dir1[2]],[0,1,0],lifeTime=1)
#p.addUserDebugLine(gripperPos,[gripperPos[0]+dir2[0],gripperPos[1]+dir2[1],gripperPos[2]+dir2[2]],[0,0,1],lifeTime=1)
self._observation.extend(list(blockInGripperPosXYEulZ))
return self._observation
def _step(self, action):
if (self._isDiscrete):
dv = 0.005
@@ -154,7 +154,7 @@ class KukaGymEnv(gym.Env):
f = 0.3
realAction = [dx,dy,-0.002,da,f]
return self.step2( realAction)
def step2(self, action):
for i in range(self._actionRepeat):
self._kuka.applyAction(action)
@@ -168,7 +168,7 @@ class KukaGymEnv(gym.Env):
#print("self._envStepCounter")
#print(self._envStepCounter)
done = self._termination()
npaction = np.array([action[3]]) #only penalize rotation until learning works well [action[0],action[1],action[3]])
actionCost = np.linalg.norm(npaction)*10.
@@ -177,9 +177,9 @@ class KukaGymEnv(gym.Env):
reward = self._reward()-actionCost
#print("reward")
#print(reward)
#print("len=%r" % len(self._observation))
return np.array(self._observation), reward, done, {}
def _render(self, mode="rgb_array", close=False):
@@ -208,18 +208,18 @@ class KukaGymEnv(gym.Env):
#print (self._kuka.endEffectorPos[2])
state = p.getLinkState(self._kuka.kukaUid,self._kuka.kukaEndEffectorIndex)
actualEndEffectorPos = state[0]
#print("self._envStepCounter")
#print(self._envStepCounter)
if (self.terminated or self._envStepCounter>self._maxSteps):
self._observation = self.getExtendedObservation()
return True
maxDist = 0.005
maxDist = 0.005
closestPoints = p.getClosestPoints(self._kuka.trayUid, self._kuka.kukaUid,maxDist)
if (len(closestPoints)):#(actualEndEffectorPos[2] <= -0.43):
self.terminated = 1
#print("terminating, closing gripper, attempting grasp")
#start grasp and terminate
fingerAngle = 0.3
@@ -230,7 +230,7 @@ class KukaGymEnv(gym.Env):
fingerAngle = fingerAngle-(0.3/100.)
if (fingerAngle<0):
fingerAngle=0
for i in range (1000):
graspAction = [0,0,0.001,0,fingerAngle]
self._kuka.applyAction(graspAction)
@@ -245,19 +245,19 @@ class KukaGymEnv(gym.Env):
if (actualEndEffectorPos[2]>0.5):
break
self._observation = self.getExtendedObservation()
return True
return False
def _reward(self):
#rewards is height of target object
blockPos,blockOrn=p.getBasePositionAndOrientation(self.blockUid)
closestPoints = p.getClosestPoints(self.blockUid,self._kuka.kukaUid,1000, -1, self._kuka.kukaEndEffectorIndex)
closestPoints = p.getClosestPoints(self.blockUid,self._kuka.kukaUid,1000, -1, self._kuka.kukaEndEffectorIndex)
reward = -1000
numPt = len(closestPoints)
#print(numPt)
if (numPt>0):
@@ -276,10 +276,7 @@ class KukaGymEnv(gym.Env):
#print(reward)
return reward
def reset(self):
"""Resets the state of the environment and returns an initial observation.
Returns: observation (object): the initial observation of the
space.
"""
return self._reset()
render = _render
reset = _reset
seed = _seed
step = _step

View File

@@ -385,3 +385,8 @@ class MinitaurBulletDuckEnv(gym.Env):
scale=self._observation_noise_stdev, size=observation.shape) *
self.minitaur.GetObservationUpperBound())
return observation
render = _render
reset = _reset
seed = _seed
step = _step

View File

@@ -376,3 +376,8 @@ class MinitaurBulletEnv(gym.Env):
scale=self._observation_noise_stdev, size=observation.shape) *
self.minitaur.GetObservationUpperBound())
return observation
render = _render
reset = _reset
seed = _seed
step = _step

View File

@@ -50,8 +50,8 @@ class RacecarGymEnv(gym.Env):
#self.reset()
observationDim = 2 #len(self.getExtendedObservation())
#print("observationDim")
#print(observationDim)
# observation_high = np.array([np.finfo(np.float32).max] * observationDim)
#print(observationDim)
# observation_high = np.array([np.finfo(np.float32).max] * observationDim)
observation_high = np.ones(observationDim) * 1000 #np.inf
if (isDiscrete):
self.action_space = spaces.Discrete(9)
@@ -59,7 +59,7 @@ class RacecarGymEnv(gym.Env):
action_dim = 2
self._action_bound = 1
action_high = np.array([self._action_bound] * action_dim)
self.action_space = spaces.Box(-action_high, action_high)
self.action_space = spaces.Box(-action_high, action_high)
self.observation_space = spaces.Box(-observation_high, observation_high)
self.viewer = None
@@ -74,14 +74,14 @@ class RacecarGymEnv(gym.Env):
# pos,orn = self._p.getBasePositionAndOrientation(i)
# newpos = [pos[0],pos[1],pos[2]-0.1]
# self._p.resetBasePositionAndOrientation(i,newpos,orn)
dist = 5 +2.*random.random()
ang = 2.*3.1415925438*random.random()
ballx = dist * math.sin(ang)
bally = dist * math.cos(ang)
ballz = 1
self._ballUniqueId = self._p.loadURDF(os.path.join(self._urdfRoot,"sphere2.urdf"),[ballx,bally,ballz])
self._p.setGravity(0,0,-10)
self._racecar = racecar.Racecar(self._p,urdfRootPath=self._urdfRoot, timeStep=self._timeStep)
@@ -101,18 +101,18 @@ class RacecarGymEnv(gym.Env):
def getExtendedObservation(self):
self._observation = [] #self._racecar.getObservation()
carpos,carorn = self._p.getBasePositionAndOrientation(self._racecar.racecarUniqueId)
ballpos,ballorn = self._p.getBasePositionAndOrientation(self._ballUniqueId)
ballpos,ballorn = self._p.getBasePositionAndOrientation(self._ballUniqueId)
invCarPos,invCarOrn = self._p.invertTransform(carpos,carorn)
ballPosInCar,ballOrnInCar = self._p.multiplyTransforms(invCarPos,invCarOrn,ballpos,ballorn)
self._observation.extend([ballPosInCar[0],ballPosInCar[1]])
return self._observation
def _step(self, action):
if (self._renders):
basePos,orn = self._p.getBasePositionAndOrientation(self._racecar.racecarUniqueId)
#self._p.resetDebugVisualizerCamera(1, 30, -40, basePos)
if (self._isDiscrete):
fwd = [-1,-1,-1,0,0,0,1,1,1]
steerings = [-0.6,0,0.6,-0.6,0,0.6,-0.6,0,0.6]
@@ -128,14 +128,14 @@ class RacecarGymEnv(gym.Env):
if self._renders:
time.sleep(self._timeStep)
self._observation = self.getExtendedObservation()
if self._termination():
break
self._envStepCounter += 1
reward = self._reward()
done = self._termination()
#print("len=%r" % len(self._observation))
return np.array(self._observation), reward, done, {}
def _render(self, mode='human', close=False):
@@ -159,13 +159,13 @@ class RacecarGymEnv(gym.Env):
rgb_array = rgb_array[:, :, :3]
return rgb_array
def _termination(self):
return self._envStepCounter>1000
def _reward(self):
closestPoints = self._p.getClosestPoints(self._racecar.racecarUniqueId,self._ballUniqueId,10000)
closestPoints = self._p.getClosestPoints(self._racecar.racecarUniqueId,self._ballUniqueId,10000)
numPt = len(closestPoints)
reward=-1000
#print(numPt)
@@ -174,3 +174,8 @@ class RacecarGymEnv(gym.Env):
reward = -closestPoints[0][8]
#print(reward)
return reward
render = _render
reset = _reset
seed = _seed
step = _step

View File

@@ -40,7 +40,7 @@ class RacecarZEDGymEnv(gym.Env):
self._renders = renders
self._width = 100
self._height = 10
self._isDiscrete = isDiscrete
if self._renders:
self._p = bullet_client.BulletClient(
@@ -53,8 +53,8 @@ class RacecarZEDGymEnv(gym.Env):
observationDim = len(self.getExtendedObservation())
#print("observationDim")
#print(observationDim)
observation_high = np.array([np.finfo(np.float32).max] * observationDim)
observation_high = np.array([np.finfo(np.float32).max] * observationDim)
if (isDiscrete):
self.action_space = spaces.Discrete(9)
else:
@@ -77,14 +77,14 @@ class RacecarZEDGymEnv(gym.Env):
pos,orn = self._p.getBasePositionAndOrientation(i)
newpos = [pos[0],pos[1],pos[2]+0.1]
self._p.resetBasePositionAndOrientation(i,newpos,orn)
dist = 5 +2.*random.random()
ang = 2.*3.1415925438*random.random()
ballx = dist * math.sin(ang)
bally = dist * math.cos(ang)
ballz = 1
self._ballUniqueId = self._p.loadURDF(os.path.join(self._urdfRoot,"sphere2red.urdf"),[ballx,bally,ballz])
self._p.setGravity(0,0,-10)
self._racecar = racecar.Racecar(self._p,urdfRootPath=self._urdfRoot, timeStep=self._timeStep)
@@ -104,13 +104,13 @@ class RacecarZEDGymEnv(gym.Env):
def getExtendedObservation(self):
carpos,carorn = self._p.getBasePositionAndOrientation(self._racecar.racecarUniqueId)
carmat = self._p.getMatrixFromQuaternion(carorn)
ballpos,ballorn = self._p.getBasePositionAndOrientation(self._ballUniqueId)
ballpos,ballorn = self._p.getBasePositionAndOrientation(self._ballUniqueId)
invCarPos,invCarOrn = self._p.invertTransform(carpos,carorn)
ballPosInCar,ballOrnInCar = self._p.multiplyTransforms(invCarPos,invCarOrn,ballpos,ballorn)
dist0 = 0.3
dist1 = 1.
eyePos = [carpos[0]+dist0*carmat[0],carpos[1]+dist0*carmat[3],carpos[2]+dist0*carmat[6]+0.3]
targetPos = [carpos[0]+dist1*carmat[0],carpos[1]+dist1*carmat[3],carpos[2]+dist1*carmat[6]+0.3]
targetPos = [carpos[0]+dist1*carmat[0],carpos[1]+dist1*carmat[3],carpos[2]+dist1*carmat[6]+0.3]
up = [carmat[2],carmat[5],carmat[8]]
viewMat = self._p.computeViewMatrix(eyePos,targetPos,up)
#viewMat = self._p.computeViewMatrixFromYawPitchRoll(carpos,1,0,0,0,2)
@@ -122,12 +122,12 @@ class RacecarZEDGymEnv(gym.Env):
np_img_arr = np.reshape(rgb, (self._height, self._width, 4))
self._observation = np_img_arr
return self._observation
def _step(self, action):
if (self._renders):
basePos,orn = self._p.getBasePositionAndOrientation(self._racecar.racecarUniqueId)
#self._p.resetDebugVisualizerCamera(1, 30, -40, basePos)
if (self._isDiscrete):
fwd = [-1,-1,-1,0,0,0,1,1,1]
steerings = [-0.6,0,0.6,-0.6,0,0.6,-0.6,0,0.6]
@@ -143,14 +143,14 @@ class RacecarZEDGymEnv(gym.Env):
if self._renders:
time.sleep(self._timeStep)
self._observation = self.getExtendedObservation()
if self._termination():
break
self._envStepCounter += 1
reward = self._reward()
done = self._termination()
#print("len=%r" % len(self._observation))
return np.array(self._observation), reward, done, {}
def _render(self, mode='human', close=False):
@@ -177,10 +177,10 @@ class RacecarZEDGymEnv(gym.Env):
def _termination(self):
return self._envStepCounter>1000
def _reward(self):
closestPoints = self._p.getClosestPoints(self._racecar.racecarUniqueId,self._ballUniqueId,10000)
closestPoints = self._p.getClosestPoints(self._racecar.racecarUniqueId,self._ballUniqueId,10000)
numPt = len(closestPoints)
reward=-1000
#print(numPt)
@@ -189,3 +189,8 @@ class RacecarZEDGymEnv(gym.Env):
reward = -closestPoints[0][8]
#print(reward)
return reward
render = _render
reset = _reset
seed = _seed
step = _step

View File

@@ -46,8 +46,8 @@ class SimpleHumanoidGymEnv(gym.Env):
observationDim = len(self.getExtendedObservation())
#print("observationDim")
#print(observationDim)
observation_high = np.array([np.finfo(np.float32).max] * observationDim)
observation_high = np.array([np.finfo(np.float32).max] * observationDim)
self.action_space = spaces.Discrete(9)
self.observation_space = spaces.Box(-observation_high, observation_high)
self.viewer = None
@@ -57,14 +57,14 @@ class SimpleHumanoidGymEnv(gym.Env):
#p.setPhysicsEngineParameter(numSolverIterations=300)
p.setTimeStep(self._timeStep)
p.loadURDF(os.path.join(self._urdfRoot,"plane.urdf"))
dist = 5 +2.*random.random()
ang = 2.*3.1415925438*random.random()
ballx = dist * math.sin(ang)
bally = dist * math.cos(ang)
ballz = 1
p.setGravity(0,0,-10)
self._humanoid = simpleHumanoid.SimpleHumanoid(urdfRootPath=self._urdfRoot, timeStep=self._timeStep)
self._envStepCounter = 0
@@ -82,7 +82,7 @@ class SimpleHumanoidGymEnv(gym.Env):
def getExtendedObservation(self):
self._observation = self._humanoid.getObservation()
return self._observation
def _step(self, action):
self._humanoid.applyAction(action)
for i in range(self._actionRepeat):
@@ -96,7 +96,7 @@ class SimpleHumanoidGymEnv(gym.Env):
reward = self._reward()
done = self._termination()
#print("len=%r" % len(self._observation))
return np.array(self._observation), reward, done, {}
def _render(self, mode='human', close=False):
@@ -104,8 +104,13 @@ class SimpleHumanoidGymEnv(gym.Env):
def _termination(self):
return self._envStepCounter>1000
def _reward(self):
reward=self._humanoid.distance
print(reward)
return reward
render = _render
reset = _reset
seed = _seed
step = _step

View File

@@ -43,7 +43,7 @@ class MJCFBaseBulletEnv(gym.Env):
conInfo = p.getConnectionInfo()
if (conInfo['isConnected']):
self.ownsPhysicsClient = False
self.physicsClientId = 0
else:
self.ownsPhysicsClient = True
@@ -75,12 +75,12 @@ class MJCFBaseBulletEnv(gym.Env):
self.isRender = True
if mode != "rgb_array":
return np.array([])
base_pos=[0,0,0]
if (hasattr(self,'robot')):
if (hasattr(self.robot,'body_xyz')):
base_pos = self.robot.body_xyz
view_matrix = p.computeViewMatrixFromYawPitchRoll(
cameraTargetPosition=base_pos,
distance=self._cam_dist,
@@ -100,6 +100,7 @@ class MJCFBaseBulletEnv(gym.Env):
rgb_array = rgb_array[:, :, :3]
return rgb_array
def _close(self):
if (self.ownsPhysicsClient):
if (self.physicsClientId>=0):
@@ -109,6 +110,17 @@ class MJCFBaseBulletEnv(gym.Env):
def HUD(self, state, a, done):
pass
# backwards compatibility for gym >= v0.9.x
# for extension of this class.
def step(self, *args, **kwargs):
return self._step(*args, **kwargs)
close = _close
render = _render
reset = _reset
seed = _seed
class Camera:
def __init__(self):
pass

View File

@@ -0,0 +1,137 @@
import pybullet as p
import math
import time
import pybullet_data
p.connect(p.GUI)
#p.loadURDF("wheel.urdf",[0,0,3])
p.setAdditionalSearchPath(pybullet_data.getDataPath())
plane=p.loadURDF("plane100.urdf",[0,0,0])
timestep = 1./240.
bike=-1
for i in range (1):
bike=p.loadURDF("bicycle/bike.urdf",[0,0+3*i,1.5], [0,0,0,1], useFixedBase=False)
p.setJointMotorControl2(bike,0,p.VELOCITY_CONTROL,targetVelocity=0,force=0.05)
#p.setJointMotorControl2(bike,1,p.VELOCITY_CONTROL,targetVelocity=5, force=1000)
p.setJointMotorControl2(bike,1,p.VELOCITY_CONTROL,targetVelocity=5, force=0)
p.setJointMotorControl2(bike,2,p.VELOCITY_CONTROL,targetVelocity=15, force=20)
p.changeDynamics(plane,-1, mass=20,lateralFriction=1, linearDamping=0, angularDamping=0)
p.changeDynamics(bike,1,lateralFriction=1,linearDamping=0, angularDamping=0)
p.changeDynamics(bike,2,lateralFriction=1,linearDamping=0, angularDamping=0)
#p.resetJointState(bike,1,0,100)
#p.resetJointState(bike,2,0,100)
#p.resetBaseVelocity(bike,[0,0,0],[0,0,0])
#p.setPhysicsEngineParameter(numSubSteps=0)
#bike=p.loadURDF("frame.urdf",useFixedBase=True)
#bike = p.loadURDF("handlebar.urdf", useFixedBase=True)
#p.loadURDF("handlebar.urdf",[0,2,1])
#coord = p.loadURDF("handlebar.urdf", [0.7700000000000005, 0, 0.22000000000000006],useFixedBase=True)# p.loadURDF("coordinateframe.urdf",[-2,0,1],useFixedBase=True)
#coord = p.loadURDF("coordinateframe.urdf",[-2,0,1],useFixedBase=True)
p.setGravity(0,0,-10)
p.setRealTimeSimulation(0)
#coordPos = [0,0,0]
#coordOrnEuler = [0,0,0]
#coordPos= [0.7000000000000004, 0, 0.22000000000000006]
#coordOrnEuler= [0, -0.2617993877991496, 0]
coordPos= [0.07, 0, -0.6900000000000004]
coordOrnEuler= [0, 0, 0]
coordPos2= [0, 0, 0 ]
coordOrnEuler2= [0, 0, 0]
invPos,invOrn=p.invertTransform(coordPos,p.getQuaternionFromEuler(coordOrnEuler))
mPos,mOrn = p.multiplyTransforms(invPos,invOrn, coordPos2,p.getQuaternionFromEuler(coordOrnEuler2))
eul = p.getEulerFromQuaternion(mOrn)
print("rpy=\"",eul[0],eul[1],eul[2],"\" xyz=\"", mPos[0],mPos[1], mPos[2])
shift=0
gui = 1
frame=0
states=[]
states.append(p.saveState())
#observations=[]
#observations.append(obs)
running = True
reverting = False
p.getCameraImage(320,200)#,renderer=p.ER_BULLET_HARDWARE_OPENGL )
while (1):
updateCam = 0
keys = p.getKeyboardEvents()
for k,v in keys.items():
if (reverting or (k == p.B3G_LEFT_ARROW and (v&p.KEY_WAS_TRIGGERED))):
reverting=True
stateIndex = len(states)-1
#print("prestateIndex=",stateIndex)
time.sleep(timestep)
updateCam=1
if (stateIndex>0):
stateIndex-=1
states=states[:stateIndex+1]
#observations=observations[:stateIndex+1]
#print("states=",states)
#print("stateIndex =",stateIndex )
p.restoreState(states[stateIndex])
#obs=observations[stateIndex]
#obs, r, done, _ = env.step(a)
if (k == p.B3G_LEFT_ARROW and (v&p.KEY_WAS_RELEASED)):
reverting = False
if (k == ord('1') and (v&p.KEY_WAS_TRIGGERED)):
gui = not gui
if (k == p.B3G_RIGHT_ARROW and (v&p.KEY_WAS_RELEASED)):
running=False
if (running or (k == p.B3G_RIGHT_ARROW and (v&p.KEY_WAS_TRIGGERED))):
running = True
if (running):
p.stepSimulation()
updateCam=1
time.sleep(timestep)
pts = p.getContactPoints()
#print("numPoints=",len(pts))
#for point in pts:
# print("Point:bodyA=", point[1],"bodyB=",point[2],"linkA=",point[3],"linkB=",point[4],"dist=",point[8],"force=",point[9])
states.append(p.saveState())
#observations.append(obs)
stateIndex = len(states)
#print("stateIndex =",stateIndex )
frame += 1
if (updateCam):
distance=5
yaw = 0
humanPos, humanOrn = p.getBasePositionAndOrientation(bike)
humanBaseVel = p.getBaseVelocity(bike)
#print("frame",frame, "humanPos=",humanPos, "humanVel=",humanBaseVel)
if (gui):
camInfo = p.getDebugVisualizerCamera()
curTargetPos = camInfo[11]
distance=camInfo[10]
yaw = camInfo[8]
pitch=camInfo[9]
targetPos = [0.95*curTargetPos[0]+0.05*humanPos[0],0.95*curTargetPos[1]+0.05*humanPos[1],curTargetPos[2]]
p.resetDebugVisualizerCamera(distance,yaw,pitch,targetPos);

View File

@@ -21,8 +21,11 @@ public partial class NativeConstants {
/// SHARED_MEMORY_KEY -> 12347
public const int SHARED_MEMORY_KEY = 12347;
/// SHARED_MEMORY_MAGIC_NUMBER -> 201709260
public const int SHARED_MEMORY_MAGIC_NUMBER = 201709260;
/// SHARED_MEMORY_MAGIC_NUMBER -> 201801170
public const int SHARED_MEMORY_MAGIC_NUMBER = 201801170;
/// MAX_VR_ANALOG_AXIS -> 5
public const int MAX_VR_ANALOG_AXIS = 5;
/// MAX_VR_BUTTONS -> 64
public const int MAX_VR_BUTTONS = 64;
@@ -42,6 +45,9 @@ public partial class NativeConstants {
/// MAX_MOUSE_EVENTS -> 256
public const int MAX_MOUSE_EVENTS = 256;
/// MAX_SDF_BODIES -> 512
public const int MAX_SDF_BODIES = 512;
/// VISUAL_SHAPE_MAX_PATH_LEN -> 1024
public const int VISUAL_SHAPE_MAX_PATH_LEN = 1024;
@@ -92,7 +98,7 @@ public enum EnumSharedMemoryClientCommand {
CMD_LOAD_MJCF,
CMD_LOAD_BUNNY,
CMD_LOAD_SOFT_BODY,
CMD_SEND_BULLET_DATA_STREAM,
@@ -138,6 +144,8 @@ public enum EnumSharedMemoryClientCommand {
CMD_CALCULATE_JACOBIAN,
CMD_CALCULATE_MASS_MATRIX,
CMD_USER_CONSTRAINT,
CMD_REQUEST_CONTACT_POINT_INFORMATION,
@@ -196,6 +204,14 @@ public enum EnumSharedMemoryClientCommand {
CMD_CUSTOM_COMMAND,
CMD_REQUEST_PHYSICS_SIMULATION_PARAMETERS,
CMD_SAVE_STATE,
CMD_RESTORE_STATE,
CMD_REQUEST_COLLISION_SHAPE_INFO,
CMD_MAX_CLIENT_COMMANDS,
}
@@ -276,6 +292,10 @@ public enum EnumSharedMemoryServerStatus {
CMD_CALCULATED_JACOBIAN_FAILED,
CMD_CALCULATED_MASS_MATRIX_COMPLETED,
CMD_CALCULATED_MASS_MATRIX_FAILED,
CMD_CONTACT_POINT_INFORMATION_COMPLETED,
CMD_CONTACT_POINT_INFORMATION_FAILED,
@@ -314,6 +334,8 @@ public enum EnumSharedMemoryServerStatus {
CMD_USER_CONSTRAINT_INFO_COMPLETED,
CMD_USER_CONSTRAINT_REQUEST_STATE_COMPLETED,
CMD_REMOVE_USER_CONSTRAINT_COMPLETED,
CMD_CHANGE_USER_CONSTRAINT_COMPLETED,
@@ -378,6 +400,24 @@ public enum EnumSharedMemoryServerStatus {
CMD_CUSTOM_COMMAND_FAILED,
CMD_REQUEST_PHYSICS_SIMULATION_PARAMETERS_COMPLETED,
CMD_SAVE_STATE_FAILED,
CMD_SAVE_STATE_COMPLETED,
CMD_RESTORE_STATE_FAILED,
CMD_RESTORE_STATE_COMPLETED,
CMD_COLLISION_SHAPE_INFO_COMPLETED,
CMD_COLLISION_SHAPE_INFO_FAILED,
CMD_LOAD_SOFT_BODY_FAILED,
CMD_LOAD_SOFT_BODY_COMPLETED,
CMD_MAX_SERVER_COMMANDS,
}
@@ -423,15 +463,15 @@ public enum b3JointInfoFlags {
eJointChangeChildFrameOrientation = 4,
}
[System.Runtime.InteropServices.StructLayoutAttribute(System.Runtime.InteropServices.LayoutKind.Sequential)]
[System.Runtime.InteropServices.StructLayoutAttribute(System.Runtime.InteropServices.LayoutKind.Sequential, CharSet=System.Runtime.InteropServices.CharSet.Ansi)]
public struct b3JointInfo {
/// char[1024]
[System.Runtime.InteropServices.MarshalAsAttribute(System.Runtime.InteropServices.UnmanagedType.ByValTStr, SizeConst = 1024)]
[System.Runtime.InteropServices.MarshalAsAttribute(System.Runtime.InteropServices.UnmanagedType.ByValTStr, SizeConst=1024)]
public string m_linkName;
/// char[1024]
[System.Runtime.InteropServices.MarshalAsAttribute(System.Runtime.InteropServices.UnmanagedType.ByValTStr, SizeConst = 1024)]
[System.Runtime.InteropServices.MarshalAsAttribute(System.Runtime.InteropServices.UnmanagedType.ByValTStr, SizeConst=1024)]
public string m_jointName;
/// int
@@ -478,6 +518,9 @@ public struct b3JointInfo {
/// double[3]
[System.Runtime.InteropServices.MarshalAsAttribute(System.Runtime.InteropServices.UnmanagedType.ByValArray, SizeConst=3, ArraySubType=System.Runtime.InteropServices.UnmanagedType.R8)]
public double[] m_jointAxis;
/// int
public int m_parentIndex;
}
[System.Runtime.InteropServices.StructLayoutAttribute(System.Runtime.InteropServices.LayoutKind.Sequential)]
@@ -529,15 +572,15 @@ public struct b3UserConstraint {
public double m_erp;
}
[System.Runtime.InteropServices.StructLayoutAttribute(System.Runtime.InteropServices.LayoutKind.Sequential)]
[System.Runtime.InteropServices.StructLayoutAttribute(System.Runtime.InteropServices.LayoutKind.Sequential, CharSet=System.Runtime.InteropServices.CharSet.Ansi)]
public struct b3BodyInfo {
/// char[1024]
[System.Runtime.InteropServices.MarshalAsAttribute(System.Runtime.InteropServices.UnmanagedType.ByValTStr, SizeConst = 1024)]
[System.Runtime.InteropServices.MarshalAsAttribute(System.Runtime.InteropServices.UnmanagedType.ByValTStr, SizeConst=1024)]
public string m_baseName;
/// char[1024]
[System.Runtime.InteropServices.MarshalAsAttribute(System.Runtime.InteropServices.UnmanagedType.ByValTStr, SizeConst = 1024)]
[System.Runtime.InteropServices.MarshalAsAttribute(System.Runtime.InteropServices.UnmanagedType.ByValTStr, SizeConst=1024)]
public string m_bodyName;
}
@@ -549,10 +592,29 @@ public struct b3DynamicsInfo {
/// double[3]
[System.Runtime.InteropServices.MarshalAsAttribute(System.Runtime.InteropServices.UnmanagedType.ByValArray, SizeConst=3, ArraySubType=System.Runtime.InteropServices.UnmanagedType.R8)]
public double[] m_localInertialPosition;
public double[] m_localInertialDiagonal;
/// double[7]
[System.Runtime.InteropServices.MarshalAsAttribute(System.Runtime.InteropServices.UnmanagedType.ByValArray, SizeConst=7, ArraySubType=System.Runtime.InteropServices.UnmanagedType.R8)]
public double[] m_localInertialFrame;
/// double
public double m_lateralFrictionCoeff;
/// double
public double m_rollingFrictionCoeff;
/// double
public double m_spinningFrictionCoeff;
/// double
public double m_restitution;
/// double
public double m_contactStiffness;
/// double
public double m_contactDamping;
}
public enum SensorType {
@@ -624,7 +686,8 @@ public struct b3CameraImageData {
public int m_pixelHeight;
/// char*
public System.IntPtr m_rgbColorData;
[System.Runtime.InteropServices.MarshalAsAttribute(System.Runtime.InteropServices.UnmanagedType.LPStr)]
public string m_rgbColorData;
/// float*
public System.IntPtr m_depthValues;
@@ -680,6 +743,17 @@ public struct b3OpenGLVisualizerCameraInfo {
public float[] m_target;
}
[System.Runtime.InteropServices.StructLayoutAttribute(System.Runtime.InteropServices.LayoutKind.Sequential)]
public struct b3UserConstraintState {
/// double[6]
[System.Runtime.InteropServices.MarshalAsAttribute(System.Runtime.InteropServices.UnmanagedType.ByValArray, SizeConst=6, ArraySubType=System.Runtime.InteropServices.UnmanagedType.R8)]
public double[] m_appliedConstraintForces;
/// int
public int m_numDofs;
}
public enum b3VREventType {
/// VR_CONTROLLER_MOVE_EVENT -> 1
@@ -751,6 +825,9 @@ public struct b3VRControllerEvent {
/// float
public float m_analogAxis;
/// float[]
public float[] m_auxAnalogAxis;
/// int[64]
[System.Runtime.InteropServices.MarshalAsAttribute(System.Runtime.InteropServices.UnmanagedType.ByValArray, SizeConst=64, ArraySubType=System.Runtime.InteropServices.UnmanagedType.I4)]
public int[] m_buttons;
@@ -965,6 +1042,41 @@ public struct b3VisualShapeInformation {
public System.IntPtr m_visualShapeData;
}
[System.Runtime.InteropServices.StructLayoutAttribute(System.Runtime.InteropServices.LayoutKind.Sequential, CharSet=System.Runtime.InteropServices.CharSet.Ansi)]
public struct b3CollisionShapeData {
/// int
public int m_objectUniqueId;
/// int
public int m_linkIndex;
/// int
public int m_collisionGeometryType;
/// double[3]
[System.Runtime.InteropServices.MarshalAsAttribute(System.Runtime.InteropServices.UnmanagedType.ByValArray, SizeConst=3, ArraySubType=System.Runtime.InteropServices.UnmanagedType.R8)]
public double[] m_dimensions;
/// double[7]
[System.Runtime.InteropServices.MarshalAsAttribute(System.Runtime.InteropServices.UnmanagedType.ByValArray, SizeConst=7, ArraySubType=System.Runtime.InteropServices.UnmanagedType.R8)]
public double[] m_localCollisionFrame;
/// char[1024]
[System.Runtime.InteropServices.MarshalAsAttribute(System.Runtime.InteropServices.UnmanagedType.ByValTStr, SizeConst=1024)]
public string m_meshAssetFileName;
}
[System.Runtime.InteropServices.StructLayoutAttribute(System.Runtime.InteropServices.LayoutKind.Sequential)]
public struct b3CollisionShapeInformation {
/// int
public int m_numCollisionShapes;
/// b3CollisionShapeData*
public System.IntPtr m_collisionShapeData;
}
public enum eLinkStateFlags {
/// ACTUAL_STATE_COMPUTE_LINKVELOCITY -> 1
@@ -1036,6 +1148,33 @@ public enum EnumRenderer {
ER_BULLET_HARDWARE_OPENGL = (1) << (17),
}
public enum EnumRendererAuxFlags {
/// ER_SEGMENTATION_MASK_OBJECT_AND_LINKINDEX -> 1
ER_SEGMENTATION_MASK_OBJECT_AND_LINKINDEX = 1,
}
public enum EnumCalculateInverseKinematicsFlags {
/// IK_DLS -> 0
IK_DLS = 0,
/// IK_SDLS -> 1
IK_SDLS = 1,
/// IK_HAS_TARGET_POSITION -> 16
IK_HAS_TARGET_POSITION = 16,
/// IK_HAS_TARGET_ORIENTATION -> 32
IK_HAS_TARGET_ORIENTATION = 32,
/// IK_HAS_NULL_SPACE_VELOCITY -> 64
IK_HAS_NULL_SPACE_VELOCITY = 64,
/// IK_HAS_JOINT_DAMPING -> 128
IK_HAS_JOINT_DAMPING = 128,
}
public enum b3ConfigureDebugVisualizerEnum {
/// COV_ENABLE_GUI -> 1
@@ -1058,12 +1197,22 @@ public enum b3ConfigureDebugVisualizerEnum {
COV_ENABLE_KEYBOARD_SHORTCUTS,
COV_ENABLE_MOUSE_PICKING,
COV_ENABLE_Y_AXIS_UP,
COV_ENABLE_TINY_RENDERER,
COV_ENABLE_RGB_BUFFER_PREVIEW,
COV_ENABLE_DEPTH_BUFFER_PREVIEW,
COV_ENABLE_SEGMENTATION_MARK_PREVIEW,
}
public enum b3AddUserDebugItemEnum {
/// DEB_DEBUG_TEXT_USE_ORIENTATION -> 1
DEB_DEBUG_TEXT_USE_ORIENTATION = 1,
/// DEB_DEBUG_TEXT_ALWAYS_FACE_CAMERA -> 1
DEB_DEBUG_TEXT_ALWAYS_FACE_CAMERA = 1,
/// DEB_DEBUG_TEXT_USE_TRUE_TYPE_FONTS -> 2
DEB_DEBUG_TEXT_USE_TRUE_TYPE_FONTS = 2,
@@ -1112,6 +1261,15 @@ public enum eURDF_Flags {
/// URDF_RESERVED -> 64
URDF_RESERVED = 64,
/// URDF_USE_IMPLICIT_CYLINDER -> 128
URDF_USE_IMPLICIT_CYLINDER = 128,
/// URDF_GLOBAL_VELOCITIES_MB -> 256
URDF_GLOBAL_VELOCITIES_MB = 256,
/// MJCF_COLORS_FROM_FILE -> 512
MJCF_COLORS_FROM_FILE = 512,
}
public enum eUrdfGeomTypes {
@@ -1138,6 +1296,15 @@ public enum eUrdfCollisionFlags {
GEOM_FORCE_CONCAVE_TRIMESH = 1,
}
public enum eUrdfVisualFlags {
/// GEOM_VISUAL_HAS_RGBA_COLOR -> 1
GEOM_VISUAL_HAS_RGBA_COLOR = 1,
/// GEOM_VISUAL_HAS_SPECULAR_COLOR -> 2
GEOM_VISUAL_HAS_SPECULAR_COLOR = 2,
}
public enum eStateLoggingFlags {
/// STATE_LOG_JOINT_MOTOR_TORQUES -> 1
@@ -1167,9 +1334,65 @@ public struct b3PluginArguments {
/// int
public int m_numFloats;
/// int[128]
[System.Runtime.InteropServices.MarshalAsAttribute(System.Runtime.InteropServices.UnmanagedType.ByValArray, SizeConst=128, ArraySubType=System.Runtime.InteropServices.UnmanagedType.I4)]
public int[] m_floats;
/// double[128]
[System.Runtime.InteropServices.MarshalAsAttribute(System.Runtime.InteropServices.UnmanagedType.ByValArray, SizeConst=128, ArraySubType=System.Runtime.InteropServices.UnmanagedType.R8)]
public double[] m_floats;
}
[System.Runtime.InteropServices.StructLayoutAttribute(System.Runtime.InteropServices.LayoutKind.Sequential)]
public struct b3PhysicsSimulationParameters {
/// double
public double m_deltaTime;
/// double[3]
[System.Runtime.InteropServices.MarshalAsAttribute(System.Runtime.InteropServices.UnmanagedType.ByValArray, SizeConst=3, ArraySubType=System.Runtime.InteropServices.UnmanagedType.R8)]
public double[] m_gravityAcceleration;
/// int
public int m_numSimulationSubSteps;
/// int
public int m_numSolverIterations;
/// int
public int m_useRealTimeSimulation;
/// int
public int m_useSplitImpulse;
/// double
public double m_splitImpulsePenetrationThreshold;
/// double
public double m_contactBreakingThreshold;
/// int
public int m_internalSimFlags;
/// double
public double m_defaultContactERP;
/// int
public int m_collisionFilterMode;
/// int
public int m_enableFileCaching;
/// double
public double m_restitutionVelocityThreshold;
/// double
public double m_defaultNonContactERP;
/// double
public double m_frictionERP;
/// int
public int m_enableConeFriction;
/// int
public int m_deterministicOverlappingPairs;
}
[System.Runtime.InteropServices.StructLayoutAttribute(System.Runtime.InteropServices.LayoutKind.Sequential)]
@@ -1194,9 +1417,8 @@ public struct b3SharedMemoryStatusHandle__ {
}
public partial class NativeMethods {
const string dllName = "pybullet_vs2010_x64_release.dll";
/// Return Type: b3PhysicsClientHandle->b3PhysicsClientHandle__*
///key: int
[System.Runtime.InteropServices.DllImportAttribute(dllName, EntryPoint="b3ConnectSharedMemory")]
@@ -1330,6 +1552,13 @@ public static extern System.IntPtr b3CreateCustomCommand(IntPtr physClient) ;
public static extern void b3CustomCommandLoadPlugin(IntPtr commandHandle, [System.Runtime.InteropServices.InAttribute()] [System.Runtime.InteropServices.MarshalAsAttribute(System.Runtime.InteropServices.UnmanagedType.LPStr)] string pluginPath) ;
/// Return Type: void
///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__*
///postFix: char*
[System.Runtime.InteropServices.DllImportAttribute(dllName, EntryPoint="b3CustomCommandLoadPluginSetPostFix")]
public static extern void b3CustomCommandLoadPluginSetPostFix(IntPtr commandHandle, [System.Runtime.InteropServices.InAttribute()] [System.Runtime.InteropServices.MarshalAsAttribute(System.Runtime.InteropServices.UnmanagedType.LPStr)] string postFix) ;
/// Return Type: int
///statusHandle: b3SharedMemoryStatusHandle->b3SharedMemoryStatusHandle__*
[System.Runtime.InteropServices.DllImportAttribute(dllName, EntryPoint="b3GetStatusPluginUniqueId")]
@@ -1445,7 +1674,7 @@ public static extern int b3GetBodyUniqueId(IntPtr physClient, int serialIndex)
///bodyUniqueId: int
///info: b3BodyInfo*
[System.Runtime.InteropServices.DllImportAttribute(dllName, EntryPoint="b3GetBodyInfo")]
public static extern int b3GetBodyInfo(IntPtr physClient, int bodyUniqueId, ref b3BodyInfo info) ;
public static extern int b3GetBodyInfo(IntPtr physClient, int bodyUniqueId, ref b3BodyInfo info) ;
/// Return Type: int
@@ -1494,6 +1723,15 @@ public static extern System.IntPtr b3InitChangeDynamicsInfo(IntPtr physClient)
public static extern int b3ChangeDynamicsInfoSetMass(IntPtr commandHandle, int bodyUniqueId, int linkIndex, double mass) ;
/// Return Type: int
///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__*
///bodyUniqueId: int
///linkIndex: int
///localInertiaDiagonal: double*
[System.Runtime.InteropServices.DllImportAttribute(dllName, EntryPoint="b3ChangeDynamicsInfoSetLocalInertiaDiagonal")]
public static extern int b3ChangeDynamicsInfoSetLocalInertiaDiagonal(IntPtr commandHandle, int bodyUniqueId, int linkIndex, ref double localInertiaDiagonal) ;
/// Return Type: int
///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__*
///bodyUniqueId: int
@@ -1651,6 +1889,20 @@ public static extern System.IntPtr b3InitRemoveUserConstraintCommand(IntPtr phy
public static extern int b3GetNumUserConstraints(IntPtr physClient) ;
/// Return Type: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__*
///physClient: b3PhysicsClientHandle->b3PhysicsClientHandle__*
///constraintUniqueId: int
[System.Runtime.InteropServices.DllImportAttribute(dllName, EntryPoint="b3InitGetUserConstraintStateCommand")]
public static extern System.IntPtr b3InitGetUserConstraintStateCommand(IntPtr physClient, int constraintUniqueId) ;
/// Return Type: int
///statusHandle: b3SharedMemoryStatusHandle->b3SharedMemoryStatusHandle__*
///constraintState: b3UserConstraintState*
[System.Runtime.InteropServices.DllImportAttribute(dllName, EntryPoint="b3GetStatusUserConstraintState")]
public static extern int b3GetStatusUserConstraintState(IntPtr statusHandle, ref b3UserConstraintState constraintState) ;
/// Return Type: int
///physClient: b3PhysicsClientHandle->b3PhysicsClientHandle__*
///constraintUniqueId: int
@@ -1753,6 +2005,13 @@ public static extern void b3UserDebugTextSetOptionFlags(IntPtr commandHandle, i
public static extern void b3UserDebugTextSetOrientation(IntPtr commandHandle, ref double orientation) ;
/// Return Type: void
///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__*
///replaceItem: int
[System.Runtime.InteropServices.DllImportAttribute(dllName, EntryPoint="b3UserDebugItemSetReplaceItemUniqueId")]
public static extern void b3UserDebugItemSetReplaceItemUniqueId(IntPtr commandHandle, int replaceItem) ;
/// Return Type: void
///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__*
///objectUniqueId: int
@@ -1905,6 +2164,13 @@ public static extern void b3RequestCameraImageSetShadow(IntPtr commandHandle, i
public static extern void b3RequestCameraImageSelectRenderer(IntPtr commandHandle, int renderer) ;
/// Return Type: void
///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__*
///flags: int
[System.Runtime.InteropServices.DllImportAttribute(dllName, EntryPoint="b3RequestCameraImageSetFlags")]
public static extern void b3RequestCameraImageSetFlags(IntPtr commandHandle, int flags) ;
/// Return Type: void
///physClient: b3PhysicsClientHandle->b3PhysicsClientHandle__*
///imageData: b3CameraImageData*
@@ -2125,6 +2391,21 @@ public static extern System.IntPtr b3InitRequestVisualShapeInformation(IntPtr p
public static extern void b3GetVisualShapeInformation(IntPtr physClient, ref b3VisualShapeInformation visualShapeInfo) ;
/// Return Type: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__*
///physClient: b3PhysicsClientHandle->b3PhysicsClientHandle__*
///bodyUniqueId: int
///linkIndex: int
[System.Runtime.InteropServices.DllImportAttribute(dllName, EntryPoint="b3InitRequestCollisionShapeInformation")]
public static extern System.IntPtr b3InitRequestCollisionShapeInformation(IntPtr physClient, int bodyUniqueId, int linkIndex) ;
/// Return Type: void
///physClient: b3PhysicsClientHandle->b3PhysicsClientHandle__*
///collisionShapeInfo: b3CollisionShapeInformation*
[System.Runtime.InteropServices.DllImportAttribute(dllName, EntryPoint="b3GetCollisionShapeInformation")]
public static extern void b3GetCollisionShapeInformation(IntPtr physClient, ref b3CollisionShapeInformation collisionShapeInfo) ;
/// Return Type: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__*
///physClient: b3PhysicsClientHandle->b3PhysicsClientHandle__*
///filename: char*
@@ -2285,6 +2566,33 @@ public static extern int b3PhysicsParamSetEnableFileCaching(IntPtr commandHandl
public static extern int b3PhysicsParamSetRestitutionVelocityThreshold(IntPtr commandHandle, double restitutionVelocityThreshold) ;
/// Return Type: int
///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__*
///enableConeFriction: int
[System.Runtime.InteropServices.DllImportAttribute(dllName, EntryPoint="b3PhysicsParamSetEnableConeFriction")]
public static extern int b3PhysicsParamSetEnableConeFriction(IntPtr commandHandle, int enableConeFriction) ;
/// Return Type: int
///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__*
///deterministicOverlappingPairs: int
[System.Runtime.InteropServices.DllImportAttribute(dllName, EntryPoint="b3PhysicsParameterSetDeterministicOverlappingPairs")]
public static extern int b3PhysicsParameterSetDeterministicOverlappingPairs(IntPtr commandHandle, int deterministicOverlappingPairs) ;
/// Return Type: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__*
///physClient: b3PhysicsClientHandle->b3PhysicsClientHandle__*
[System.Runtime.InteropServices.DllImportAttribute(dllName, EntryPoint="b3InitRequestPhysicsParamCommand")]
public static extern System.IntPtr b3InitRequestPhysicsParamCommand(IntPtr physClient) ;
/// Return Type: int
///statusHandle: b3SharedMemoryStatusHandle->b3SharedMemoryStatusHandle__*
///params: b3PhysicsSimulationParameters*
[System.Runtime.InteropServices.DllImportAttribute(dllName, EntryPoint="b3GetStatusPhysicsSimulationParameters")]
public static extern int b3GetStatusPhysicsSimulationParameters(IntPtr statusHandle, ref b3PhysicsSimulationParameters @params) ;
/// Return Type: int
///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__*
///flags: int
@@ -2358,6 +2666,38 @@ public static extern int b3LoadUrdfCommandSetFlags(IntPtr commandHandle, int fl
public static extern int b3LoadUrdfCommandSetGlobalScaling(IntPtr commandHandle, double globalScaling) ;
/// Return Type: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__*
///physClient: b3PhysicsClientHandle->b3PhysicsClientHandle__*
[System.Runtime.InteropServices.DllImportAttribute(dllName, EntryPoint="b3SaveStateCommandInit")]
public static extern System.IntPtr b3SaveStateCommandInit(IntPtr physClient) ;
/// Return Type: int
///statusHandle: b3SharedMemoryStatusHandle->b3SharedMemoryStatusHandle__*
[System.Runtime.InteropServices.DllImportAttribute(dllName, EntryPoint="b3GetStatusGetStateId")]
public static extern int b3GetStatusGetStateId(IntPtr statusHandle) ;
/// Return Type: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__*
///physClient: b3PhysicsClientHandle->b3PhysicsClientHandle__*
[System.Runtime.InteropServices.DllImportAttribute(dllName, EntryPoint="b3LoadStateCommandInit")]
public static extern System.IntPtr b3LoadStateCommandInit(IntPtr physClient) ;
/// Return Type: int
///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__*
///stateId: int
[System.Runtime.InteropServices.DllImportAttribute(dllName, EntryPoint="b3LoadStateSetStateId")]
public static extern int b3LoadStateSetStateId(IntPtr commandHandle, int stateId) ;
/// Return Type: int
///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__*
///fileName: char*
[System.Runtime.InteropServices.DllImportAttribute(dllName, EntryPoint="b3LoadStateSetFileName")]
public static extern int b3LoadStateSetFileName(IntPtr commandHandle, [System.Runtime.InteropServices.InAttribute()] [System.Runtime.InteropServices.MarshalAsAttribute(System.Runtime.InteropServices.UnmanagedType.LPStr)] string fileName) ;
/// Return Type: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__*
///physClient: b3PhysicsClientHandle->b3PhysicsClientHandle__*
///fileName: char*
@@ -2426,6 +2766,23 @@ public static extern System.IntPtr b3CalculateJacobianCommandInit(IntPtr physCl
public static extern int b3GetStatusJacobian(IntPtr statusHandle, ref int dofCount, ref double linearJacobian, ref double angularJacobian) ;
/// Return Type: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__*
///physClient: b3PhysicsClientHandle->b3PhysicsClientHandle__*
///bodyIndex: int
///jointPositionsQ: double*
[System.Runtime.InteropServices.DllImportAttribute(dllName, EntryPoint="b3CalculateMassMatrixCommandInit")]
public static extern System.IntPtr b3CalculateMassMatrixCommandInit(IntPtr physClient, int bodyIndex, ref double jointPositionsQ) ;
/// Return Type: int
///physClient: b3PhysicsClientHandle->b3PhysicsClientHandle__*
///statusHandle: b3SharedMemoryStatusHandle->b3SharedMemoryStatusHandle__*
///dofCount: int*
///massMatrix: double*
[System.Runtime.InteropServices.DllImportAttribute(dllName, EntryPoint="b3GetStatusMassMatrix")]
public static extern int b3GetStatusMassMatrix(IntPtr physClient, IntPtr statusHandle, ref int dofCount, ref double massMatrix) ;
/// Return Type: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__*
///physClient: b3PhysicsClientHandle->b3PhysicsClientHandle__*
///bodyIndex: int
@@ -2485,6 +2842,13 @@ public static extern void b3CalculateInverseKinematicsPosOrnWithNullSpaceVel(In
public static extern void b3CalculateInverseKinematicsSetJointDamping(IntPtr commandHandle, int numDof, ref double jointDampingCoeff) ;
/// Return Type: void
///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__*
///solver: int
[System.Runtime.InteropServices.DllImportAttribute(dllName, EntryPoint="b3CalculateInverseKinematicsSelectSolver")]
public static extern void b3CalculateInverseKinematicsSelectSolver(IntPtr commandHandle, int solver) ;
/// Return Type: int
///statusHandle: b3SharedMemoryStatusHandle->b3SharedMemoryStatusHandle__*
///bodyUniqueId: int*
@@ -2561,6 +2925,14 @@ public static extern int b3JointControlSetKp(IntPtr commandHandle, int dofIndex
public static extern int b3JointControlSetKd(IntPtr commandHandle, int dofIndex, double value) ;
/// Return Type: int
///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__*
///dofIndex: int
///maximumVelocity: double
[System.Runtime.InteropServices.DllImportAttribute(dllName, EntryPoint="b3JointControlSetMaximumVelocity")]
public static extern int b3JointControlSetMaximumVelocity(IntPtr commandHandle, int dofIndex, double maximumVelocity) ;
/// Return Type: int
///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__*
///dofIndex: int
@@ -2666,6 +3038,85 @@ public static extern int b3GetStatusCollisionShapeUniqueId(IntPtr statusHandle)
public static extern System.IntPtr b3CreateVisualShapeCommandInit(IntPtr physClient) ;
/// Return Type: int
///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__*
///radius: double
[System.Runtime.InteropServices.DllImportAttribute(dllName, EntryPoint="b3CreateVisualShapeAddSphere")]
public static extern int b3CreateVisualShapeAddSphere(IntPtr commandHandle, double radius) ;
/// Return Type: int
///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__*
///halfExtents: double*
[System.Runtime.InteropServices.DllImportAttribute(dllName, EntryPoint="b3CreateVisualShapeAddBox")]
public static extern int b3CreateVisualShapeAddBox(IntPtr commandHandle, ref double halfExtents) ;
/// Return Type: int
///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__*
///radius: double
///height: double
[System.Runtime.InteropServices.DllImportAttribute(dllName, EntryPoint="b3CreateVisualShapeAddCapsule")]
public static extern int b3CreateVisualShapeAddCapsule(IntPtr commandHandle, double radius, double height) ;
/// Return Type: int
///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__*
///radius: double
///height: double
[System.Runtime.InteropServices.DllImportAttribute(dllName, EntryPoint="b3CreateVisualShapeAddCylinder")]
public static extern int b3CreateVisualShapeAddCylinder(IntPtr commandHandle, double radius, double height) ;
/// Return Type: int
///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__*
///planeNormal: double*
///planeConstant: double
[System.Runtime.InteropServices.DllImportAttribute(dllName, EntryPoint="b3CreateVisualShapeAddPlane")]
public static extern int b3CreateVisualShapeAddPlane(IntPtr commandHandle, ref double planeNormal, double planeConstant) ;
/// Return Type: int
///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__*
///fileName: char*
///meshScale: double*
[System.Runtime.InteropServices.DllImportAttribute(dllName, EntryPoint="b3CreateVisualShapeAddMesh")]
public static extern int b3CreateVisualShapeAddMesh(IntPtr commandHandle, [System.Runtime.InteropServices.InAttribute()] [System.Runtime.InteropServices.MarshalAsAttribute(System.Runtime.InteropServices.UnmanagedType.LPStr)] string fileName, ref double meshScale) ;
/// Return Type: void
///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__*
///shapeIndex: int
///flags: int
[System.Runtime.InteropServices.DllImportAttribute(dllName, EntryPoint="b3CreateVisualSetFlag")]
public static extern void b3CreateVisualSetFlag(IntPtr commandHandle, int shapeIndex, int flags) ;
/// Return Type: void
///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__*
///shapeIndex: int
///childPosition: double*
///childOrientation: double*
[System.Runtime.InteropServices.DllImportAttribute(dllName, EntryPoint="b3CreateVisualShapeSetChildTransform")]
public static extern void b3CreateVisualShapeSetChildTransform(IntPtr commandHandle, int shapeIndex, ref double childPosition, ref double childOrientation) ;
/// Return Type: void
///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__*
///shapeIndex: int
///specularColor: double*
[System.Runtime.InteropServices.DllImportAttribute(dllName, EntryPoint="b3CreateVisualShapeSetSpecularColor")]
public static extern void b3CreateVisualShapeSetSpecularColor(IntPtr commandHandle, int shapeIndex, ref double specularColor) ;
/// Return Type: void
///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__*
///shapeIndex: int
///rgbaColor: double*
[System.Runtime.InteropServices.DllImportAttribute(dllName, EntryPoint="b3CreateVisualShapeSetRGBAColor")]
public static extern void b3CreateVisualShapeSetRGBAColor(IntPtr commandHandle, int shapeIndex, ref double rgbaColor) ;
/// Return Type: int
///statusHandle: b3SharedMemoryStatusHandle->b3SharedMemoryStatusHandle__*
[System.Runtime.InteropServices.DllImportAttribute(dllName, EntryPoint="b3GetStatusVisualShapeUniqueId")]
@@ -3000,29 +3451,30 @@ public static extern void b3ApplyExternalTorque(IntPtr commandHandle, int bodyU
/// Return Type: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__*
///physClient: b3PhysicsClientHandle->b3PhysicsClientHandle__*
[System.Runtime.InteropServices.DllImportAttribute(dllName, EntryPoint="b3LoadBunnyCommandInit")]
public static extern System.IntPtr b3LoadBunnyCommandInit(IntPtr physClient) ;
///fileName: char*
[System.Runtime.InteropServices.DllImportAttribute(dllName, EntryPoint="b3LoadSoftBodyCommandInit")]
public static extern System.IntPtr b3LoadSoftBodyCommandInit(IntPtr physClient, [System.Runtime.InteropServices.InAttribute()] [System.Runtime.InteropServices.MarshalAsAttribute(System.Runtime.InteropServices.UnmanagedType.LPStr)] string fileName) ;
/// Return Type: int
///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__*
///scale: double
[System.Runtime.InteropServices.DllImportAttribute(dllName, EntryPoint="b3LoadBunnySetScale")]
public static extern int b3LoadBunnySetScale(IntPtr commandHandle, double scale) ;
[System.Runtime.InteropServices.DllImportAttribute(dllName, EntryPoint="b3LoadSoftBodySetScale")]
public static extern int b3LoadSoftBodySetScale(IntPtr commandHandle, double scale) ;
/// Return Type: int
///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__*
///mass: double
[System.Runtime.InteropServices.DllImportAttribute(dllName, EntryPoint="b3LoadBunnySetMass")]
public static extern int b3LoadBunnySetMass(IntPtr commandHandle, double mass) ;
[System.Runtime.InteropServices.DllImportAttribute(dllName, EntryPoint="b3LoadSoftBodySetMass")]
public static extern int b3LoadSoftBodySetMass(IntPtr commandHandle, double mass) ;
/// Return Type: int
///commandHandle: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__*
///collisionMargin: double
[System.Runtime.InteropServices.DllImportAttribute(dllName, EntryPoint="b3LoadBunnySetCollisionMargin")]
public static extern int b3LoadBunnySetCollisionMargin(IntPtr commandHandle, double collisionMargin) ;
[System.Runtime.InteropServices.DllImportAttribute(dllName, EntryPoint="b3LoadSoftBodySetCollisionMargin")]
public static extern int b3LoadSoftBodySetCollisionMargin(IntPtr commandHandle, double collisionMargin) ;
/// Return Type: b3SharedMemoryCommandHandle->b3SharedMemoryCommandHandle__*