Merge pull request #1121 from erwincoumans/master

don't render objects with zero alpha, expose the changeVisualShape RGBA color
This commit is contained in:
erwincoumans
2017-05-13 21:25:43 +00:00
committed by GitHub
33 changed files with 607 additions and 1503 deletions

View File

@@ -38,7 +38,8 @@ struct GUIHelperInterface
virtual int registerGraphicsInstance(int shapeIndex, const float* position, const float* quaternion, const float* color, const float* scaling) =0;
virtual void removeAllGraphicsInstances()=0;
virtual void removeGraphicsInstance(int graphicsUid) {}
virtual void changeRGBAColor(int instanceUid, const double rgbaColor[4]) {}
virtual Common2dCanvasInterface* get2dCanvasInterface()=0;
virtual CommonParameterInterface* getParameterInterface()=0;
@@ -125,6 +126,7 @@ struct DummyGUIHelper : public GUIHelperInterface
virtual int registerGraphicsInstance(int shapeIndex, const float* position, const float* quaternion, const float* color, const float* scaling) {return -1;}
virtual void removeAllGraphicsInstances(){}
virtual void removeGraphicsInstance(int graphicsUid){}
virtual void changeRGBAColor(int instanceUid, const double rgbaColor[4]) {}
virtual Common2dCanvasInterface* get2dCanvasInterface()
{

View File

@@ -55,10 +55,10 @@ struct CommonRenderInterface
virtual void writeSingleInstanceTransformToCPU(const float* position, const float* orientation, int srcIndex)=0;
virtual void writeSingleInstanceTransformToCPU(const double* position, const double* orientation, int srcIndex)=0;
virtual void writeSingleInstanceColorToCPU(float* color, int srcIndex)=0;
virtual void writeSingleInstanceColorToCPU(double* color, int srcIndex)=0;
virtual void writeSingleInstanceScaleToCPU(float* scale, int srcIndex)=0;
virtual void writeSingleInstanceScaleToCPU(double* scale, int srcIndex)=0;
virtual void writeSingleInstanceColorToCPU(const float* color, int srcIndex)=0;
virtual void writeSingleInstanceColorToCPU(const double* color, int srcIndex)=0;
virtual void writeSingleInstanceScaleToCPU(const float* scale, int srcIndex)=0;
virtual void writeSingleInstanceScaleToCPU(const double* scale, int srcIndex)=0;
virtual int getTotalNumInstances() const = 0;

View File

@@ -193,6 +193,8 @@ SET(BulletExampleBrowser_SRCS
../SharedMemory/PhysicsServerCommandProcessor.h
../SharedMemory/SharedMemoryCommands.h
../SharedMemory/SharedMemoryPublic.h
../RobotSimulator/b3RobotSimulatorClientAPI.cpp
../RobotSimulator/b3RobotSimulatorClientAPI.h
../BasicDemo/BasicExample.cpp
../BasicDemo/BasicExample.h
../InverseDynamics/InverseDynamicsExample.cpp
@@ -254,8 +256,6 @@ SET(BulletExampleBrowser_SRCS
../RoboticsLearning/GripperGraspExample.cpp
../RoboticsLearning/GripperGraspExample.h
../RoboticsLearning/b3RobotSimAPI.cpp
../RoboticsLearning/b3RobotSimAPI.h
../RoboticsLearning/R2D2GraspExample.cpp
../RoboticsLearning/R2D2GraspExample.h
../RoboticsLearning/KukaGraspExample.cpp

View File

@@ -314,6 +314,14 @@ void OpenGLGuiHelper::removeGraphicsInstance(int graphicsUid)
};
}
void OpenGLGuiHelper::changeRGBAColor(int instanceUid, const double rgbaColor[4])
{
if (instanceUid>=0)
{
m_data->m_glApp->m_renderer->writeSingleInstanceColorToCPU(rgbaColor,instanceUid);
};
}
int OpenGLGuiHelper::createCheckeredTexture(int red,int green, int blue)
{
int texWidth=1024;

View File

@@ -26,7 +26,8 @@ struct OpenGLGuiHelper : public GUIHelperInterface
virtual int registerGraphicsInstance(int shapeIndex, const float* position, const float* quaternion, const float* color, const float* scaling);
virtual void removeAllGraphicsInstances();
virtual void removeGraphicsInstance(int graphicsUid);
virtual void changeRGBAColor(int instanceUid, const double rgbaColor[4]);
virtual void createCollisionShapeGraphicsObject(btCollisionShape* collisionShape);
virtual void syncPhysicsToGraphics(const btDiscreteDynamicsWorld* rbWorld);

View File

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

View File

@@ -375,7 +375,7 @@ void GLInstancingRenderer::readSingleInstanceTransformFromCPU(int bodyUniqueId,
orientation[2] = m_data->m_instance_quaternion_ptr[srcIndex*4+2];
orientation[3] = m_data->m_instance_quaternion_ptr[srcIndex*4+3];
}
void GLInstancingRenderer::writeSingleInstanceColorToCPU(double* color, int bodyUniqueId)
void GLInstancingRenderer::writeSingleInstanceColorToCPU(const double* color, int bodyUniqueId)
{
b3PublicGraphicsInstance* pg = m_data->m_publicGraphicsInstances.getHandle(bodyUniqueId);
b3Assert(pg);
@@ -387,7 +387,7 @@ void GLInstancingRenderer::writeSingleInstanceColorToCPU(double* color, int body
m_data->m_instance_colors_ptr[srcIndex*4+3]=float(color[3]);
}
void GLInstancingRenderer::writeSingleInstanceColorToCPU(float* color, int bodyUniqueId)
void GLInstancingRenderer::writeSingleInstanceColorToCPU(const float* color, int bodyUniqueId)
{
b3PublicGraphicsInstance* pg = m_data->m_publicGraphicsInstances.getHandle(bodyUniqueId);
b3Assert(pg);
@@ -399,7 +399,7 @@ void GLInstancingRenderer::writeSingleInstanceColorToCPU(float* color, int bodyU
m_data->m_instance_colors_ptr[srcIndex*4+3]=color[3];
}
void GLInstancingRenderer::writeSingleInstanceScaleToCPU(float* scale, int bodyUniqueId)
void GLInstancingRenderer::writeSingleInstanceScaleToCPU(const float* scale, int bodyUniqueId)
{
b3PublicGraphicsInstance* pg = m_data->m_publicGraphicsInstances.getHandle(bodyUniqueId);
b3Assert(pg);
@@ -410,7 +410,7 @@ void GLInstancingRenderer::writeSingleInstanceScaleToCPU(float* scale, int bodyU
m_data->m_instance_scale_ptr[srcIndex*3+2]=scale[2];
}
void GLInstancingRenderer::writeSingleInstanceScaleToCPU(double* scale, int bodyUniqueId)
void GLInstancingRenderer::writeSingleInstanceScaleToCPU(const double* scale, int bodyUniqueId)
{
b3PublicGraphicsInstance* pg = m_data->m_publicGraphicsInstances.getHandle(bodyUniqueId);
b3Assert(pg);

View File

@@ -98,11 +98,11 @@ public:
virtual void writeSingleInstanceTransformToGPU(float* position, float* orientation, int srcIndex);
virtual void writeSingleInstanceColorToCPU(float* color, int srcIndex);
virtual void writeSingleInstanceColorToCPU(double* color, int srcIndex);
virtual void writeSingleInstanceColorToCPU(const float* color, int srcIndex);
virtual void writeSingleInstanceColorToCPU(const double* color, int srcIndex);
virtual void writeSingleInstanceScaleToCPU(float* scale, int srcIndex);
virtual void writeSingleInstanceScaleToCPU(double* scale, int srcIndex);
virtual void writeSingleInstanceScaleToCPU(const float* scale, int srcIndex);
virtual void writeSingleInstanceScaleToCPU(const double* scale, int srcIndex);
virtual struct GLInstanceRendererInternalData* getInternalData();

View File

@@ -23,10 +23,12 @@ out vec4 color;
void main(void)
{
vec4 texel = fragment.color*texture(Diffuse,vert.texcoord);
vec4 texel = fragment.color*texture(Diffuse,vert.texcoord);
vec3 ct,cf;
float intensity,at,af;
if (fragment.color.w==0)
discard;
intensity = 0.5+0.5*clamp( dot( normalize(normal),lightDir ), -1,1 );
af = 1.0;
@@ -45,6 +47,5 @@ void main(void)
intensity = 0.7*intensity + 0.3*intensity*visibility;
cf = intensity*(vec3(1.0,1.0,1.0)-ambient)+ambient;
color = vec4(ct * cf, fragment.color.w);
}

View File

@@ -17,10 +17,11 @@ static const char* useShadowMapInstancingFragmentShader= \
"out vec4 color;\n"
"void main(void)\n"
"{\n"
" vec4 texel = fragment.color*texture(Diffuse,vert.texcoord);\n"
" vec4 texel = fragment.color*texture(Diffuse,vert.texcoord);\n"
" vec3 ct,cf;\n"
" float intensity,at,af;\n"
" \n"
" if (fragment.color.w==0)\n"
" discard;\n"
" intensity = 0.5+0.5*clamp( dot( normalize(normal),lightDir ), -1,1 );\n"
" \n"
" af = 1.0;\n"
@@ -37,7 +38,6 @@ static const char* useShadowMapInstancingFragmentShader= \
" intensity = 0.7*intensity + 0.3*intensity*visibility;\n"
" \n"
" cf = intensity*(vec3(1.0,1.0,1.0)-ambient)+ambient;\n"
" \n"
" color = vec4(ct * cf, fragment.color.w);\n"
"}\n"
;

View File

@@ -26,7 +26,7 @@ B3_ATTRIBUTE_ALIGNED16(struct) SimpleGL2Instance
int m_shapeIndex;
b3Vector3 m_position;
b3Quaternion orn;
b3Vector3 m_rgbColor;
b3Vector4 m_rgbColor;
b3Vector3 m_scaling;
void clear()
{
@@ -139,18 +139,18 @@ void SimpleOpenGL2Renderer::removeGraphicsInstance(int instanceUid)
m_data->m_graphicsInstancesPool.freeHandle(instanceUid);
}
void SimpleOpenGL2Renderer::writeSingleInstanceColorToCPU(float* color, int srcIndex)
void SimpleOpenGL2Renderer::writeSingleInstanceColorToCPU(const float* color, int srcIndex)
{
}
void SimpleOpenGL2Renderer::writeSingleInstanceColorToCPU(double* color, int srcIndex)
void SimpleOpenGL2Renderer::writeSingleInstanceColorToCPU(const double* color, int srcIndex)
{
}
void SimpleOpenGL2Renderer::writeSingleInstanceScaleToCPU(float* scale, int srcIndex)
void SimpleOpenGL2Renderer::writeSingleInstanceScaleToCPU(const float* scale, int srcIndex)
{
}
void SimpleOpenGL2Renderer::writeSingleInstanceScaleToCPU(double* scale, int srcIndex)
void SimpleOpenGL2Renderer::writeSingleInstanceScaleToCPU(const double* scale, int srcIndex)
{
}
@@ -182,6 +182,10 @@ void SimpleOpenGL2Renderer::drawOpenGL(int instanceIndex)
const SimpleGL2Instance& inst = *instPtr;
const SimpleGL2Shape* shape = m_data->m_shapes[inst.m_shapeIndex];
if (inst.m_rgbColor[3]==0)
{
return;
}
glPushMatrix();
b3Transform tr;
@@ -475,6 +479,8 @@ int SimpleOpenGL2Renderer::registerGraphicsInstance(int shapeIndex, const double
instance.m_rgbColor[0] = color[0];
instance.m_rgbColor[1] = color[1];
instance.m_rgbColor[2] = color[2];
instance.m_rgbColor[3] = color[3];
instance.m_scaling[0] = scaling[0];
instance.m_scaling[1] = scaling[1];
instance.m_scaling[2] = scaling[2];
@@ -496,6 +502,8 @@ int SimpleOpenGL2Renderer::registerGraphicsInstance(int shapeIndex, const float*
instance.m_rgbColor[0] = color[0];
instance.m_rgbColor[1] = color[1];
instance.m_rgbColor[2] = color[2];
instance.m_rgbColor[3] = color[3];
instance.m_scaling[0] = scaling[0];
instance.m_scaling[1] = scaling[1];
instance.m_scaling[2] = scaling[2];

View File

@@ -34,10 +34,10 @@ public:
virtual void removeAllInstances();
virtual void removeGraphicsInstance(int instanceUid);
virtual void writeSingleInstanceColorToCPU(float* color, int srcIndex);
virtual void writeSingleInstanceColorToCPU(double* color, int srcIndex);
virtual void writeSingleInstanceScaleToCPU(float* scale, int srcIndex);
virtual void writeSingleInstanceScaleToCPU(double* scale, int srcIndex);
virtual void writeSingleInstanceColorToCPU(const float* color, int srcIndex);
virtual void writeSingleInstanceColorToCPU(const double* color, int srcIndex);
virtual void writeSingleInstanceScaleToCPU(const float* scale, int srcIndex);
virtual void writeSingleInstanceScaleToCPU(const double* scale, int srcIndex);
virtual void getCameraViewMatrix(float viewMat[16]) const;
virtual void getCameraProjectionMatrix(float projMat[16]) const;

View File

@@ -2,29 +2,32 @@
//#include "SharedMemoryCommands.h"
#include "SharedMemory/PhysicsClientC_API.h"
#include "../SharedMemory/PhysicsClientC_API.h"
#ifdef BT_ENABLE_ENET
#include "SharedMemory/PhysicsClientUDP_C_API.h"
#include "../SharedMemory/PhysicsClientUDP_C_API.h"
#endif //PHYSICS_UDP
#ifdef BT_ENABLE_CLSOCKET
#include "SharedMemory/PhysicsClientTCP_C_API.h"
#include "../SharedMemory/PhysicsClientTCP_C_API.h"
#endif //PHYSICS_TCP
#include "SharedMemory/PhysicsDirectC_API.h"
#include "../SharedMemory/PhysicsDirectC_API.h"
#include "SharedMemory/SharedMemoryInProcessPhysicsC_API.h"
#include "../SharedMemory/SharedMemoryInProcessPhysicsC_API.h"
#include "SharedMemory/SharedMemoryPublic.h"
#include "../SharedMemory/SharedMemoryPublic.h"
#include "Bullet3Common/b3Logging.h"
struct b3RobotSimulatorClientAPI_InternalData
{
b3PhysicsClientHandle m_physicsClientHandle;
struct GUIHelperInterface* m_guiHelper;
b3RobotSimulatorClientAPI_InternalData()
: m_physicsClientHandle(0)
: m_physicsClientHandle(0),
m_guiHelper(0)
{
}
};
@@ -39,6 +42,66 @@ b3RobotSimulatorClientAPI::~b3RobotSimulatorClientAPI()
delete m_data;
}
void b3RobotSimulatorClientAPI::setGuiHelper(struct GUIHelperInterface* guiHelper)
{
m_data->m_guiHelper = guiHelper;
}
void b3RobotSimulatorClientAPI::renderScene()
{
if (!isConnected())
{
b3Warning("Not connected");
return;
}
if (m_data->m_guiHelper)
{
b3InProcessRenderSceneInternal(m_data->m_physicsClientHandle);
}
}
void b3RobotSimulatorClientAPI::debugDraw(int debugDrawMode)
{
if (!isConnected())
{
b3Warning("Not connected");
return;
}
if (m_data->m_guiHelper)
{
b3InProcessDebugDrawInternal(m_data->m_physicsClientHandle,debugDrawMode);
}
}
bool b3RobotSimulatorClientAPI::mouseMoveCallback(float x,float y)
{
if (!isConnected())
{
b3Warning("Not connected");
return false;
}
if (m_data->m_guiHelper)
{
return b3InProcessMouseMoveCallback(m_data->m_physicsClientHandle, x,y);
}
return false;
}
bool b3RobotSimulatorClientAPI::mouseButtonCallback(int button, int state, float x, float y)
{
if (!isConnected())
{
b3Warning("Not connected");
return false;
}
if (m_data->m_guiHelper)
{
return b3InProcessMouseButtonCallback(m_data->m_physicsClientHandle, button,state,x,y);
}
return false;
}
bool b3RobotSimulatorClientAPI::connect(int mode, const std::string& hostName, int portOrKey)
{
if (m_data->m_physicsClientHandle)
@@ -55,6 +118,12 @@ bool b3RobotSimulatorClientAPI::connect(int mode, const std::string& hostName, i
switch (mode)
{
case eCONNECT_EXISTING_EXAMPLE_BROWSER:
{
sm = b3CreateInProcessPhysicsServerFromExistingExampleBrowserAndConnect(m_data->m_guiHelper);
break;
}
case eCONNECT_GUI:
{
int argc = 0;
@@ -644,8 +713,72 @@ bool b3RobotSimulatorClientAPI::getJointState(int bodyUniqueId, int jointIndex,
return false;
}
bool b3RobotSimulatorClientAPI::getJointStates(int bodyUniqueId, b3JointStates2& state)
{
if (!isConnected())
{
b3Warning("Not connected");
return false;
}
b3SharedMemoryCommandHandle command = b3RequestActualStateCommandInit(m_data->m_physicsClientHandle,bodyUniqueId);
b3SharedMemoryStatusHandle statusHandle = b3SubmitClientCommandAndWaitStatus(m_data->m_physicsClientHandle, command);
if (statusHandle)
{
// double rootInertialFrame[7];
const double* rootLocalInertialFrame;
const double* actualStateQ;
const double* actualStateQdot;
const double* jointReactionForces;
int stat = b3GetStatusActualState(statusHandle,
&state.m_bodyUniqueId,
&state.m_numDegreeOfFreedomQ,
&state.m_numDegreeOfFreedomU,
&rootLocalInertialFrame,
&actualStateQ,
&actualStateQdot,
&jointReactionForces);
if (stat)
{
state.m_actualStateQ.resize(state.m_numDegreeOfFreedomQ);
state.m_actualStateQdot.resize(state.m_numDegreeOfFreedomU);
for (int i=0;i<state.m_numDegreeOfFreedomQ;i++)
{
state.m_actualStateQ[i] = actualStateQ[i];
}
for (int i=0;i<state.m_numDegreeOfFreedomU;i++)
{
state.m_actualStateQdot[i] = actualStateQdot[i];
}
int numJoints = getNumJoints(bodyUniqueId);
state.m_jointReactionForces.resize(6*numJoints);
for (int i=0;i<numJoints*6;i++)
{
state.m_jointReactionForces[i] = jointReactionForces[i];
}
return true;
}
//rootInertialFrame,
// &state.m_actualStateQ[0],
// &state.m_actualStateQdot[0],
// &state.m_jointReactionForces[0]);
}
return false;
}
bool b3RobotSimulatorClientAPI::resetJointState(int bodyUniqueId, int jointIndex, double targetValue)
{
if (!isConnected())
{
b3Warning("Not connected");
return false;
}
b3SharedMemoryCommandHandle commandHandle;
b3SharedMemoryStatusHandle statusHandle;
int numJoints;
@@ -995,4 +1128,19 @@ void b3RobotSimulatorClientAPI::submitProfileTiming(const std::string& profileN
b3SetProfileTimingDuractionInMicroSeconds(commandHandle, durationInMicroSeconds);
}
b3SubmitClientCommandAndWaitStatus(m_data->m_physicsClientHandle, commandHandle);
}
void b3RobotSimulatorClientAPI::loadBunny(double scale, double mass, double collisionMargin)
{
if (!isConnected())
{
b3Warning("Not connected");
return;
}
b3SharedMemoryCommandHandle command = b3LoadBunnyCommandInit(m_data->m_physicsClientHandle);
b3LoadBunnySetScale(command, scale);
b3LoadBunnySetMass(command, mass);
b3LoadBunnySetCollisionMargin(command, collisionMargin);
b3SubmitClientCommand(m_data->m_physicsClientHandle, command);
}

View File

@@ -124,6 +124,17 @@ struct b3RobotSimulatorInverseKinematicsResults
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
///as documented in the pybullet Quickstart Guide
///https://docs.google.com/document/d/10sXEhzFRSnvFcl3XxNGhnD4N2SedqwdAvK3dsihxVUA
@@ -177,6 +188,8 @@ public:
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);
@@ -213,6 +226,21 @@ public:
void submitProfileTiming(const std::string& profileName, int durationInMicroSeconds=1);
//////////////// INTERNAL
void loadBunny(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 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

@@ -199,6 +199,7 @@ if not _OPTIONS["no-enet"] then
end
if _OPTIONS["serial"] then
project ("App_VRGloveHandSimulator")
@@ -248,12 +249,11 @@ project ("App_VRGloveHandSimulator")
}
defines {"B3_ENABLE_TINY_AUDIO"}
if _OPTIONS["serial"] then
defines{"B3_ENABLE_SERIAL"}
includedirs {"../../examples/ThirdPartyLibs/serial/include"}
links {"serial"}
end
defines{"B3_ENABLE_SERIAL"}
includedirs {"../../examples/ThirdPartyLibs/serial/include"}
links {"serial"}
if os.is("Windows") then
links {"winmm","Wsock32","dsound"}
defines {"WIN32","__WINDOWS_MM__","__WINDOWS_DS__"}
@@ -280,3 +280,4 @@ project ("App_VRGloveHandSimulator")
if os.is("Linux") then
initX11()
end
end

View File

@@ -13,7 +13,7 @@
#include "../SharedMemory/SharedMemoryPublic.h"
#include <string>
#include "b3RobotSimAPI.h"
#include "../RobotSimulator/b3RobotSimulatorClientAPI.h"
#include "../Utils/b3Clock.h"
static btScalar sGripperVerticalVelocity = 0.f;
@@ -23,7 +23,7 @@ class GripperGraspExample : public CommonExampleInterface
{
CommonGraphicsApp* m_app;
GUIHelperInterface* m_guiHelper;
b3RobotSimAPI m_robotSim;
b3RobotSimulatorClientAPI m_robotSim;
int m_options;
int m_gripperIndex;
@@ -55,8 +55,12 @@ public:
}
virtual void initPhysics()
{
bool connected = m_robotSim.connect(m_guiHelper);
b3Printf("robotSim connected = %d",connected);
int mode = eCONNECT_EXISTING_EXAMPLE_BROWSER;
m_robotSim.setGuiHelper(m_guiHelper);
bool connected = m_robotSim.connect(mode);
b3Printf("robotSim connected = %d",connected);
if ((m_options & eGRIPPER_GRASP)!=0)
{
@@ -76,23 +80,18 @@ public:
m_guiHelper->getParameterInterface()->registerSliderFloatParameter(slider);
}
{
b3RobotSimLoadFileArgs args("");
b3RobotSimLoadFileResults results;
args.m_fileName = "cube_small.urdf";
b3RobotSimulatorLoadUrdfFileArgs args;
args.m_startPosition.setValue(0, 0, .107);
args.m_startOrientation.setEulerZYX(0, 0, 0);
args.m_useMultiBody = true;
m_robotSim.loadFile(args, results);
m_robotSim.loadURDF("cube_small.urdf", args);
}
{
b3RobotSimLoadFileArgs args("");
args.m_fileName = "gripper/wsg50_with_r2d2_gripper.sdf";
args.m_fileType = B3_SDF_FILE;
args.m_useMultiBody = true;
b3RobotSimLoadFileResults results;
if (m_robotSim.loadFile(args, results) && results.m_uniqueObjectIds.size()==1)
b3RobotSimulatorLoadFileResults results;
m_robotSim.loadSDF("gripper/wsg50_with_r2d2_gripper.sdf",results);
if (results.m_uniqueObjectIds.size()==1)
{
m_gripperIndex = results.m_uniqueObjectIds[0];
@@ -111,7 +110,7 @@ public:
double fingerTargetPositions[2]={-0.04,0.04};
for (int i=0;i<2;i++)
{
b3JointMotorArgs controlArgs(CONTROL_MODE_POSITION_VELOCITY_PD);
b3RobotSimulatorJointMotorArgs controlArgs(CONTROL_MODE_POSITION_VELOCITY_PD);
controlArgs.m_targetPosition = fingerTargetPositions[i];
controlArgs.m_kp = 5.0;
controlArgs.m_kd = 3.0;
@@ -124,7 +123,7 @@ public:
double maxTorqueValues[3]={40.0,50.0,50.0};
for (int i=0;i<3;i++)
{
b3JointMotorArgs controlArgs(CONTROL_MODE_VELOCITY);
b3RobotSimulatorJointMotorArgs controlArgs(CONTROL_MODE_VELOCITY);
controlArgs.m_targetVelocity = fingerTargetVelocities[i];
controlArgs.m_maxTorqueValue = maxTorqueValues[i];
controlArgs.m_kd = 1.;
@@ -135,15 +134,7 @@ public:
if (1)
{
b3RobotSimLoadFileArgs args("");
args.m_fileName = "plane.urdf";
args.m_startPosition.setValue(0,0,0);
args.m_startOrientation.setEulerZYX(0,0,0);
args.m_forceOverrideFixedBase = true;
args.m_useMultiBody = true;
b3RobotSimLoadFileResults results;
m_robotSim.loadFile(args,results);
m_robotSim.loadURDF("plane.urdf");
}
m_robotSim.setGravity(b3MakeVector3(0,0,-10));
m_robotSim.setNumSimulationSubSteps(4);
@@ -152,24 +143,17 @@ public:
if ((m_options & eTWO_POINT_GRASP)!=0)
{
{
b3RobotSimLoadFileArgs args("");
b3RobotSimLoadFileResults results;
args.m_fileName = "cube_small.urdf";
b3RobotSimulatorLoadUrdfFileArgs args;
args.m_startPosition.setValue(0, 0, .107);
args.m_startOrientation.setEulerZYX(0, 0, 0);
args.m_useMultiBody = true;
m_robotSim.loadFile(args, results);
m_robotSim.loadURDF("cube_small.urdf", args);
}
{
b3RobotSimLoadFileArgs args("");
b3RobotSimLoadFileResults results;
args.m_fileName = "cube_gripper_left.urdf";
b3RobotSimulatorLoadUrdfFileArgs args;
args.m_startPosition.setValue(0.068, 0.02, 0.11);
args.m_useMultiBody = true;
m_robotSim.loadFile(args, results);
m_robotSim.loadURDF("cube_gripper_left.urdf", args);
b3JointMotorArgs controlArgs(CONTROL_MODE_VELOCITY);
b3RobotSimulatorJointMotorArgs controlArgs(CONTROL_MODE_VELOCITY);
controlArgs.m_targetVelocity = -0.1;
controlArgs.m_maxTorqueValue = 10.0;
controlArgs.m_kd = 1.;
@@ -177,14 +161,11 @@ public:
}
{
b3RobotSimLoadFileArgs args("");
b3RobotSimLoadFileResults results;
args.m_fileName = "cube_gripper_right.urdf";
b3RobotSimulatorLoadUrdfFileArgs args;
args.m_startPosition.setValue(-0.068, 0.02, 0.11);
args.m_useMultiBody = true;
m_robotSim.loadFile(args, results);
m_robotSim.loadURDF("cube_gripper_right.urdf", args);
b3JointMotorArgs controlArgs(CONTROL_MODE_VELOCITY);
b3RobotSimulatorJointMotorArgs controlArgs(CONTROL_MODE_VELOCITY);
controlArgs.m_targetVelocity = 0.1;
controlArgs.m_maxTorqueValue = 10.0;
controlArgs.m_kd = 1.;
@@ -193,14 +174,7 @@ public:
if (1)
{
b3RobotSimLoadFileArgs args("");
args.m_fileName = "plane.urdf";
args.m_startPosition.setValue(0,0,0);
args.m_startOrientation.setEulerZYX(0,0,0);
args.m_forceOverrideFixedBase = true;
args.m_useMultiBody = true;
b3RobotSimLoadFileResults results;
m_robotSim.loadFile(args,results);
m_robotSim.loadURDF("plane.urdf");
}
m_robotSim.setGravity(b3MakeVector3(0,0,-10));
@@ -225,22 +199,17 @@ public:
m_guiHelper->getParameterInterface()->registerSliderFloatParameter(slider);
}
{
b3RobotSimLoadFileArgs args("");
b3RobotSimLoadFileResults results;
args.m_fileName = "dinnerware/pan_tefal.urdf";
b3RobotSimulatorLoadUrdfFileArgs args;
args.m_startPosition.setValue(0, -0.2, .47);
args.m_startOrientation.setEulerZYX(SIMD_HALF_PI, 0, 0);
args.m_useMultiBody = true;
m_robotSim.loadFile(args, results);
m_robotSim.loadURDF("dinnerware/pan_tefal.urdf", args);
}
{
b3RobotSimLoadFileArgs args("");
args.m_fileName = "gripper/wsg50_one_motor_gripper_new.sdf";
args.m_fileType = B3_SDF_FILE;
args.m_useMultiBody = true;
b3RobotSimLoadFileResults results;
if (m_robotSim.loadFile(args, results) && results.m_uniqueObjectIds.size()==1)
b3RobotSimulatorLoadFileResults args;
b3RobotSimulatorLoadFileResults results;
m_robotSim.loadSDF("gripper/wsg50_one_motor_gripper_new.sdf",results);
if (results.m_uniqueObjectIds.size()==1)
{
m_gripperIndex = results.m_uniqueObjectIds[0];
@@ -256,7 +225,7 @@ public:
for (int i=0;i<8;i++)
{
b3JointMotorArgs controlArgs(CONTROL_MODE_VELOCITY);
b3RobotSimulatorJointMotorArgs controlArgs(CONTROL_MODE_VELOCITY);
controlArgs.m_maxTorqueValue = 0.0;
m_robotSim.setJointMotorControl(m_gripperIndex,i,controlArgs);
}
@@ -266,15 +235,7 @@ public:
if (1)
{
b3RobotSimLoadFileArgs args("");
args.m_fileName = "plane.urdf";
args.m_startPosition.setValue(0,0,0);
args.m_startOrientation.setEulerZYX(0,0,0);
args.m_forceOverrideFixedBase = true;
args.m_useMultiBody = true;
b3RobotSimLoadFileResults results;
m_robotSim.loadFile(args,results);
m_robotSim.loadURDF("plane.urdf");
}
m_robotSim.setGravity(b3MakeVector3(0,0,-10));
@@ -316,8 +277,8 @@ public:
revoluteJoint2.m_jointAxis[1] = 0.0;
revoluteJoint2.m_jointAxis[2] = 0.0;
revoluteJoint2.m_jointType = ePoint2PointType;
m_robotSim.createJoint(1, 2, 1, 4, &revoluteJoint1);
m_robotSim.createJoint(1, 3, 1, 6, &revoluteJoint2);
m_robotSim.createConstraint(1, 2, 1, 4, &revoluteJoint1);
m_robotSim.createConstraint(1, 3, 1, 6, &revoluteJoint2);
}
if ((m_options & eGRASP_SOFT_BODY)!=0)
@@ -337,13 +298,10 @@ public:
m_guiHelper->getParameterInterface()->registerSliderFloatParameter(slider);
}
{
b3RobotSimLoadFileArgs args("");
args.m_fileName = "gripper/wsg50_one_motor_gripper_new.sdf";
args.m_fileType = B3_SDF_FILE;
args.m_useMultiBody = true;
b3RobotSimLoadFileResults results;
if (m_robotSim.loadFile(args, results) && results.m_uniqueObjectIds.size()==1)
b3RobotSimulatorLoadFileResults results;
m_robotSim.loadSDF("gripper/wsg50_one_motor_gripper_new.sdf",results);
if (results.m_uniqueObjectIds.size()==1)
{
m_gripperIndex = results.m_uniqueObjectIds[0];
@@ -359,7 +317,7 @@ public:
for (int i=0;i<8;i++)
{
b3JointMotorArgs controlArgs(CONTROL_MODE_VELOCITY);
b3RobotSimulatorJointMotorArgs controlArgs(CONTROL_MODE_VELOCITY);
controlArgs.m_maxTorqueValue = 0.0;
m_robotSim.setJointMotorControl(m_gripperIndex,i,controlArgs);
}
@@ -367,14 +325,10 @@ public:
}
}
{
b3RobotSimLoadFileArgs args("");
args.m_fileName = "plane.urdf";
b3RobotSimulatorLoadUrdfFileArgs args;
args.m_startPosition.setValue(0,0,-0.2);
args.m_startOrientation.setEulerZYX(0,0,0);
args.m_forceOverrideFixedBase = true;
args.m_useMultiBody = true;
b3RobotSimLoadFileResults results;
m_robotSim.loadFile(args,results);
m_robotSim.loadURDF("plane.urdf", args);
}
m_robotSim.setGravity(b3MakeVector3(0,0,-10));
@@ -418,23 +372,20 @@ public:
revoluteJoint2.m_jointAxis[1] = 0.0;
revoluteJoint2.m_jointAxis[2] = 0.0;
revoluteJoint2.m_jointType = ePoint2PointType;
m_robotSim.createJoint(0, 2, 0, 4, &revoluteJoint1);
m_robotSim.createJoint(0, 3, 0, 6, &revoluteJoint2);
m_robotSim.createConstraint(0, 2, 0, 4, &revoluteJoint1);
m_robotSim.createConstraint(0, 3, 0, 6, &revoluteJoint2);
}
if ((m_options & eSOFTBODY_MULTIBODY_COUPLING)!=0)
{
{
b3RobotSimLoadFileArgs args("");
args.m_fileName = "kuka_iiwa/model_free_base.urdf";
b3RobotSimulatorLoadUrdfFileArgs args;
args.m_startPosition.setValue(0,1.0,2.0);
args.m_startOrientation.setEulerZYX(0,0,1.57);
args.m_forceOverrideFixedBase = false;
args.m_useMultiBody = true;
b3RobotSimLoadFileResults results;
m_robotSim.loadFile(args,results);
int kukaId = m_robotSim.loadURDF("kuka_iiwa/model_free_base.urdf", args);
int kukaId = results.m_uniqueObjectIds[0];
int numJoints = m_robotSim.getNumJoints(kukaId);
b3Printf("numJoints = %d",numJoints);
@@ -443,20 +394,18 @@ public:
b3JointInfo jointInfo;
m_robotSim.getJointInfo(kukaId,i,&jointInfo);
b3Printf("joint[%d].m_jointName=%s",i,jointInfo.m_jointName);
b3JointMotorArgs controlArgs(CONTROL_MODE_VELOCITY);
b3RobotSimulatorJointMotorArgs controlArgs(CONTROL_MODE_VELOCITY);
controlArgs.m_maxTorqueValue = 0.0;
m_robotSim.setJointMotorControl(kukaId,i,controlArgs);
}
}
{
b3RobotSimLoadFileArgs args("");
args.m_fileName = "plane.urdf";
b3RobotSimulatorLoadUrdfFileArgs args;
args.m_startPosition.setValue(0,0,0);
args.m_startOrientation.setEulerZYX(0,0,0);
args.m_forceOverrideFixedBase = true;
args.m_useMultiBody = false;
b3RobotSimLoadFileResults results;
m_robotSim.loadFile(args,results);
m_robotSim.loadURDF("plane.urdf", args);
}
m_robotSim.setGravity(b3MakeVector3(0,0,-10));
m_robotSim.loadBunny(0.5,10.0,0.1);
@@ -479,7 +428,7 @@ public:
double maxTorqueValues[3]={40.0,50.0,50.0};
for (int i=0;i<3;i++)
{
b3JointMotorArgs controlArgs(CONTROL_MODE_VELOCITY);
b3RobotSimulatorJointMotorArgs controlArgs(CONTROL_MODE_VELOCITY);
controlArgs.m_targetVelocity = fingerTargetVelocities[i];
controlArgs.m_maxTorqueValue = maxTorqueValues[i];
controlArgs.m_kd = 1.;
@@ -496,7 +445,7 @@ public:
double maxTorqueValues[2]={800.0,800.0};
for (int i=0;i<2;i++)
{
b3JointMotorArgs controlArgs(CONTROL_MODE_VELOCITY);
b3RobotSimulatorJointMotorArgs controlArgs(CONTROL_MODE_VELOCITY);
controlArgs.m_targetVelocity = fingerTargetVelocities[i];
controlArgs.m_maxTorqueValue = maxTorqueValues[i];
controlArgs.m_kd = 1.;
@@ -512,7 +461,7 @@ public:
double maxTorqueValues[2]={50.0,10.0};
for (int i=0;i<2;i++)
{
b3JointMotorArgs controlArgs(CONTROL_MODE_VELOCITY);
b3RobotSimulatorJointMotorArgs controlArgs(CONTROL_MODE_VELOCITY);
controlArgs.m_targetVelocity = fingerTargetVelocities[i];
controlArgs.m_maxTorqueValue = maxTorqueValues[i];
controlArgs.m_kd = 1.;
@@ -531,17 +480,13 @@ public:
}
virtual void physicsDebugDraw()
{
}
virtual bool mouseMoveCallback(float x,float y)
{
return false;
return m_robotSim.mouseMoveCallback(x,y);
}
virtual bool mouseButtonCallback(int button, int state, float x, float y)
{
return false;
return m_robotSim.mouseButtonCallback(button,state,x,y);
}
virtual bool keyboardCallback(int key, int state)
{

View File

@@ -11,8 +11,8 @@
#include "../SharedMemory/PhysicsServerSharedMemory.h"
#include "../SharedMemory/PhysicsClientC_API.h"
#include <string>
#include "../RobotSimulator/b3RobotSimulatorClientAPI.h"
#include "b3RobotSimAPI.h"
#include "../Utils/b3Clock.h"
///quick demo showing the right-handed coordinate system and positive rotations around each axis
@@ -20,7 +20,8 @@ class KukaGraspExample : public CommonExampleInterface
{
CommonGraphicsApp* m_app;
GUIHelperInterface* m_guiHelper;
b3RobotSimAPI m_robotSim;
b3RobotSimulatorClientAPI m_robotSim;
int m_kukaIndex;
IKTrajectoryHelper m_ikHelper;
@@ -57,10 +58,7 @@ public:
}
virtual void physicsDebugDraw(int debugDrawMode)
{
}
virtual void initPhysics()
{
@@ -78,19 +76,18 @@ public:
bool connected = m_robotSim.connect(m_guiHelper);
int mode = eCONNECT_EXISTING_EXAMPLE_BROWSER;
m_robotSim.setGuiHelper(m_guiHelper);
bool connected = m_robotSim.connect(mode);
// 0;//m_robotSim.connect(m_guiHelper);
b3Printf("robotSim connected = %d",connected);
{
b3RobotSimLoadFileArgs args("");
args.m_fileName = "kuka_iiwa/model.urdf";
args.m_startPosition.setValue(0,0,0);
b3RobotSimLoadFileResults results;
if (m_robotSim.loadFile(args, results) && results.m_uniqueObjectIds.size()==1)
m_kukaIndex = m_robotSim.loadURDF("kuka_iiwa/model.urdf");
if (m_kukaIndex >=0)
{
m_kukaIndex = results.m_uniqueObjectIds[0];
int numJoints = m_robotSim.getNumJoints(m_kukaIndex);
b3Printf("numJoints = %d",numJoints);
@@ -112,24 +109,9 @@ public:
}
*/
}
if (0)
{
b3RobotSimLoadFileArgs args("");
args.m_fileName = "kiva_shelf/model.sdf";
args.m_forceOverrideFixedBase = true;
args.m_fileType = B3_SDF_FILE;
args.m_startOrientation = b3Quaternion(0,0,0,1);
b3RobotSimLoadFileResults results;
m_robotSim.loadFile(args,results);
}
{
b3RobotSimLoadFileArgs args("");
args.m_fileName = "plane.urdf";
args.m_startPosition.setValue(0,0,0);
args.m_forceOverrideFixedBase = true;
b3RobotSimLoadFileResults results;
m_robotSim.loadFile(args,results);
m_robotSim.loadURDF("plane.urdf");
m_robotSim.setGravity(b3MakeVector3(0,0,0));
}
@@ -157,9 +139,7 @@ public:
{
double q_current[7]={0,0,0,0,0,0,0};
double world_position[3]={0,0,0};
double world_orientation[4]={0,0,0,0};
b3JointStates jointStates;
b3JointStates2 jointStates;
if (m_robotSim.getJointStates(m_kukaIndex,jointStates))
{
@@ -171,10 +151,13 @@ public:
}
}
// compute body position and orientation
m_robotSim.getLinkState(0, 6, world_position, world_orientation);
m_worldPos.setValue(world_position[0], world_position[1], world_position[2]);
m_worldOri.setValue(world_orientation[0], world_orientation[1], world_orientation[2], world_orientation[3]);
b3LinkState linkState;
m_robotSim.getLinkState(0, 6, &linkState);
m_worldPos.setValue(linkState.m_worldLinkFramePosition[0], linkState.m_worldLinkFramePosition[1], linkState.m_worldLinkFramePosition[2]);
m_worldOri.setValue(linkState.m_worldLinkFrameOrientation[0], linkState.m_worldLinkFrameOrientation[1], linkState.m_worldLinkFrameOrientation[2], linkState.m_worldLinkFrameOrientation[3]);
b3Vector3DoubleData targetPosDataOut;
m_targetPos.serializeDouble(targetPosDataOut);
b3Vector3DoubleData worldPosDataOut;
@@ -185,8 +168,8 @@ public:
m_worldOri.serializeDouble(worldOriDataOut);
b3RobotSimInverseKinematicArgs ikargs;
b3RobotSimInverseKinematicsResults ikresults;
b3RobotSimulatorInverseKinematicArgs ikargs;
b3RobotSimulatorInverseKinematicsResults ikresults;
ikargs.m_bodyUniqueId = m_kukaIndex;
@@ -247,7 +230,7 @@ public:
//copy the IK result to the desired state of the motor/actuator
for (int i=0;i<numJoints;i++)
{
b3JointMotorArgs t(CONTROL_MODE_POSITION_VELOCITY_PD);
b3RobotSimulatorJointMotorArgs t(CONTROL_MODE_POSITION_VELOCITY_PD);
t.m_targetPosition = ikresults.m_calculatedJointPositions[i];
t.m_maxTorqueValue = 100.0;
t.m_kp= 1.0;
@@ -257,6 +240,7 @@ public:
}
}
}
@@ -279,9 +263,9 @@ public:
}
virtual void physicsDebugDraw()
virtual void physicsDebugDraw(int debugDrawMode)
{
m_robotSim.debugDraw(debugDrawMode);
}
virtual bool mouseMoveCallback(float x,float y)
{

View File

@@ -11,7 +11,7 @@
#include "../SharedMemory/PhysicsClientC_API.h"
#include <string>
#include "b3RobotSimAPI.h"
#include "../RobotSimulator/b3RobotSimulatorClientAPI.h"
#include "../Utils/b3Clock.h"
///quick demo showing the right-handed coordinate system and positive rotations around each axis
@@ -19,7 +19,7 @@ class R2D2GraspExample : public CommonExampleInterface
{
CommonGraphicsApp* m_app;
GUIHelperInterface* m_guiHelper;
b3RobotSimAPI m_robotSim;
b3RobotSimulatorClientAPI m_robotSim;
int m_options;
int m_r2d2Index;
@@ -51,20 +51,22 @@ public:
}
virtual void initPhysics()
{
bool connected = m_robotSim.connect(m_guiHelper);
int mode = eCONNECT_EXISTING_EXAMPLE_BROWSER;
m_robotSim.setGuiHelper(m_guiHelper);
bool connected = m_robotSim.connect(mode);
b3Printf("robotSim connected = %d",connected);
if ((m_options & eROBOTIC_LEARN_GRASP)!=0)
{
{
b3RobotSimLoadFileArgs args("");
args.m_fileName = "r2d2.urdf";
b3RobotSimulatorLoadUrdfFileArgs args;
args.m_startPosition.setValue(0,0,.5);
b3RobotSimLoadFileResults results;
if (m_robotSim.loadFile(args, results) && results.m_uniqueObjectIds.size()==1)
m_r2d2Index = m_robotSim.loadURDF("r2d2.urdf",args);
if (m_r2d2Index>=0)
{
m_r2d2Index = results.m_uniqueObjectIds[0];
int numJoints = m_robotSim.getNumJoints(m_r2d2Index);
b3Printf("numJoints = %d",numJoints);
@@ -78,7 +80,7 @@ public:
int wheelTargetVelocities[4]={-10,-10,-10,-10};
for (int i=0;i<4;i++)
{
b3JointMotorArgs controlArgs(CONTROL_MODE_VELOCITY);
b3RobotSimulatorJointMotorArgs controlArgs(CONTROL_MODE_VELOCITY);
controlArgs.m_targetVelocity = wheelTargetVelocities[i];
controlArgs.m_maxTorqueValue = 1e30;
m_robotSim.setJointMotorControl(m_r2d2Index,wheelJointIndices[i],controlArgs);
@@ -86,84 +88,67 @@ public:
}
}
{
b3RobotSimLoadFileArgs args("");
args.m_fileName = "kiva_shelf/model.sdf";
args.m_forceOverrideFixedBase = true;
args.m_fileType = B3_SDF_FILE;
args.m_startOrientation = b3Quaternion(0,0,0,1);
b3RobotSimLoadFileResults results;
m_robotSim.loadFile(args,results);
b3RobotSimulatorLoadFileResults results;
m_robotSim.loadSDF("kiva_shelf/model.sdf",results);
}
{
b3RobotSimLoadFileArgs args("");
args.m_fileName = "plane.urdf";
args.m_startPosition.setValue(0,0,0);
args.m_forceOverrideFixedBase = true;
b3RobotSimLoadFileResults results;
m_robotSim.loadFile(args,results);
m_robotSim.setGravity(b3MakeVector3(0,0,-10));
m_robotSim.loadURDF("results");
}
m_robotSim.setGravity(b3MakeVector3(0,0,-10));
}
if ((m_options & eROBOTIC_LEARN_COMPLIANT_CONTACT)!=0)
{
b3RobotSimLoadFileArgs args("");
b3RobotSimLoadFileResults results;
b3RobotSimulatorLoadUrdfFileArgs args;
b3RobotSimulatorLoadFileResults results;
{
args.m_fileName = "cube_soft.urdf";
args.m_startPosition.setValue(0,0,2.5);
args.m_startOrientation.setEulerZYX(0,0.2,0);
m_robotSim.loadFile(args,results);
m_r2d2Index = m_robotSim.loadURDF("cube_soft.urdf",args);
}
{
args.m_fileName = "cube_no_friction.urdf";
args.m_startPosition.setValue(0,2,2.5);
args.m_startOrientation.setEulerZYX(0,0.2,0);
m_robotSim.loadFile(args,results);
m_robotSim.loadURDF("cube_no_friction.urdf",args);
}
{
b3RobotSimLoadFileArgs args("");
args.m_fileName = "plane.urdf";
args.m_startPosition.setValue(0,0,0);
args.m_startOrientation.setEulerZYX(0,0.2,0);
args.m_forceOverrideFixedBase = true;
b3RobotSimLoadFileResults results;
m_robotSim.loadFile(args,results);
m_robotSim.setGravity(b3MakeVector3(0,0,-10));
m_robotSim.loadURDF("plane.urdf",args);
}
m_robotSim.setGravity(b3MakeVector3(0,0,-10));
}
if ((m_options & eROBOTIC_LEARN_ROLLING_FRICTION)!=0)
{
b3RobotSimLoadFileArgs args("");
b3RobotSimLoadFileResults results;
b3RobotSimulatorLoadUrdfFileArgs args;
b3RobotSimulatorLoadFileResults results;
{
args.m_fileName = "sphere2_rolling_friction.urdf";
args.m_startPosition.setValue(0,0,2.5);
args.m_startOrientation.setEulerZYX(0,0,0);
args.m_useMultiBody = true;
m_robotSim.loadFile(args,results);
m_robotSim.loadURDF("sphere2_rolling_friction.urdf",args);
}
{
args.m_fileName = "sphere2.urdf";
args.m_startPosition.setValue(0,2,2.5);
args.m_startOrientation.setEulerZYX(0,0,0);
args.m_useMultiBody = true;
m_robotSim.loadFile(args,results);
m_robotSim.loadURDF("sphere2.urdf", args);
}
{
b3RobotSimLoadFileArgs args("");
args.m_fileName = "plane.urdf";
args.m_startPosition.setValue(0,0,0);
args.m_startOrientation.setEulerZYX(0,0.2,0);
args.m_useMultiBody = true;
args.m_forceOverrideFixedBase = true;
b3RobotSimLoadFileResults results;
m_robotSim.loadFile(args,results);
m_robotSim.setGravity(b3MakeVector3(0,0,-10));
m_robotSim.loadURDF("plane.urdf", args);
}
}
m_robotSim.setGravity(b3MakeVector3(0,0,-10));
}
}

File diff suppressed because it is too large Load Diff

View File

@@ -1,174 +0,0 @@
#ifndef B3_ROBOT_SIM_API_H
#define B3_ROBOT_SIM_API_H
///todo: remove those includes from this header
#include "../SharedMemory/PhysicsClientC_API.h"
#include "../SharedMemory/SharedMemoryPublic.h"
#include "Bullet3Common/b3Vector3.h"
#include "Bullet3Common/b3Quaternion.h"
#include "Bullet3Common/b3Transform.h"
#include "Bullet3Common/b3AlignedObjectArray.h"
#include <string>
enum b3RigidSimFileType
{
B3_URDF_FILE=1,
B3_SDF_FILE,
B3_AUTO_DETECT_FILE//todo based on extension
};
struct b3JointStates
{
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 b3RobotSimLoadFileArgs
{
std::string m_fileName;
b3Vector3 m_startPosition;
b3Quaternion m_startOrientation;
bool m_forceOverrideFixedBase;
bool m_useMultiBody;
int m_fileType;
b3RobotSimLoadFileArgs(const std::string& fileName)
:m_fileName(fileName),
m_startPosition(b3MakeVector3(0,0,0)),
m_startOrientation(b3Quaternion(0,0,0,1)),
m_forceOverrideFixedBase(false),
m_useMultiBody(true),
m_fileType(B3_URDF_FILE)
{
}
};
struct b3RobotSimLoadFileResults
{
b3AlignedObjectArray<int> m_uniqueObjectIds;
b3RobotSimLoadFileResults()
{
}
};
struct b3JointMotorArgs
{
int m_controlMode;
double m_targetPosition;
double m_kp;
double m_targetVelocity;
double m_kd;
double m_maxTorqueValue;
b3JointMotorArgs(int controlMode)
:m_controlMode(controlMode),
m_targetPosition(0),
m_kp(0.1),
m_targetVelocity(0),
m_kd(0.9),
m_maxTorqueValue(1000)
{
}
};
enum b3InverseKinematicsFlags
{
B3_HAS_IK_TARGET_ORIENTATION=1,
B3_HAS_NULL_SPACE_VELOCITY=2,
B3_HAS_JOINT_DAMPING=4,
};
struct b3RobotSimInverseKinematicArgs
{
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;
b3RobotSimInverseKinematicArgs()
: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 b3RobotSimInverseKinematicsResults
{
int m_bodyUniqueId;
b3AlignedObjectArray<double> m_calculatedJointPositions;
};
class b3RobotSimAPI
{
struct b3RobotSimAPI_InternalData* m_data;
void processMultiThreadedGraphicsRequests();
b3SharedMemoryStatusHandle submitClientCommandAndWaitStatusMultiThreaded(b3PhysicsClientHandle physClient, b3SharedMemoryCommandHandle commandHandle);
public:
b3RobotSimAPI();
virtual ~b3RobotSimAPI();
bool connect(struct GUIHelperInterface* guiHelper);
void disconnect();
bool loadFile(const struct b3RobotSimLoadFileArgs& args, b3RobotSimLoadFileResults& results);
int getNumJoints(int bodyUniqueId) const;
bool getJointInfo(int bodyUniqueId, int jointIndex, b3JointInfo* jointInfo);
void createJoint(int parentBodyIndex, int parentJointIndex, int childBodyIndex, int childJointIndex, b3JointInfo* jointInfo);
bool getJointStates(int bodyUniqueId, b3JointStates& state);
void setJointMotorControl(int bodyUniqueId, int jointIndex, const struct b3JointMotorArgs& args);
void stepSimulation();
void setGravity(const b3Vector3& gravityAcceleration);
void setNumSimulationSubSteps(int numSubSteps);
void setNumSolverIterations(int numIterations);
bool calculateInverseKinematics(const struct b3RobotSimInverseKinematicArgs& args, struct b3RobotSimInverseKinematicsResults& results);
void renderScene();
void debugDraw(int debugDrawMode);
void getBodyJacobian(int bodyUniqueId, int linkIndex, const double* localPosition, const double* jointPositions, const double* jointVelocities, const double* jointAccelerations, double* linearJacobian, double* angularJacobian);
void getLinkState(int bodyUniqueId, int linkIndex, double* worldPosition, double* worldOrientation);
void loadBunny(double scale, double mass, double collisionMargin);
};
#endif //B3_ROBOT_SIM_API_H

View File

@@ -2320,9 +2320,30 @@ b3SharedMemoryCommandHandle b3InitUpdateVisualShape(b3PhysicsClientHandle physCl
command->m_updateVisualShapeDataArguments.m_shapeIndex = shapeIndex;
command->m_updateVisualShapeDataArguments.m_textureUniqueId = textureUniqueId;
command->m_updateFlags = 0;
if (textureUniqueId>=0)
{
command->m_updateFlags |= CMD_UPDATE_VISUAL_SHAPE_TEXTURE;
}
return (b3SharedMemoryCommandHandle) command;
}
void b3UpdateVisualShapeRGBAColor(b3SharedMemoryCommandHandle commandHandle, double rgbaColor[4])
{
struct SharedMemoryCommand* command = (struct SharedMemoryCommand*) commandHandle;
b3Assert(command);
b3Assert(command->m_type == CMD_UPDATE_VISUAL_SHAPE);
if (command->m_type == CMD_UPDATE_VISUAL_SHAPE)
{
command->m_updateVisualShapeDataArguments.m_rgbaColor[0] = rgbaColor[0];
command->m_updateVisualShapeDataArguments.m_rgbaColor[1] = rgbaColor[1];
command->m_updateVisualShapeDataArguments.m_rgbaColor[2] = rgbaColor[2];
command->m_updateVisualShapeDataArguments.m_rgbaColor[3] = rgbaColor[3];
command->m_updateFlags |= CMD_UPDATE_VISUAL_SHAPE_RGBA_COLOR;
}
}
b3SharedMemoryCommandHandle b3ApplyExternalForceCommandInit(b3PhysicsClientHandle physClient)
{
PhysicsClient* cl = (PhysicsClient* ) physClient;

View File

@@ -198,6 +198,7 @@ void b3GetVisualShapeInformation(b3PhysicsClientHandle physClient, struct b3Visu
b3SharedMemoryCommandHandle b3InitLoadTexture(b3PhysicsClientHandle physClient, const char* filename);
b3SharedMemoryCommandHandle b3InitUpdateVisualShape(b3PhysicsClientHandle physClient, int bodyUniqueId, int jointIndex, int shapeIndex, int textureUniqueId);
void b3UpdateVisualShapeRGBAColor(b3SharedMemoryCommandHandle commandHandle, double rgbaColor[4]);
b3SharedMemoryCommandHandle b3InitPhysicsParamCommand(b3PhysicsClientHandle physClient);
int b3PhysicsParamSetGravity(b3SharedMemoryCommandHandle commandHandle, double gravx,double gravy, double gravz);

View File

@@ -14,7 +14,7 @@ protected:
void processBodyJointInfo(int bodyUniqueId, const struct SharedMemoryStatus& serverCmd);
void resetData();
void removeCachedBody(int bodyUniqueId);
virtual void renderSceneInternal() {};
public:
PhysicsClientSharedMemory();
virtual ~PhysicsClientSharedMemory();

View File

@@ -5585,9 +5585,52 @@ bool PhysicsServerCommandProcessor::processCommand(const struct SharedMemoryComm
SharedMemoryStatus& serverCmd = serverStatusOut;
serverCmd.m_type = CMD_VISUAL_SHAPE_UPDATE_FAILED;
m_data->m_visualConverter.activateShapeTexture(clientCmd.m_updateVisualShapeDataArguments.m_bodyUniqueId, clientCmd.m_updateVisualShapeDataArguments.m_jointIndex, clientCmd.m_updateVisualShapeDataArguments.m_shapeIndex, clientCmd.m_updateVisualShapeDataArguments.m_textureUniqueId);
serverCmd.m_type = CMD_VISUAL_SHAPE_UPDATE_COMPLETED;
if (clientCmd.m_updateFlags & CMD_UPDATE_VISUAL_SHAPE_TEXTURE)
{
if (clientCmd.m_updateVisualShapeDataArguments.m_textureUniqueId>=0)
{
m_data->m_visualConverter.activateShapeTexture(clientCmd.m_updateVisualShapeDataArguments.m_bodyUniqueId, clientCmd.m_updateVisualShapeDataArguments.m_jointIndex, clientCmd.m_updateVisualShapeDataArguments.m_shapeIndex, clientCmd.m_updateVisualShapeDataArguments.m_textureUniqueId);
}
}
if (clientCmd.m_updateFlags & CMD_UPDATE_VISUAL_SHAPE_RGBA_COLOR)
{
int bodyUniqueId = clientCmd.m_updateVisualShapeDataArguments.m_bodyUniqueId;
int linkIndex = clientCmd.m_updateVisualShapeDataArguments.m_jointIndex;
InternalBodyHandle* bodyHandle = m_data->m_bodyHandles.getHandle(bodyUniqueId);
if (bodyHandle)
{
if (bodyHandle->m_multiBody)
{
if (linkIndex==-1)
{
if (bodyHandle->m_multiBody->getBaseCollider())
{
//m_data->m_visualConverter.changeRGBAColor(...)
int graphicsIndex = bodyHandle->m_multiBody->getBaseCollider()->getUserIndex();
m_data->m_guiHelper->changeRGBAColor(graphicsIndex,clientCmd.m_updateVisualShapeDataArguments.m_rgbaColor);
}
} else
{
if (linkIndex<bodyHandle->m_multiBody->getNumLinks())
{
if (bodyHandle->m_multiBody->getLink(linkIndex).m_collider)
{
//m_data->m_visualConverter.changeRGBAColor(...)
int graphicsIndex = bodyHandle->m_multiBody->getLink(linkIndex).m_collider->getUserIndex();
m_data->m_guiHelper->changeRGBAColor(graphicsIndex,clientCmd.m_updateVisualShapeDataArguments.m_rgbaColor);
}
}
}
} else
{
//todo: change color for rigid body
}
}
}
serverCmd.m_type = CMD_VISUAL_SHAPE_UPDATE_COMPLETED;
hasStatus = true;
break;

View File

@@ -180,6 +180,7 @@ enum MultiThreadedGUIHelperCommunicationEnums
eGUIUserDebugRemoveAllItems,
eGUIDumpFramesToVideo,
eGUIHelperRemoveGraphicsInstance,
eGUIHelperChangeGraphicsInstanceRGBAColor,
};
@@ -788,6 +789,20 @@ public:
workerThreadWait();
}
double m_rgbaColor[4];
int m_graphicsInstanceChangeColor;
virtual void changeRGBAColor(int instanceUid, const double rgbaColor[4])
{
m_graphicsInstanceChangeColor = instanceUid;
m_rgbaColor[0] = rgbaColor[0];
m_rgbaColor[1] = rgbaColor[1];
m_rgbaColor[2] = rgbaColor[2];
m_rgbaColor[3] = rgbaColor[3];
m_cs->lock();
m_cs->setSharedParam(1,eGUIHelperChangeGraphicsInstanceRGBAColor);
workerThreadWait();
}
virtual Common2dCanvasInterface* get2dCanvasInterface()
{
return 0;
@@ -1573,8 +1588,13 @@ void PhysicsServerExample::updateGraphics()
m_multiThreadedHelper->mainThreadRelease();
break;
}
case eGUIHelperChangeGraphicsInstanceRGBAColor:
{
m_multiThreadedHelper->m_childGuiHelper->changeRGBAColor(m_multiThreadedHelper->m_graphicsInstanceChangeColor,m_multiThreadedHelper->m_rgbaColor);
m_multiThreadedHelper->mainThreadRelease();
break;
}
case eGUIHelperCopyCameraImageData:
{

View File

@@ -245,12 +245,19 @@ struct RequestVisualShapeDataArgs
int m_startingVisualShapeIndex;
};
enum EnumUpdateVisualShapeData
{
CMD_UPDATE_VISUAL_SHAPE_TEXTURE=1,
CMD_UPDATE_VISUAL_SHAPE_RGBA_COLOR=2,
};
struct UpdateVisualShapeDataArgs
{
int m_bodyUniqueId;
int m_jointIndex;
int m_shapeIndex;
int m_textureUniqueId;
double m_rgbaColor[4];
};
struct LoadTextureArgs

View File

@@ -4,6 +4,9 @@
#include "PhysicsClientSharedMemory.h"
#include"../ExampleBrowser/InProcessExampleBrowser.h"
#include "PhysicsServerExample.h"
#include "../CommonInterfaces/CommonExampleInterface.h"
#include "InProcessMemory.h"
#include "Bullet3Common/b3Logging.h"
class InProcessPhysicsClientSharedMemoryMainThread : public PhysicsClientSharedMemory
@@ -124,3 +127,109 @@ b3PhysicsClientHandle b3CreateInProcessPhysicsServerAndConnect(int argc, char* a
return (b3PhysicsClientHandle ) cl;
}
class InProcessPhysicsClientExistingExampleBrowser : public PhysicsClientSharedMemory
{
CommonExampleInterface* m_physicsServerExample;
SharedMemoryInterface* m_sharedMem;
b3Clock m_clock;
unsigned long long int m_prevTime;
public:
InProcessPhysicsClientExistingExampleBrowser (struct GUIHelperInterface* guiHelper)
{
m_sharedMem = new InProcessMemory;
CommonExampleOptions options(guiHelper);
options.m_sharedMem = m_sharedMem;
m_physicsServerExample = PhysicsServerCreateFunc(options);
m_physicsServerExample ->initPhysics();
m_physicsServerExample ->resetCamera();
setSharedMemoryInterface(m_sharedMem);
m_clock.reset();
m_prevTime = m_clock.getTimeMicroseconds();
}
virtual ~InProcessPhysicsClientExistingExampleBrowser()
{
m_physicsServerExample->exitPhysics();
//s_instancingRenderer->removeAllInstances();
delete m_physicsServerExample;
delete m_sharedMem;
}
// return non-null if there is a status, nullptr otherwise
virtual const struct SharedMemoryStatus* processServerStatus()
{
//m_physicsServerExample->updateGraphics();
unsigned long long int curTime = m_clock.getTimeMicroseconds();
unsigned long long int dtMicro = curTime - m_prevTime;
m_prevTime = curTime;
double dt = double(dtMicro)/1000000.;
m_physicsServerExample->stepSimulation(dt);
{
b3Clock::usleep(0);
}
const SharedMemoryStatus* stat = 0;
{
stat = PhysicsClientSharedMemory::processServerStatus();
}
return stat;
}
virtual void renderScene()
{
m_physicsServerExample->renderScene();
}
virtual void debugDraw(int debugDrawMode)
{
m_physicsServerExample->physicsDebugDraw(debugDrawMode);
}
virtual bool mouseMoveCallback(float x, float y)
{
return m_physicsServerExample->mouseMoveCallback(x,y);
}
virtual bool mouseButtonCallback(int button, int state, float x, float y)
{
return m_physicsServerExample->mouseButtonCallback(button,state,x,y);
}
};
void b3InProcessDebugDrawInternal(b3PhysicsClientHandle clientHandle, int debugDrawMode)
{
InProcessPhysicsClientExistingExampleBrowser* cl = (InProcessPhysicsClientExistingExampleBrowser*) clientHandle;
cl->debugDraw(debugDrawMode);
}
void b3InProcessRenderSceneInternal(b3PhysicsClientHandle clientHandle)
{
InProcessPhysicsClientExistingExampleBrowser* cl = (InProcessPhysicsClientExistingExampleBrowser*) clientHandle;
cl->renderScene();
}
int b3InProcessMouseMoveCallback(b3PhysicsClientHandle clientHandle,float x,float y)
{
InProcessPhysicsClientExistingExampleBrowser* cl = (InProcessPhysicsClientExistingExampleBrowser*) clientHandle;
return cl->mouseMoveCallback(x,y);
}
int b3InProcessMouseButtonCallback(b3PhysicsClientHandle clientHandle, int button, int state, float x, float y)
{
InProcessPhysicsClientExistingExampleBrowser* cl = (InProcessPhysicsClientExistingExampleBrowser*) clientHandle;
return cl->mouseButtonCallback(button,state, x,y);
}
b3PhysicsClientHandle b3CreateInProcessPhysicsServerFromExistingExampleBrowserAndConnect(struct GUIHelperInterface* guiHelper)
{
InProcessPhysicsClientExistingExampleBrowser* cl = new InProcessPhysicsClientExistingExampleBrowser(guiHelper);
//InProcessPhysicsClientFromGuiHelper* cl = new InProcessPhysicsClientFromGuiHelper(guiHelper);
cl->connect();
return (b3PhysicsClientHandle ) cl;
}

View File

@@ -14,9 +14,14 @@ b3PhysicsClientHandle b3CreateInProcessPhysicsServerAndConnect(int argc, char* a
b3PhysicsClientHandle b3CreateInProcessPhysicsServerAndConnectMainThread(int argc, char* argv[]);
b3PhysicsClientHandle b3CreateInProcessPhysicsServerFromExistingExampleBrowserAndConnect(struct GUIHelperInterface* guiHelper);
///ignore the following APIs, they are for internal use for example browser
void b3InProcessRenderSceneInternal(b3PhysicsClientHandle clientHandle);
void b3InProcessDebugDrawInternal(b3PhysicsClientHandle clientHandle, int debugDrawMode);
int b3InProcessMouseMoveCallback(b3PhysicsClientHandle clientHandle,float x,float y);
int b3InProcessMouseButtonCallback(b3PhysicsClientHandle clientHandle, int button, int state, float x, float y);
#ifdef __cplusplus
}
#endif

View File

@@ -503,6 +503,7 @@ enum eCONNECT_METHOD {
eCONNECT_SHARED_MEMORY = 3,
eCONNECT_UDP = 4,
eCONNECT_TCP = 5,
eCONNECT_EXISTING_EXAMPLE_BROWSER=6,
};
enum eURDF_Flags

View File

@@ -487,7 +487,10 @@ void TinyRenderer::renderObject(TinyRenderObjectData& renderData)
Model* model = renderData.m_model;
if (0==model)
return;
//discard invisible objects (zero alpha)
if (model->getColorRGBA()[3]==0)
return;
renderData.m_viewportMatrix = viewport(0,0,width, height);
b3AlignedObjectArray<float>& zbuffer = renderData.m_depthBuffer;
@@ -506,7 +509,8 @@ void TinyRenderer::renderObject(TinyRenderObjectData& renderData)
btVector3 P(viewMatrixInv[0][3], viewMatrixInv[1][3], viewMatrixInv[2][3]);
Shader shader(model, light_dir_local, light_color, modelViewMatrix, lightModelViewMatrix, renderData.m_projectionMatrix,renderData.m_modelMatrix, renderData.m_viewportMatrix, localScaling, model->getColorRGBA(), width, height, shadowBufferPtr, renderData.m_lightAmbientCoeff, renderData.m_lightDiffuseCoeff, renderData.m_lightSpecularCoeff);
for (int i=0; i<model->nfaces(); i++)
{
B3_PROFILE("face");

View File

@@ -198,11 +198,13 @@ void b3Clock::usleep(int microSeconds)
Sleep(millis);
}
#else
::usleep(microSeconds);
//struct timeval tv;
//tv.tv_sec = microSeconds/1000000L;
//tv.tv_usec = microSeconds%1000000L;
//return select(0, 0, 0, 0, &tv);
if (microSeconds>0)
{
::usleep(microSeconds);
//struct timeval tv;
//tv.tv_sec = microSeconds/1000000L;
//tv.tv_usec = microSeconds%1000000L;
//return select(0, 0, 0, 0, &tv);
}
#endif
}

View File

@@ -4027,7 +4027,7 @@ static PyObject* pybullet_getVisualShapeData(PyObject* self, PyObject* args, PyO
return Py_None;
}
static PyObject* pybullet_resetVisualShapeData(PyObject* self, PyObject* args, PyObject* keywds)
static PyObject* pybullet_changeVisualShape(PyObject* self, PyObject* args, PyObject* keywds)
{
int objectUniqueId = -1;
int jointIndex = -1;
@@ -4037,9 +4037,11 @@ static PyObject* pybullet_resetVisualShapeData(PyObject* self, PyObject* args, P
b3SharedMemoryStatusHandle statusHandle;
int statusType;
int physicsClientId = 0;
PyObject* rgbaColorObj = 0;
b3PhysicsClientHandle sm = 0;
static char* kwlist[] = {"objectUniqueId", "jointIndex", "shapeIndex", "textureUniqueId", "physicsClientId", NULL};
if (!PyArg_ParseTupleAndKeywords(args, keywds, "iiii|i", kwlist, &objectUniqueId, &jointIndex, &shapeIndex, &textureUniqueId, &physicsClientId))
static char* kwlist[] = {"objectUniqueId", "linkIndex", "shapeIndex", "textureUniqueId", "rgbaColor", "physicsClientId", NULL};
if (!PyArg_ParseTupleAndKeywords(args, keywds, "ii|iiOi", kwlist, &objectUniqueId, &jointIndex, &shapeIndex, &textureUniqueId, &rgbaColorObj, &physicsClientId))
{
return NULL;
}
@@ -4052,6 +4054,14 @@ static PyObject* pybullet_resetVisualShapeData(PyObject* self, PyObject* args, P
{
commandHandle = b3InitUpdateVisualShape(sm, objectUniqueId, jointIndex, shapeIndex, textureUniqueId);
if (rgbaColorObj)
{
double rgbaColor[4] = {1,1,1,1};
pybullet_internalSetVector4d(rgbaColorObj, rgbaColor);
b3UpdateVisualShapeRGBAColor(commandHandle,rgbaColor);
}
statusHandle = b3SubmitClientCommandAndWaitStatus(sm, commandHandle);
statusType = b3GetStatusType(statusHandle);
if (statusType == CMD_VISUAL_SHAPE_UPDATE_COMPLETED)
@@ -5913,7 +5923,7 @@ static PyMethodDef SpamMethods[] = {
"Reset the state (position, velocity etc) for a joint on a body "
"instantaneously, not through physics simulation."},
{"changeDynamicsInfo", (PyCFunction)pybullet_changeDynamicsInfo, METH_VARARGS | METH_KEYWORDS,
{"changeDynamics", (PyCFunction)pybullet_changeDynamicsInfo, METH_VARARGS | METH_KEYWORDS,
"change dynamics information such as mass, lateral friction coefficient."},
{"getDynamicsInfo", (PyCFunction)pybullet_getDynamicsInfo, METH_VARARGS | METH_KEYWORDS,
@@ -6019,8 +6029,11 @@ static PyMethodDef SpamMethods[] = {
{"getVisualShapeData", (PyCFunction)pybullet_getVisualShapeData, METH_VARARGS | METH_KEYWORDS,
"Return the visual shape information for one object."},
{"resetVisualShapeData", (PyCFunction)pybullet_resetVisualShapeData, METH_VARARGS | METH_KEYWORDS,
"Reset part of the visual shape information for one object."},
{"changeVisualShape", (PyCFunction)pybullet_changeVisualShape, METH_VARARGS | METH_KEYWORDS,
"Change part of the visual shape information for one object."},
{"resetVisualShapeData", (PyCFunction)pybullet_changeVisualShape, METH_VARARGS | METH_KEYWORDS,
"Obsolete method, kept for backward compatibility, use changeVisualShapeData instead."},
{"loadTexture", (PyCFunction)pybullet_loadTexture, METH_VARARGS | METH_KEYWORDS,
"Load texture file."},

View File

@@ -204,6 +204,8 @@ project ("Test_PhysicsServerLoopBack")
"../../examples/Utils/RobotLoggingUtil.h",
"../../examples/Utils/b3Clock.cpp",
"../../examples/Utils/b3Clock.h",
"../../examples/Utils/ChromeTraceUtil.cpp",
"../../examples/Utils/ChromeTraceUtil.h",
"../../examples/ThirdPartyLibs/tinyxml/tinystr.cpp",
"../../examples/ThirdPartyLibs/tinyxml/tinyxml.cpp",
"../../examples/ThirdPartyLibs/tinyxml/tinyxmlerror.cpp",