summaryrefslogtreecommitdiff
diff options
context:
space:
mode:
authorChuyuan Fu <fuchuyuan.kelly@gmail.com>2019-05-02 14:09:26 -0700
committerChuyuan Fu <fuchuyuan.kelly@gmail.com>2019-05-02 14:15:18 -0700
commitee10d47b177631579775eadbeb2a313a81858bf4 (patch)
treec7dbb122e8cfc7eb7eb09040f1652751158cd87b
parent3fb0a7c19b419182973c4d75d47d04018fb90a97 (diff)
downloadbullet3-ee10d47b177631579775eadbeb2a313a81858bf4.tar.gz
fix space
fix space
-rw-r--r--examples/RoboticsLearning/GripperGraspExample.cpp8
-rw-r--r--examples/SharedMemory/PhysicsClientC_API.h5
-rw-r--r--examples/SharedMemory/PhysicsServerCommandProcessor.cpp4
-rw-r--r--examples/SharedMemory/b3RobotSimulatorClientAPI_NoDirect.cpp2
-rw-r--r--examples/SharedMemory/b3RobotSimulatorClientAPI_NoDirect.h26
5 files changed, 20 insertions, 25 deletions
diff --git a/examples/RoboticsLearning/GripperGraspExample.cpp b/examples/RoboticsLearning/GripperGraspExample.cpp
index 6d9e3122c..8f5ec1a8e 100644
--- a/examples/RoboticsLearning/GripperGraspExample.cpp
+++ b/examples/RoboticsLearning/GripperGraspExample.cpp
@@ -326,9 +326,9 @@ public:
m_robotSim.loadURDF("plane.urdf", args);
}
m_robotSim.setGravity(btVector3(0, 0, -10));
- b3RobotSimulatorLoadSoftBodyArgs args(0.1, 1, 0.02);
- args.m_startPosition.setValue(0, 0, 5);
- args.m_startOrientation.setValue(1, 0, 0, 1);
+ b3RobotSimulatorLoadSoftBodyArgs args(0.1, 1, 0.02);
+ args.m_startPosition.setValue(0, 0, 5);
+ args.m_startOrientation.setValue(1, 0, 0, 1);
m_robotSim.loadSoftBody("bunny.obj", args);
b3JointInfo revoluteJoint1;
@@ -405,7 +405,7 @@ public:
m_robotSim.loadURDF("plane.urdf", args);
}
m_robotSim.setGravity(btVector3(0, 0, -10));
- b3RobotSimulatorLoadSoftBodyArgs args(0.3, 10, 0.1);
+ b3RobotSimulatorLoadSoftBodyArgs args(0.3, 10, 0.1);
m_robotSim.loadSoftBody("bunny.obj", args);
}
}
diff --git a/examples/SharedMemory/PhysicsClientC_API.h b/examples/SharedMemory/PhysicsClientC_API.h
index 85319aeb4..9ba2dc37c 100644
--- a/examples/SharedMemory/PhysicsClientC_API.h
+++ b/examples/SharedMemory/PhysicsClientC_API.h
@@ -614,9 +614,8 @@ extern "C"
B3_SHARED_API int b3LoadSoftBodySetScale(b3SharedMemoryCommandHandle commandHandle, double scale);
B3_SHARED_API int b3LoadSoftBodySetMass(b3SharedMemoryCommandHandle commandHandle, double mass);
B3_SHARED_API int b3LoadSoftBodySetCollisionMargin(b3SharedMemoryCommandHandle commandHandle, double collisionMargin);
- B3_SHARED_API int b3LoadSoftBodySetStartPosition(b3SharedMemoryCommandHandle commandHandle, double startPosX, double startPosY, double startPosZ);
- B3_SHARED_API int b3LoadSoftBodySetStartOrientation(b3SharedMemoryCommandHandle commandHandle, double startOrnX, double startOrnY, double startOrnZ, double startOrnW);
-
+ B3_SHARED_API int b3LoadSoftBodySetStartPosition(b3SharedMemoryCommandHandle commandHandle, double startPosX, double startPosY, double startPosZ);
+ B3_SHARED_API int b3LoadSoftBodySetStartOrientation(b3SharedMemoryCommandHandle commandHandle, double startOrnX, double startOrnY, double startOrnZ, double startOrnW);
B3_SHARED_API b3SharedMemoryCommandHandle b3RequestVREventsCommandInit(b3PhysicsClientHandle physClient);
B3_SHARED_API void b3VREventsSetDeviceTypeFilter(b3SharedMemoryCommandHandle commandHandle, int deviceTypeFilter);
diff --git a/examples/SharedMemory/PhysicsServerCommandProcessor.cpp b/examples/SharedMemory/PhysicsServerCommandProcessor.cpp
index 7682e7786..9164c5bd4 100644
--- a/examples/SharedMemory/PhysicsServerCommandProcessor.cpp
+++ b/examples/SharedMemory/PhysicsServerCommandProcessor.cpp
@@ -7376,8 +7376,8 @@ bool PhysicsServerCommandProcessor::processLoadSoftBodyCommand(const struct Shar
psb->generateBendingConstraints(2, pm);
psb->m_cfg.piterations = 20;
psb->m_cfg.kDF = 0.5;
- //turn on softbody vs softbody collision
- psb->m_cfg.collisions |= btSoftBody::fCollision::VF_SS;
+ //turn on softbody vs softbody collision
+ psb->m_cfg.collisions |= btSoftBody::fCollision::VF_SS;
psb->randomizeConstraints();
psb->rotate(initialOrn);
psb->translate(initialPos);
diff --git a/examples/SharedMemory/b3RobotSimulatorClientAPI_NoDirect.cpp b/examples/SharedMemory/b3RobotSimulatorClientAPI_NoDirect.cpp
index 4b4f50c8a..27bc23163 100644
--- a/examples/SharedMemory/b3RobotSimulatorClientAPI_NoDirect.cpp
+++ b/examples/SharedMemory/b3RobotSimulatorClientAPI_NoDirect.cpp
@@ -1143,7 +1143,7 @@ void b3RobotSimulatorClientAPI_NoDirect::loadSoftBody(const std::string& fileNam
}
b3SharedMemoryCommandHandle command = b3LoadSoftBodyCommandInit(m_data->m_physicsClientHandle, fileName.c_str());
- b3LoadSoftBodySetStartPosition(command, args.m_startPosition[0], args.m_startPosition[1], args.m_startPosition[2]);
+ b3LoadSoftBodySetStartPosition(command, args.m_startPosition[0], args.m_startPosition[1], args.m_startPosition[2]);
b3LoadSoftBodySetStartOrientation(command, args.m_startOrientation[0], args.m_startOrientation[1], args.m_startOrientation[2], args.m_startOrientation[3]);
b3LoadSoftBodySetScale(command, args.m_scale);
b3LoadSoftBodySetMass(command, args.m_mass);
diff --git a/examples/SharedMemory/b3RobotSimulatorClientAPI_NoDirect.h b/examples/SharedMemory/b3RobotSimulatorClientAPI_NoDirect.h
index 50e7478bf..d8fd179c0 100644
--- a/examples/SharedMemory/b3RobotSimulatorClientAPI_NoDirect.h
+++ b/examples/SharedMemory/b3RobotSimulatorClientAPI_NoDirect.h
@@ -56,43 +56,39 @@ struct b3RobotSimulatorLoadSoftBodyArgs
{
btVector3 m_startPosition;
btQuaternion m_startOrientation;
- double m_scale;
- double m_mass;
- double m_collisionMargin;
+ double m_scale;
+ double m_mass;
+ double m_collisionMargin;
- b3RobotSimulatorLoadSoftBodyArgs(const btVector3 &startPos, const btQuaternion &startOrn, const double& scale, const double& mass, const double& collisionMargin )
+ b3RobotSimulatorLoadSoftBodyArgs(const btVector3 &startPos, const btQuaternion &startOrn, const double &scale, const double &mass, const double &collisionMargin)
: m_startPosition(startPos),
m_startOrientation(startOrn),
m_scale(scale),
m_mass(mass),
- m_collisionMargin(collisionMargin)
+ m_collisionMargin(collisionMargin)
{
}
-
- b3RobotSimulatorLoadSoftBodyArgs(const btVector3 &startPos, const btQuaternion &startOrn)
+ b3RobotSimulatorLoadSoftBodyArgs(const btVector3 &startPos, const btQuaternion &startOrn)
{
- b3RobotSimulatorLoadSoftBodyArgs(startPos, startOrn, 1.0, 1.0, 0.02);
+ b3RobotSimulatorLoadSoftBodyArgs(startPos, startOrn, 1.0, 1.0, 0.02);
}
-
b3RobotSimulatorLoadSoftBodyArgs()
{
- b3RobotSimulatorLoadSoftBodyArgs(btVector3(0, 0, 0), btQuaternion(0, 0, 0, 1));
+ b3RobotSimulatorLoadSoftBodyArgs(btVector3(0, 0, 0), btQuaternion(0, 0, 0, 1));
}
-
- b3RobotSimulatorLoadSoftBodyArgs(double scale, double mass, double collisionMargin)
+ b3RobotSimulatorLoadSoftBodyArgs(double scale, double mass, double collisionMargin)
: m_startPosition(btVector3(0, 0, 0)),
m_startOrientation(btQuaternion(0, 0, 0, 1)),
m_scale(scale),
m_mass(mass),
- m_collisionMargin(collisionMargin)
+ m_collisionMargin(collisionMargin)
{
}
};
-
struct b3RobotSimulatorLoadFileResults
{
btAlignedObjectArray<int> m_uniqueObjectIds;
@@ -688,7 +684,7 @@ public:
int getConstraintUniqueId(int serialIndex);
- void loadSoftBody(const std::string &fileName, const struct b3RobotSimulatorLoadSoftBodyArgs& args);
+ void loadSoftBody(const std::string &fileName, const struct b3RobotSimulatorLoadSoftBodyArgs &args);
virtual void setGuiHelper(struct GUIHelperInterface *guiHelper);
virtual struct GUIHelperInterface *getGuiHelper();