Code-style consistency improvement:
Apply clang-format-all.sh using the _clang-format file through all the cpp/.h files. make sure not to apply it to certain serialization structures, since some parser expects the * as part of the name, instead of type. This commit contains no other changes aside from adding and applying clang-format-all.sh
This commit is contained in:
@@ -21,21 +21,21 @@ struct b3RobotSimulatorLoadUrdfFileArgs
|
||||
bool m_useMultiBody;
|
||||
int m_flags;
|
||||
|
||||
b3RobotSimulatorLoadUrdfFileArgs(const btVector3& startPos, const btQuaternion& startOrn)
|
||||
b3RobotSimulatorLoadUrdfFileArgs(const btVector3 &startPos, const btQuaternion &startOrn)
|
||||
: m_startPosition(startPos),
|
||||
m_startOrientation(startOrn),
|
||||
m_forceOverrideFixedBase(false),
|
||||
m_useMultiBody(true),
|
||||
m_flags(0)
|
||||
m_startOrientation(startOrn),
|
||||
m_forceOverrideFixedBase(false),
|
||||
m_useMultiBody(true),
|
||||
m_flags(0)
|
||||
{
|
||||
}
|
||||
|
||||
b3RobotSimulatorLoadUrdfFileArgs()
|
||||
: m_startPosition(btVector3(0, 0, 0)),
|
||||
m_startOrientation(btQuaternion(0, 0, 0, 1)),
|
||||
m_forceOverrideFixedBase(false),
|
||||
m_useMultiBody(true),
|
||||
m_flags(0)
|
||||
m_startOrientation(btQuaternion(0, 0, 0, 1)),
|
||||
m_forceOverrideFixedBase(false),
|
||||
m_useMultiBody(true),
|
||||
m_flags(0)
|
||||
{
|
||||
}
|
||||
};
|
||||
@@ -47,7 +47,7 @@ struct b3RobotSimulatorLoadSdfFileArgs
|
||||
|
||||
b3RobotSimulatorLoadSdfFileArgs()
|
||||
: m_forceOverrideFixedBase(false),
|
||||
m_useMultiBody(true)
|
||||
m_useMultiBody(true)
|
||||
{
|
||||
}
|
||||
};
|
||||
@@ -62,26 +62,26 @@ struct b3RobotSimulatorLoadFileResults
|
||||
|
||||
struct b3RobotSimulatorChangeVisualShapeArgs
|
||||
{
|
||||
int m_objectUniqueId;
|
||||
int m_linkIndex;
|
||||
int m_shapeIndex;
|
||||
int m_textureUniqueId;
|
||||
btVector4 m_rgbaColor;
|
||||
bool m_hasRgbaColor;
|
||||
btVector3 m_specularColor;
|
||||
bool m_hasSpecularColor;
|
||||
|
||||
b3RobotSimulatorChangeVisualShapeArgs()
|
||||
:m_objectUniqueId(-1),
|
||||
m_linkIndex(-1),
|
||||
m_shapeIndex(-1),
|
||||
m_textureUniqueId(-1),
|
||||
m_rgbaColor(0,0,0,1),
|
||||
m_hasRgbaColor(false),
|
||||
m_specularColor(1,1,1),
|
||||
m_hasSpecularColor(false)
|
||||
{
|
||||
}
|
||||
int m_objectUniqueId;
|
||||
int m_linkIndex;
|
||||
int m_shapeIndex;
|
||||
int m_textureUniqueId;
|
||||
btVector4 m_rgbaColor;
|
||||
bool m_hasRgbaColor;
|
||||
btVector3 m_specularColor;
|
||||
bool m_hasSpecularColor;
|
||||
|
||||
b3RobotSimulatorChangeVisualShapeArgs()
|
||||
: m_objectUniqueId(-1),
|
||||
m_linkIndex(-1),
|
||||
m_shapeIndex(-1),
|
||||
m_textureUniqueId(-1),
|
||||
m_rgbaColor(0, 0, 0, 1),
|
||||
m_hasRgbaColor(false),
|
||||
m_specularColor(1, 1, 1),
|
||||
m_hasSpecularColor(false)
|
||||
{
|
||||
}
|
||||
};
|
||||
|
||||
struct b3RobotSimulatorJointMotorArgs
|
||||
@@ -98,11 +98,11 @@ struct b3RobotSimulatorJointMotorArgs
|
||||
|
||||
b3RobotSimulatorJointMotorArgs(int controlMode)
|
||||
: m_controlMode(controlMode),
|
||||
m_targetPosition(0),
|
||||
m_kp(0.1),
|
||||
m_targetVelocity(0),
|
||||
m_kd(0.9),
|
||||
m_maxTorqueValue(1000)
|
||||
m_targetPosition(0),
|
||||
m_kp(0.1),
|
||||
m_targetVelocity(0),
|
||||
m_kd(0.9),
|
||||
m_maxTorqueValue(1000)
|
||||
{
|
||||
}
|
||||
};
|
||||
@@ -112,7 +112,7 @@ enum b3RobotSimulatorInverseKinematicsFlags
|
||||
B3_HAS_IK_TARGET_ORIENTATION = 1,
|
||||
B3_HAS_NULL_SPACE_VELOCITY = 2,
|
||||
B3_HAS_JOINT_DAMPING = 4,
|
||||
B3_HAS_CURRENT_POSITIONS = 8,
|
||||
B3_HAS_CURRENT_POSITIONS = 8,
|
||||
};
|
||||
|
||||
struct b3RobotSimulatorInverseKinematicArgs
|
||||
@@ -128,12 +128,12 @@ struct b3RobotSimulatorInverseKinematicArgs
|
||||
btAlignedObjectArray<double> m_jointRanges;
|
||||
btAlignedObjectArray<double> m_restPoses;
|
||||
btAlignedObjectArray<double> m_jointDamping;
|
||||
btAlignedObjectArray<double> m_currentJointPositions;
|
||||
btAlignedObjectArray<double> m_currentJointPositions;
|
||||
|
||||
b3RobotSimulatorInverseKinematicArgs()
|
||||
: m_bodyUniqueId(-1),
|
||||
m_endEffectorLinkIndex(-1),
|
||||
m_flags(0)
|
||||
m_endEffectorLinkIndex(-1),
|
||||
m_flags(0)
|
||||
{
|
||||
m_endEffectorTargetPosition[0] = 0;
|
||||
m_endEffectorTargetPosition[1] = 0;
|
||||
@@ -163,7 +163,6 @@ struct b3JointStates2
|
||||
btAlignedObjectArray<double> m_jointReactionForces;
|
||||
};
|
||||
|
||||
|
||||
struct b3RobotSimulatorJointMotorArrayArgs
|
||||
{
|
||||
int m_controlMode;
|
||||
@@ -209,40 +208,35 @@ struct b3RobotSimulatorGetCameraImageArgs
|
||||
|
||||
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)
|
||||
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 : b3PhysicsSimulationParameters
|
||||
{
|
||||
|
||||
b3RobotSimulatorSetPhysicsEngineParameters()
|
||||
{
|
||||
|
||||
m_deltaTime=-1;
|
||||
m_deltaTime = -1;
|
||||
m_gravityAcceleration[0] = 0;
|
||||
m_gravityAcceleration[1] = 0;
|
||||
m_gravityAcceleration[2] = 0;
|
||||
|
||||
m_numSimulationSubSteps=-1;
|
||||
m_numSolverIterations=-1;
|
||||
|
||||
m_numSimulationSubSteps = -1;
|
||||
m_numSolverIterations = -1;
|
||||
m_useRealTimeSimulation = -1;
|
||||
m_useSplitImpulse = -1;
|
||||
m_splitImpulsePenetrationThreshold =-1;
|
||||
m_splitImpulsePenetrationThreshold = -1;
|
||||
m_contactBreakingThreshold = -1;
|
||||
m_internalSimFlags = -1;
|
||||
m_defaultContactERP = -1;
|
||||
@@ -259,18 +253,17 @@ struct b3RobotSimulatorSetPhysicsEngineParameters : b3PhysicsSimulationParameter
|
||||
m_jointFeedbackMode = -1;
|
||||
m_solverResidualThreshold = -1;
|
||||
m_contactSlop = -1;
|
||||
|
||||
m_collisionFilterMode=-1;
|
||||
m_contactBreakingThreshold=-1;
|
||||
|
||||
m_enableFileCaching=-1;
|
||||
m_restitutionVelocityThreshold=-1;
|
||||
|
||||
m_frictionERP=-1;
|
||||
m_solverResidualThreshold=-1;
|
||||
|
||||
m_collisionFilterMode = -1;
|
||||
m_contactBreakingThreshold = -1;
|
||||
|
||||
m_enableFileCaching = -1;
|
||||
m_restitutionVelocityThreshold = -1;
|
||||
|
||||
m_frictionERP = -1;
|
||||
m_solverResidualThreshold = -1;
|
||||
m_constraintSolverType = -1;
|
||||
m_minimumSolverIslandSize = -1;
|
||||
|
||||
}
|
||||
};
|
||||
|
||||
@@ -290,17 +283,18 @@ struct b3RobotSimulatorChangeDynamicsArgs
|
||||
|
||||
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),
|
||||
m_activationState(-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),
|
||||
m_activationState(-1)
|
||||
{
|
||||
}
|
||||
};
|
||||
|
||||
struct b3RobotSimulatorAddUserDebugLineArgs
|
||||
@@ -312,11 +306,10 @@ struct b3RobotSimulatorAddUserDebugLineArgs
|
||||
int m_parentLinkIndex;
|
||||
|
||||
b3RobotSimulatorAddUserDebugLineArgs()
|
||||
:
|
||||
m_lineWidth(1),
|
||||
m_lifeTime(0),
|
||||
m_parentObjectUniqueId(-1),
|
||||
m_parentLinkIndex(-1)
|
||||
: m_lineWidth(1),
|
||||
m_lifeTime(0),
|
||||
m_parentObjectUniqueId(-1),
|
||||
m_parentLinkIndex(-1)
|
||||
{
|
||||
m_colorRGB[0] = 1;
|
||||
m_colorRGB[1] = 1;
|
||||
@@ -324,7 +317,8 @@ struct b3RobotSimulatorAddUserDebugLineArgs
|
||||
}
|
||||
};
|
||||
|
||||
enum b3AddUserDebugTextFlags {
|
||||
enum b3AddUserDebugTextFlags
|
||||
{
|
||||
DEBUG_TEXT_HAS_ORIENTATION = 1
|
||||
};
|
||||
|
||||
@@ -340,10 +334,10 @@ struct b3RobotSimulatorAddUserDebugTextArgs
|
||||
|
||||
b3RobotSimulatorAddUserDebugTextArgs()
|
||||
: m_size(1),
|
||||
m_lifeTime(0),
|
||||
m_parentObjectUniqueId(-1),
|
||||
m_parentLinkIndex(-1),
|
||||
m_flags(0)
|
||||
m_lifeTime(0),
|
||||
m_parentObjectUniqueId(-1),
|
||||
m_parentLinkIndex(-1),
|
||||
m_flags(0)
|
||||
{
|
||||
m_colorRGB[0] = 1;
|
||||
m_colorRGB[1] = 1;
|
||||
@@ -353,7 +347,6 @@ struct b3RobotSimulatorAddUserDebugTextArgs
|
||||
m_textOrientation[1] = 0;
|
||||
m_textOrientation[2] = 0;
|
||||
m_textOrientation[3] = 1;
|
||||
|
||||
}
|
||||
};
|
||||
|
||||
@@ -366,10 +359,11 @@ struct b3RobotSimulatorGetContactPointsArgs
|
||||
|
||||
b3RobotSimulatorGetContactPointsArgs()
|
||||
: m_bodyUniqueIdA(-1),
|
||||
m_bodyUniqueIdB(-1),
|
||||
m_linkIndexA(-2),
|
||||
m_linkIndexB(-2)
|
||||
{}
|
||||
m_bodyUniqueIdB(-1),
|
||||
m_linkIndexA(-2),
|
||||
m_linkIndexB(-2)
|
||||
{
|
||||
}
|
||||
};
|
||||
|
||||
struct b3RobotSimulatorCreateCollisionShapeArgs
|
||||
@@ -378,16 +372,16 @@ struct b3RobotSimulatorCreateCollisionShapeArgs
|
||||
double m_radius;
|
||||
btVector3 m_halfExtents;
|
||||
double m_height;
|
||||
char* m_fileName;
|
||||
char *m_fileName;
|
||||
btVector3 m_meshScale;
|
||||
btVector3 m_planeNormal;
|
||||
int m_flags;
|
||||
b3RobotSimulatorCreateCollisionShapeArgs()
|
||||
: m_shapeType(-1),
|
||||
m_radius(0.5),
|
||||
m_height(1),
|
||||
m_fileName(NULL),
|
||||
m_flags(0)
|
||||
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;
|
||||
@@ -401,7 +395,6 @@ struct b3RobotSimulatorCreateCollisionShapeArgs
|
||||
m_planeNormal.m_floats[1] = 0;
|
||||
m_planeNormal.m_floats[2] = 1;
|
||||
}
|
||||
|
||||
};
|
||||
|
||||
struct b3RobotSimulatorCreateMultiBodyArgs
|
||||
@@ -429,28 +422,15 @@ struct b3RobotSimulatorCreateMultiBodyArgs
|
||||
int m_useMaximalCoordinates;
|
||||
|
||||
b3RobotSimulatorCreateMultiBodyArgs()
|
||||
: m_baseMass(0), m_baseCollisionShapeIndex(-1), m_baseVisualShapeIndex(-1),
|
||||
m_numLinks(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_useMaximalCoordinates(0)
|
||||
: m_baseMass(0), m_baseCollisionShapeIndex(-1), m_baseVisualShapeIndex(-1), m_numLinks(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_useMaximalCoordinates(0)
|
||||
{
|
||||
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);
|
||||
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);
|
||||
}
|
||||
};
|
||||
|
||||
|
||||
struct b3RobotJointInfo : public b3JointInfo
|
||||
{
|
||||
b3RobotJointInfo()
|
||||
@@ -480,7 +460,7 @@ struct b3RobotJointInfo : public b3JointInfo
|
||||
m_parentFrame[5] = 0;
|
||||
m_parentFrame[6] = 1;
|
||||
|
||||
//position
|
||||
//position
|
||||
m_childFrame[0] = 0;
|
||||
m_childFrame[1] = 0;
|
||||
m_childFrame[2] = 0;
|
||||
@@ -490,28 +470,23 @@ struct b3RobotJointInfo : public b3JointInfo
|
||||
m_childFrame[5] = 0;
|
||||
m_childFrame[6] = 1;
|
||||
|
||||
|
||||
m_jointAxis[0] = 0;
|
||||
m_jointAxis[1] = 0;
|
||||
m_jointAxis[2] = 1;
|
||||
}
|
||||
};
|
||||
|
||||
|
||||
|
||||
class b3RobotSimulatorClientAPI_NoDirect
|
||||
{
|
||||
protected:
|
||||
|
||||
struct b3RobotSimulatorClientAPI_InternalData* m_data;
|
||||
struct b3RobotSimulatorClientAPI_InternalData *m_data;
|
||||
|
||||
public:
|
||||
|
||||
b3RobotSimulatorClientAPI_NoDirect();
|
||||
virtual ~b3RobotSimulatorClientAPI_NoDirect();
|
||||
|
||||
//No 'connect', use setInternalData to bypass the connect method, pass an existing client
|
||||
virtual void setInternalData(struct b3RobotSimulatorClientAPI_InternalData* data);
|
||||
virtual void setInternalData(struct b3RobotSimulatorClientAPI_InternalData *data);
|
||||
|
||||
void disconnect();
|
||||
|
||||
@@ -523,52 +498,52 @@ public:
|
||||
|
||||
void resetSimulation();
|
||||
|
||||
btQuaternion getQuaternionFromEuler(const btVector3& rollPitchYaw);
|
||||
btVector3 getEulerFromQuaternion(const btQuaternion& quat);
|
||||
btQuaternion getQuaternionFromEuler(const btVector3 &rollPitchYaw);
|
||||
btVector3 getEulerFromQuaternion(const btQuaternion &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 saveBullet(const std::string& fileName);
|
||||
|
||||
int loadTexture(const std::string& fileName);
|
||||
|
||||
bool changeVisualShape(const struct b3RobotSimulatorChangeVisualShapeArgs& args);
|
||||
|
||||
bool savePythonWorld(const std::string& fileName);
|
||||
|
||||
bool getBodyInfo(int bodyUniqueId, struct b3BodyInfo* bodyInfo);
|
||||
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 saveBullet(const std::string &fileName);
|
||||
|
||||
bool getBasePositionAndOrientation(int bodyUniqueId, btVector3& basePosition, btQuaternion& baseOrientation) const;
|
||||
bool resetBasePositionAndOrientation(int bodyUniqueId, btVector3& basePosition, btQuaternion& baseOrientation);
|
||||
int loadTexture(const std::string &fileName);
|
||||
|
||||
bool getBaseVelocity(int bodyUniqueId, btVector3& baseLinearVelocity, btVector3& baseAngularVelocity) const;
|
||||
bool resetBaseVelocity(int bodyUniqueId, const btVector3& linearVelocity, const btVector3& angularVelocity) const;
|
||||
bool changeVisualShape(const struct b3RobotSimulatorChangeVisualShapeArgs &args);
|
||||
|
||||
bool savePythonWorld(const std::string &fileName);
|
||||
|
||||
bool getBodyInfo(int bodyUniqueId, struct b3BodyInfo *bodyInfo);
|
||||
|
||||
bool getBasePositionAndOrientation(int bodyUniqueId, btVector3 &basePosition, btQuaternion &baseOrientation) const;
|
||||
bool resetBasePositionAndOrientation(int bodyUniqueId, btVector3 &basePosition, btQuaternion &baseOrientation);
|
||||
|
||||
bool getBaseVelocity(int bodyUniqueId, btVector3 &baseLinearVelocity, btVector3 &baseAngularVelocity) const;
|
||||
bool resetBaseVelocity(int bodyUniqueId, const btVector3 &linearVelocity, const btVector3 &angularVelocity) const;
|
||||
|
||||
int getNumJoints(int bodyUniqueId) const;
|
||||
|
||||
bool getJointInfo(int bodyUniqueId, int jointIndex, b3JointInfo* jointInfo);
|
||||
bool getJointInfo(int bodyUniqueId, int jointIndex, b3JointInfo *jointInfo);
|
||||
|
||||
int createConstraint(int parentBodyIndex, int parentJointIndex, int childBodyIndex, int childJointIndex, b3JointInfo* jointInfo);
|
||||
int createConstraint(int parentBodyIndex, int parentJointIndex, int childBodyIndex, int childJointIndex, b3JointInfo *jointInfo);
|
||||
|
||||
int changeConstraint(int constraintId, b3JointInfo *jointInfo);
|
||||
|
||||
int changeConstraint(int constraintId, b3JointInfo* jointInfo);
|
||||
|
||||
void removeConstraint(int constraintId);
|
||||
|
||||
bool getConstraintInfo(int constraintUniqueId, struct b3UserConstraint& constraintInfo);
|
||||
|
||||
bool getJointState(int bodyUniqueId, int jointIndex, struct b3JointSensorState* state);
|
||||
bool getConstraintInfo(int constraintUniqueId, struct b3UserConstraint &constraintInfo);
|
||||
|
||||
bool getJointStates(int bodyUniqueId, b3JointStates2& state);
|
||||
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 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);
|
||||
int *jointIndices, double *targetVelocities, double *targetPositions,
|
||||
double *forces, double *kps, double *kds);
|
||||
|
||||
void stepSimulation();
|
||||
|
||||
@@ -578,33 +553,33 @@ public:
|
||||
|
||||
void setInternalSimFlags(int flags);
|
||||
|
||||
void setGravity(const btVector3& gravityAcceleration);
|
||||
void setGravity(const btVector3 &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 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 getBodyJacobian(int bodyUniqueId, int linkIndex, const double *localPosition, const double *jointPositions, const double *jointVelocities, const double *jointAccelerations, double *linearJacobian, double *angularJacobian);
|
||||
|
||||
void configureDebugVisualizer(enum b3ConfigureDebugVisualizerEnum flag, int enable);
|
||||
void resetDebugVisualizerCamera(double cameraDistance, double cameraPitch, double cameraYaw, const btVector3& targetPos);
|
||||
void resetDebugVisualizerCamera(double cameraDistance, double cameraPitch, double cameraYaw, const btVector3 &targetPos);
|
||||
|
||||
int startStateLogging(b3StateLoggingType loggingType, const std::string& fileName, const btAlignedObjectArray<int>& objectUniqueIds=btAlignedObjectArray<int>(), int maxLogDof = -1);
|
||||
int startStateLogging(b3StateLoggingType loggingType, const std::string &fileName, const btAlignedObjectArray<int> &objectUniqueIds = btAlignedObjectArray<int>(), int maxLogDof = -1);
|
||||
void stopStateLogging(int stateLoggerUniqueId);
|
||||
|
||||
void getVREvents(b3VREventsData* vrEventsData, int deviceTypeFilter);
|
||||
void getKeyboardEvents(b3KeyboardEventsData* keyboardEventsData);
|
||||
void getVREvents(b3VREventsData *vrEventsData, int deviceTypeFilter);
|
||||
void getKeyboardEvents(b3KeyboardEventsData *keyboardEventsData);
|
||||
|
||||
void submitProfileTiming(const std::string& profileName, int durationInMicroSeconds=1);
|
||||
void submitProfileTiming(const std::string &profileName, int durationInMicroSeconds = 1);
|
||||
|
||||
// JFC: added these 24 methods
|
||||
|
||||
void getMouseEvents(b3MouseEventsData* mouseEventsData);
|
||||
void getMouseEvents(b3MouseEventsData *mouseEventsData);
|
||||
|
||||
bool getLinkState(int bodyUniqueId, int linkIndex, int computeLinkVelocity, int computeForwardKinematics, b3LinkState* linkState);
|
||||
bool getLinkState(int bodyUniqueId, int linkIndex, int computeLinkVelocity, int computeForwardKinematics, b3LinkState *linkState);
|
||||
|
||||
bool getCameraImage(int width, int height, struct b3RobotSimulatorGetCameraImageArgs args, b3CameraImageData &imageData);
|
||||
|
||||
@@ -636,9 +611,9 @@ public:
|
||||
|
||||
bool setJointMotorControlArray(int bodyUniqueId, struct b3RobotSimulatorJointMotorArrayArgs &args);
|
||||
|
||||
bool setPhysicsEngineParameter(const struct b3RobotSimulatorSetPhysicsEngineParameters&args);
|
||||
|
||||
bool getPhysicsEngineParameters(struct b3RobotSimulatorSetPhysicsEngineParameters&args);
|
||||
bool setPhysicsEngineParameter(const struct b3RobotSimulatorSetPhysicsEngineParameters &args);
|
||||
|
||||
bool getPhysicsEngineParameters(struct b3RobotSimulatorSetPhysicsEngineParameters &args);
|
||||
|
||||
bool applyExternalForce(int objectUniqueId, int linkIndex, double *force, double *position, int flags);
|
||||
|
||||
@@ -672,10 +647,10 @@ public:
|
||||
|
||||
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();
|
||||
void loadSoftBody(const std::string &fileName, double scale, double mass, double collisionMargin);
|
||||
|
||||
virtual void setGuiHelper(struct GUIHelperInterface *guiHelper);
|
||||
virtual struct GUIHelperInterface *getGuiHelper();
|
||||
|
||||
bool getCollisionShapeData(int bodyUniqueId, int linkIndex, b3CollisionShapeInformation &collisionShapeInfo);
|
||||
|
||||
@@ -688,9 +663,7 @@ public:
|
||||
{
|
||||
return SHARED_MEMORY_MAGIC_NUMBER;
|
||||
}
|
||||
void setAdditionalSearchPath(const std::string& path);
|
||||
void setAdditionalSearchPath(const std::string &path);
|
||||
};
|
||||
|
||||
|
||||
|
||||
#endif //B3_ROBOT_SIMULATOR_CLIENT_API_NO_DIRECT_H
|
||||
|
||||
Reference in New Issue
Block a user