Create project file for BussIK inverse kinematics library (premake, cmake)
URDF/SDF: add a flag to force concave mesh collisiofor static objects. <collision concave="yes" name="pod_collision"> VR: support teleporting using buttong, allow multiple controllers to be used, fast wireframe rendering, Turn off warnings about deprecated C routine in btScalar.h/b3Scalar.h Add a dummy return to stop a warning Expose defaultContactERP in shared memory api/pybullet. First start to expose IK in shared memory api/pybullet (not working yet)
This commit is contained in:
@@ -50,6 +50,7 @@ struct b3RobotSimLoadFileArgs
|
||||
}
|
||||
};
|
||||
|
||||
|
||||
struct b3RobotSimLoadFileResults
|
||||
{
|
||||
b3AlignedObjectArray<int> m_uniqueObjectIds;
|
||||
@@ -81,6 +82,35 @@ struct b3JointMotorArgs
|
||||
}
|
||||
};
|
||||
|
||||
enum b3InverseKinematicsFlags
|
||||
{
|
||||
B3_HAS_IK_TARGET_ORIENTATION=1,
|
||||
};
|
||||
|
||||
struct b3RobotSimInverseKinematicArgs
|
||||
{
|
||||
int m_bodyUniqueId;
|
||||
double* m_currentJointPositions;
|
||||
int m_numPositions;
|
||||
double m_endEffectorTargetPosition[3];
|
||||
double m_endEffectorTargetOrientation[3];
|
||||
int m_flags;
|
||||
|
||||
b3RobotSimInverseKinematicArgs()
|
||||
:m_bodyUniqueId(-1),
|
||||
m_currentJointPositions(0),
|
||||
m_numPositions(0),
|
||||
m_flags(0)
|
||||
{
|
||||
}
|
||||
};
|
||||
|
||||
struct b3RobotSimInverseKinematicsResults
|
||||
{
|
||||
int m_bodyUniqueId;
|
||||
double* m_calculatedJointPositions;
|
||||
int m_numPositions;
|
||||
};
|
||||
|
||||
class b3RobotSimAPI
|
||||
{
|
||||
@@ -113,6 +143,8 @@ public:
|
||||
|
||||
void setNumSimulationSubSteps(int numSubSteps);
|
||||
|
||||
bool calculateInverseKinematics(const struct b3RobotSimInverseKinematicArgs& args, struct b3RobotSimInverseKinematicsResults& results);
|
||||
|
||||
void renderScene();
|
||||
void debugDraw(int debugDrawMode);
|
||||
};
|
||||
|
||||
Reference in New Issue
Block a user