2015-09-17 06:09:10 +00:00
|
|
|
#ifndef SHARED_MEMORY_PUBLIC_H
|
|
|
|
#define SHARED_MEMORY_PUBLIC_H
|
|
|
|
|
|
|
|
#define SHARED_MEMORY_KEY 12347
|
2017-02-22 17:33:30 +00:00
|
|
|
///increase the SHARED_MEMORY_MAGIC_NUMBER whenever incompatible changes are made in the structures
|
|
|
|
///my convention is year/month/day/rev
|
2017-08-28 02:34:00 +00:00
|
|
|
|
2017-10-19 02:15:35 +00:00
|
|
|
#define SHARED_MEMORY_MAGIC_NUMBER 201710180
|
|
|
|
//#define SHARED_MEMORY_MAGIC_NUMBER 201710050
|
2017-09-26 17:05:17 +00:00
|
|
|
//#define SHARED_MEMORY_MAGIC_NUMBER 201708270
|
2017-08-28 02:34:00 +00:00
|
|
|
//#define SHARED_MEMORY_MAGIC_NUMBER 201707140
|
2017-07-14 22:12:16 +00:00
|
|
|
//#define SHARED_MEMORY_MAGIC_NUMBER 201706015
|
2017-06-16 02:46:27 +00:00
|
|
|
//#define SHARED_MEMORY_MAGIC_NUMBER 201706001
|
Improve debug text/line rendering, can be use to draw frames and text in local coordinate of an object / link.
example:
kuka = p.loadURDF("kuka_iiwa/model.urdf")
p.getNumJoints(kuka)
pybullet.addUserDebugLine([0,0,0],[0,0,0.1],[0,0,1],trackObjectUniqueId=2,trackLinkIndex=6)
pybullet.addUserDebugText("tip", [0,0,0.1],textColorRGB=[1,0,0],trackObjectUniqueId=2,trackLinkIndex=6)
Also allow to render text using a given orientation (instead of pointing to the camera), example:
pybullet.addUserDebugText("tip", [0,0,0.1],textColorRGB=[1,0,0],textOrientation=[0,0,0,1], trackObjectUniqueId=2,trackLinkIndex=6)
Add drawTexturedTriangleMesh, for drawing 3d text.
Expose readSingleInstanceTransformToCPU, to extract position/orientation from graphics index.
updateTexture: allow to not flip texels around up axis
2017-05-24 05:05:26 +00:00
|
|
|
//#define SHARED_MEMORY_MAGIC_NUMBER 201703024
|
2015-09-17 06:09:10 +00:00
|
|
|
|
2017-06-03 17:57:56 +00:00
|
|
|
|
2015-09-17 06:09:10 +00:00
|
|
|
enum EnumSharedMemoryClientCommand
|
|
|
|
{
|
2016-06-04 02:03:56 +00:00
|
|
|
CMD_LOAD_SDF,
|
|
|
|
CMD_LOAD_URDF,
|
2016-11-11 22:44:50 +00:00
|
|
|
CMD_LOAD_BULLET,
|
|
|
|
CMD_SAVE_BULLET,
|
|
|
|
CMD_LOAD_MJCF,
|
2016-10-17 20:01:04 +00:00
|
|
|
CMD_LOAD_BUNNY,
|
2016-11-12 02:07:42 +00:00
|
|
|
CMD_SEND_BULLET_DATA_STREAM,
|
|
|
|
CMD_CREATE_BOX_COLLISION_SHAPE,
|
|
|
|
CMD_CREATE_RIGID_BODY,
|
|
|
|
CMD_DELETE_RIGID_BODY,
|
|
|
|
CMD_CREATE_SENSOR,///enable or disable joint feedback for force/torque sensors
|
|
|
|
CMD_INIT_POSE,
|
|
|
|
CMD_SEND_PHYSICS_SIMULATION_PARAMETERS,
|
|
|
|
CMD_SEND_DESIRED_STATE,//todo: reconsider naming, for example SET_JOINT_CONTROL_VARIABLE?
|
|
|
|
CMD_REQUEST_ACTUAL_STATE,
|
|
|
|
CMD_REQUEST_DEBUG_LINES,
|
2016-06-15 01:41:19 +00:00
|
|
|
CMD_REQUEST_BODY_INFO,
|
2016-11-05 00:06:55 +00:00
|
|
|
CMD_REQUEST_INTERNAL_DATA,
|
2015-09-17 06:09:10 +00:00
|
|
|
CMD_STEP_FORWARD_SIMULATION,
|
|
|
|
CMD_RESET_SIMULATION,
|
2015-09-25 05:42:22 +00:00
|
|
|
CMD_PICK_BODY,
|
|
|
|
CMD_MOVE_PICKED_BODY,
|
|
|
|
CMD_REMOVE_PICKING_CONSTRAINT_BODY,
|
2016-05-18 06:57:19 +00:00
|
|
|
CMD_REQUEST_CAMERA_IMAGE_DATA,
|
2016-06-27 01:18:30 +00:00
|
|
|
CMD_APPLY_EXTERNAL_FORCE,
|
2016-08-10 01:40:12 +00:00
|
|
|
CMD_CALCULATE_INVERSE_DYNAMICS,
|
2016-08-30 21:44:11 +00:00
|
|
|
CMD_CALCULATE_INVERSE_KINEMATICS,
|
2016-09-07 23:00:38 +00:00
|
|
|
CMD_CALCULATE_JACOBIAN,
|
2017-09-30 20:39:11 +00:00
|
|
|
CMD_CALCULATE_MASS_MATRIX,
|
2016-11-14 22:08:05 +00:00
|
|
|
CMD_USER_CONSTRAINT,
|
2016-09-01 20:30:07 +00:00
|
|
|
CMD_REQUEST_CONTACT_POINT_INFORMATION,
|
2016-12-27 03:40:09 +00:00
|
|
|
CMD_REQUEST_RAY_CAST_INTERSECTIONS,
|
|
|
|
|
2016-11-10 19:22:22 +00:00
|
|
|
CMD_REQUEST_AABB_OVERLAP,
|
2016-12-27 03:40:09 +00:00
|
|
|
|
2016-10-13 06:03:36 +00:00
|
|
|
CMD_SAVE_WORLD,
|
2016-10-19 05:05:28 +00:00
|
|
|
CMD_REQUEST_VISUAL_SHAPE_INFO,
|
2016-10-20 17:56:44 +00:00
|
|
|
CMD_UPDATE_VISUAL_SHAPE,
|
2016-10-21 06:40:30 +00:00
|
|
|
CMD_LOAD_TEXTURE,
|
2016-11-29 21:19:35 +00:00
|
|
|
CMD_SET_SHADOW,
|
2016-11-14 15:39:34 +00:00
|
|
|
CMD_USER_DEBUG_DRAW,
|
2016-12-27 03:40:09 +00:00
|
|
|
CMD_REQUEST_VR_EVENTS_DATA,
|
2017-01-06 01:41:58 +00:00
|
|
|
CMD_SET_VR_CAMERA_STATE,
|
2017-01-21 02:13:24 +00:00
|
|
|
CMD_SYNC_BODY_INFO,
|
2017-02-17 22:25:53 +00:00
|
|
|
CMD_STATE_LOGGING,
|
2017-02-22 01:36:54 +00:00
|
|
|
CMD_CONFIGURE_OPENGL_VISUALIZER,
|
2017-03-02 20:33:22 +00:00
|
|
|
CMD_REQUEST_KEYBOARD_EVENTS_DATA,
|
2017-04-10 18:03:41 +00:00
|
|
|
CMD_REQUEST_OPENGL_VISUALIZER_CAMERA,
|
2017-05-04 04:53:29 +00:00
|
|
|
CMD_REMOVE_BODY,
|
2017-05-09 17:44:33 +00:00
|
|
|
CMD_CHANGE_DYNAMICS_INFO,
|
2017-05-09 17:31:28 +00:00
|
|
|
CMD_GET_DYNAMICS_INFO,
|
2017-05-05 00:51:40 +00:00
|
|
|
CMD_PROFILE_TIMING,
|
2017-06-03 17:57:56 +00:00
|
|
|
CMD_CREATE_COLLISION_SHAPE,
|
|
|
|
CMD_CREATE_VISUAL_SHAPE,
|
|
|
|
CMD_CREATE_MULTI_BODY,
|
2017-06-17 01:10:10 +00:00
|
|
|
CMD_REQUEST_COLLISION_INFO,
|
2017-06-17 20:29:14 +00:00
|
|
|
CMD_REQUEST_MOUSE_EVENTS_DATA,
|
2017-07-01 02:11:43 +00:00
|
|
|
CMD_CHANGE_TEXTURE,
|
2017-08-28 02:34:00 +00:00
|
|
|
CMD_SET_ADDITIONAL_SEARCH_PATH,
|
2017-09-23 02:17:57 +00:00
|
|
|
CMD_CUSTOM_COMMAND,
|
2017-10-05 18:43:14 +00:00
|
|
|
CMD_REQUEST_PHYSICS_SIMULATION_PARAMETERS,
|
2016-09-01 20:30:07 +00:00
|
|
|
//don't go beyond this command!
|
2016-08-23 01:14:29 +00:00
|
|
|
CMD_MAX_CLIENT_COMMANDS,
|
2016-09-01 20:30:07 +00:00
|
|
|
|
2015-09-17 06:09:10 +00:00
|
|
|
};
|
|
|
|
|
|
|
|
enum EnumSharedMemoryServerStatus
|
|
|
|
{
|
|
|
|
CMD_SHARED_MEMORY_NOT_INITIALIZED=0,
|
|
|
|
CMD_WAITING_FOR_CLIENT_COMMAND,
|
|
|
|
//CMD_CLIENT_COMMAND_COMPLETED is a generic 'completed' status that doesn't need special handling on the client
|
|
|
|
CMD_CLIENT_COMMAND_COMPLETED,
|
|
|
|
//the server will skip unknown command and report a status 'CMD_UNKNOWN_COMMAND_FLUSHED'
|
|
|
|
CMD_UNKNOWN_COMMAND_FLUSHED,
|
2016-06-04 02:03:56 +00:00
|
|
|
CMD_SDF_LOADING_COMPLETED,
|
|
|
|
CMD_SDF_LOADING_FAILED,
|
2015-09-17 06:09:10 +00:00
|
|
|
CMD_URDF_LOADING_COMPLETED,
|
|
|
|
CMD_URDF_LOADING_FAILED,
|
2016-11-12 02:07:42 +00:00
|
|
|
CMD_BULLET_LOADING_COMPLETED,
|
|
|
|
CMD_BULLET_LOADING_FAILED,
|
|
|
|
CMD_BULLET_SAVING_COMPLETED,
|
|
|
|
CMD_BULLET_SAVING_FAILED,
|
|
|
|
CMD_MJCF_LOADING_COMPLETED,
|
|
|
|
CMD_MJCF_LOADING_FAILED,
|
2016-11-05 00:06:55 +00:00
|
|
|
CMD_REQUEST_INTERNAL_DATA_COMPLETED,
|
|
|
|
CMD_REQUEST_INTERNAL_DATA_FAILED,
|
2015-09-17 06:09:10 +00:00
|
|
|
CMD_BULLET_DATA_STREAM_RECEIVED_COMPLETED,
|
|
|
|
CMD_BULLET_DATA_STREAM_RECEIVED_FAILED,
|
|
|
|
CMD_BOX_COLLISION_SHAPE_CREATION_COMPLETED,
|
|
|
|
CMD_RIGID_BODY_CREATION_COMPLETED,
|
|
|
|
CMD_SET_JOINT_FEEDBACK_COMPLETED,
|
|
|
|
CMD_ACTUAL_STATE_UPDATE_COMPLETED,
|
|
|
|
CMD_ACTUAL_STATE_UPDATE_FAILED,
|
|
|
|
CMD_DEBUG_LINES_COMPLETED,
|
|
|
|
CMD_DEBUG_LINES_OVERFLOW_FAILED,
|
|
|
|
CMD_DESIRED_STATE_RECEIVED_COMPLETED,
|
|
|
|
CMD_STEP_FORWARD_SIMULATION_COMPLETED,
|
2016-05-20 01:37:15 +00:00
|
|
|
CMD_RESET_SIMULATION_COMPLETED,
|
|
|
|
CMD_CAMERA_IMAGE_COMPLETED,
|
|
|
|
CMD_CAMERA_IMAGE_FAILED,
|
2016-06-15 01:41:19 +00:00
|
|
|
CMD_BODY_INFO_COMPLETED,
|
|
|
|
CMD_BODY_INFO_FAILED,
|
2016-03-10 22:36:46 +00:00
|
|
|
CMD_INVALID_STATUS,
|
2016-08-10 01:40:12 +00:00
|
|
|
CMD_CALCULATED_INVERSE_DYNAMICS_COMPLETED,
|
|
|
|
CMD_CALCULATED_INVERSE_DYNAMICS_FAILED,
|
2016-09-07 23:00:38 +00:00
|
|
|
CMD_CALCULATED_JACOBIAN_COMPLETED,
|
|
|
|
CMD_CALCULATED_JACOBIAN_FAILED,
|
2017-09-30 20:39:11 +00:00
|
|
|
CMD_CALCULATED_MASS_MATRIX_COMPLETED,
|
|
|
|
CMD_CALCULATED_MASS_MATRIX_FAILED,
|
2016-09-01 20:30:07 +00:00
|
|
|
CMD_CONTACT_POINT_INFORMATION_COMPLETED,
|
|
|
|
CMD_CONTACT_POINT_INFORMATION_FAILED,
|
2016-11-10 19:22:22 +00:00
|
|
|
CMD_REQUEST_AABB_OVERLAP_COMPLETED,
|
|
|
|
CMD_REQUEST_AABB_OVERLAP_FAILED,
|
2016-09-08 22:15:58 +00:00
|
|
|
CMD_CALCULATE_INVERSE_KINEMATICS_COMPLETED,
|
|
|
|
CMD_CALCULATE_INVERSE_KINEMATICS_FAILED,
|
2016-10-13 06:03:36 +00:00
|
|
|
CMD_SAVE_WORLD_COMPLETED,
|
|
|
|
CMD_SAVE_WORLD_FAILED,
|
2016-10-19 05:05:28 +00:00
|
|
|
CMD_VISUAL_SHAPE_INFO_COMPLETED,
|
|
|
|
CMD_VISUAL_SHAPE_INFO_FAILED,
|
2016-10-20 17:56:44 +00:00
|
|
|
CMD_VISUAL_SHAPE_UPDATE_COMPLETED,
|
|
|
|
CMD_VISUAL_SHAPE_UPDATE_FAILED,
|
2016-10-21 06:40:30 +00:00
|
|
|
CMD_LOAD_TEXTURE_COMPLETED,
|
|
|
|
CMD_LOAD_TEXTURE_FAILED,
|
2016-11-14 15:39:34 +00:00
|
|
|
CMD_USER_DEBUG_DRAW_COMPLETED,
|
2017-01-17 23:42:32 +00:00
|
|
|
CMD_USER_DEBUG_DRAW_PARAMETER_COMPLETED,
|
2016-11-14 15:39:34 +00:00
|
|
|
CMD_USER_DEBUG_DRAW_FAILED,
|
2016-11-14 22:08:05 +00:00
|
|
|
CMD_USER_CONSTRAINT_COMPLETED,
|
2017-01-23 03:08:31 +00:00
|
|
|
CMD_USER_CONSTRAINT_INFO_COMPLETED,
|
2017-10-19 02:15:35 +00:00
|
|
|
CMD_USER_CONSTRAINT_REQUEST_STATE_COMPLETED,
|
2017-01-23 03:08:31 +00:00
|
|
|
CMD_REMOVE_USER_CONSTRAINT_COMPLETED,
|
|
|
|
CMD_CHANGE_USER_CONSTRAINT_COMPLETED,
|
|
|
|
CMD_REMOVE_USER_CONSTRAINT_FAILED,
|
|
|
|
CMD_CHANGE_USER_CONSTRAINT_FAILED,
|
2016-11-14 22:08:05 +00:00
|
|
|
CMD_USER_CONSTRAINT_FAILED,
|
2016-12-27 03:40:09 +00:00
|
|
|
CMD_REQUEST_VR_EVENTS_DATA_COMPLETED,
|
|
|
|
CMD_REQUEST_RAY_CAST_INTERSECTIONS_COMPLETED,
|
2017-01-21 02:13:24 +00:00
|
|
|
CMD_SYNC_BODY_INFO_COMPLETED,
|
|
|
|
CMD_SYNC_BODY_INFO_FAILED,
|
2017-02-17 22:25:53 +00:00
|
|
|
CMD_STATE_LOGGING_COMPLETED,
|
|
|
|
CMD_STATE_LOGGING_START_COMPLETED,
|
|
|
|
CMD_STATE_LOGGING_FAILED,
|
2017-03-02 20:33:22 +00:00
|
|
|
CMD_REQUEST_KEYBOARD_EVENTS_DATA_COMPLETED,
|
|
|
|
CMD_REQUEST_KEYBOARD_EVENTS_DATA_FAILED,
|
2017-04-10 18:03:41 +00:00
|
|
|
CMD_REQUEST_OPENGL_VISUALIZER_CAMERA_FAILED,
|
|
|
|
CMD_REQUEST_OPENGL_VISUALIZER_CAMERA_COMPLETED,
|
2017-05-04 04:53:29 +00:00
|
|
|
CMD_REMOVE_BODY_COMPLETED,
|
|
|
|
CMD_REMOVE_BODY_FAILED,
|
2017-05-09 17:31:28 +00:00
|
|
|
CMD_GET_DYNAMICS_INFO_COMPLETED,
|
|
|
|
CMD_GET_DYNAMICS_INFO_FAILED,
|
2017-06-03 17:57:56 +00:00
|
|
|
CMD_CREATE_COLLISION_SHAPE_FAILED,
|
|
|
|
CMD_CREATE_COLLISION_SHAPE_COMPLETED,
|
|
|
|
CMD_CREATE_VISUAL_SHAPE_FAILED,
|
|
|
|
CMD_CREATE_VISUAL_SHAPE_COMPLETED,
|
|
|
|
CMD_CREATE_MULTI_BODY_FAILED,
|
|
|
|
CMD_CREATE_MULTI_BODY_COMPLETED,
|
2017-06-17 01:10:10 +00:00
|
|
|
CMD_REQUEST_COLLISION_INFO_COMPLETED,
|
|
|
|
CMD_REQUEST_COLLISION_INFO_FAILED,
|
2017-06-17 20:29:14 +00:00
|
|
|
CMD_REQUEST_MOUSE_EVENTS_DATA_COMPLETED,
|
2017-07-01 02:11:43 +00:00
|
|
|
CMD_CHANGE_TEXTURE_COMMAND_FAILED,
|
2017-09-23 02:17:57 +00:00
|
|
|
CMD_CUSTOM_COMMAND_COMPLETED,
|
|
|
|
CMD_CUSTOM_COMMAND_FAILED,
|
2017-10-05 18:43:14 +00:00
|
|
|
CMD_REQUEST_PHYSICS_SIMULATION_PARAMETERS_COMPLETED,
|
2016-10-19 05:05:28 +00:00
|
|
|
//don't go beyond 'CMD_MAX_SERVER_COMMANDS!
|
2015-09-17 06:09:10 +00:00
|
|
|
CMD_MAX_SERVER_COMMANDS
|
|
|
|
};
|
|
|
|
|
|
|
|
enum JointInfoFlags
|
|
|
|
{
|
|
|
|
JOINT_HAS_MOTORIZED_POWER=1,
|
|
|
|
};
|
2015-10-27 21:55:46 +00:00
|
|
|
|
|
|
|
enum
|
|
|
|
{
|
|
|
|
COLLISION_SHAPE_TYPE_BOX=1,
|
|
|
|
COLLISION_SHAPE_TYPE_CYLINDER_X,
|
|
|
|
COLLISION_SHAPE_TYPE_CYLINDER_Y,
|
|
|
|
COLLISION_SHAPE_TYPE_CYLINDER_Z,
|
|
|
|
COLLISION_SHAPE_TYPE_CAPSULE_X,
|
|
|
|
COLLISION_SHAPE_TYPE_CAPSULE_Y,
|
|
|
|
COLLISION_SHAPE_TYPE_CAPSULE_Z,
|
|
|
|
COLLISION_SHAPE_TYPE_SPHERE
|
|
|
|
};
|
|
|
|
|
2015-11-23 04:50:32 +00:00
|
|
|
// copied from btMultiBodyLink.h
|
|
|
|
enum JointType {
|
2016-12-15 04:44:10 +00:00
|
|
|
eRevoluteType = 0,
|
|
|
|
ePrismaticType = 1,
|
|
|
|
eSphericalType = 2,
|
|
|
|
ePlanarType = 3,
|
|
|
|
eFixedType = 4,
|
|
|
|
ePoint2PointType = 5,
|
2017-06-07 20:44:34 +00:00
|
|
|
eGearType=6
|
2015-11-23 04:50:32 +00:00
|
|
|
};
|
|
|
|
|
2017-12-20 22:54:32 +00:00
|
|
|
enum b3RequestDynamicsInfoFlags
|
|
|
|
{
|
|
|
|
eDYNAMICS_INFO_REPORT_INERTIA=1,
|
|
|
|
};
|
2017-05-02 05:35:33 +00:00
|
|
|
|
|
|
|
enum b3JointInfoFlags
|
|
|
|
{
|
|
|
|
eJointChangeMaxForce = 1,
|
|
|
|
eJointChangeChildFramePosition = 2,
|
|
|
|
eJointChangeChildFrameOrientation = 4,
|
|
|
|
};
|
|
|
|
|
2015-09-17 06:09:10 +00:00
|
|
|
struct b3JointInfo
|
|
|
|
{
|
2017-10-04 01:01:53 +00:00
|
|
|
char m_linkName[1024];
|
|
|
|
char m_jointName[1024];
|
2015-09-17 06:09:10 +00:00
|
|
|
int m_jointType;
|
|
|
|
int m_qIndex;
|
|
|
|
int m_uIndex;
|
2015-09-25 05:42:22 +00:00
|
|
|
int m_jointIndex;
|
2015-09-17 06:09:10 +00:00
|
|
|
int m_flags;
|
2016-03-17 21:54:46 +00:00
|
|
|
double m_jointDamping;
|
|
|
|
double m_jointFriction;
|
2017-03-26 20:06:46 +00:00
|
|
|
double m_jointLowerLimit;
|
|
|
|
double m_jointUpperLimit;
|
|
|
|
double m_jointMaxForce;
|
|
|
|
double m_jointMaxVelocity;
|
|
|
|
double m_parentFrame[7]; // position and orientation (quaternion)
|
|
|
|
double m_childFrame[7]; // ^^^
|
|
|
|
double m_jointAxis[3]; // joint axis in parent local frame
|
2015-09-17 06:09:10 +00:00
|
|
|
};
|
|
|
|
|
2017-06-03 17:57:56 +00:00
|
|
|
|
2017-01-23 03:08:31 +00:00
|
|
|
struct b3UserConstraint
|
|
|
|
{
|
|
|
|
int m_parentBodyIndex;
|
|
|
|
int m_parentJointIndex;
|
|
|
|
int m_childBodyIndex;
|
|
|
|
int m_childJointIndex;
|
|
|
|
double m_parentFrame[7];
|
|
|
|
double m_childFrame[7];
|
|
|
|
double m_jointAxis[3];
|
|
|
|
int m_jointType;
|
|
|
|
double m_maxAppliedForce;
|
|
|
|
int m_userConstraintUniqueId;
|
2017-06-07 20:44:34 +00:00
|
|
|
double m_gearRatio;
|
2017-06-24 03:24:04 +00:00
|
|
|
int m_gearAuxLink;
|
2017-09-27 02:54:36 +00:00
|
|
|
double m_relativePositionTarget;
|
|
|
|
double m_erp;
|
2017-01-23 03:08:31 +00:00
|
|
|
};
|
|
|
|
|
2016-09-27 19:13:45 +00:00
|
|
|
struct b3BodyInfo
|
|
|
|
{
|
2017-10-04 01:01:53 +00:00
|
|
|
char m_baseName[1024];
|
|
|
|
char m_bodyName[1024]; // for btRigidBody, it does not have a base, but can still have a body name from urdf
|
2016-09-27 19:13:45 +00:00
|
|
|
};
|
|
|
|
|
2017-05-09 17:31:28 +00:00
|
|
|
struct b3DynamicsInfo
|
2017-05-02 05:18:54 +00:00
|
|
|
{
|
|
|
|
double m_mass;
|
2017-12-20 22:54:32 +00:00
|
|
|
double m_localInertialDiagonal[3];
|
2017-05-08 04:09:08 +00:00
|
|
|
double m_lateralFrictionCoeff;
|
2017-05-02 05:18:54 +00:00
|
|
|
};
|
2017-01-31 18:14:00 +00:00
|
|
|
|
|
|
|
// copied from btMultiBodyLink.h
|
|
|
|
enum SensorType {
|
|
|
|
eSensorForceTorqueType = 1,
|
|
|
|
};
|
2016-09-27 19:13:45 +00:00
|
|
|
|
|
|
|
|
2015-09-25 05:42:22 +00:00
|
|
|
struct b3JointSensorState
|
|
|
|
{
|
|
|
|
double m_jointPosition;
|
|
|
|
double m_jointVelocity;
|
|
|
|
double m_jointForceTorque[6]; /* note to roboticists: this is NOT the motor torque/force, but the spatial reaction force vector at joint */
|
2016-04-19 19:22:38 +00:00
|
|
|
double m_jointMotorTorque;
|
2015-09-25 05:42:22 +00:00
|
|
|
};
|
|
|
|
|
2015-09-17 06:09:10 +00:00
|
|
|
struct b3DebugLines
|
|
|
|
{
|
|
|
|
int m_numDebugLines;
|
|
|
|
const float* m_linesFrom;//float x,y,z times 'm_numDebugLines'.
|
|
|
|
const float* m_linesTo;//float x,y,z times 'm_numDebugLines'.
|
|
|
|
const float* m_linesColor;//float red,green,blue times 'm_numDebugLines'.
|
|
|
|
};
|
|
|
|
|
2016-11-10 19:22:22 +00:00
|
|
|
struct b3OverlappingObject
|
|
|
|
{
|
|
|
|
int m_objectUniqueId;
|
|
|
|
int m_linkIndex;
|
|
|
|
};
|
|
|
|
|
2016-11-10 05:01:04 +00:00
|
|
|
struct b3AABBOverlapData
|
|
|
|
{
|
|
|
|
int m_numOverlappingObjects;
|
2016-11-10 19:22:22 +00:00
|
|
|
struct b3OverlappingObject* m_overlappingObjects;
|
2016-11-10 05:01:04 +00:00
|
|
|
};
|
|
|
|
|
2016-05-18 06:57:19 +00:00
|
|
|
struct b3CameraImageData
|
|
|
|
{
|
|
|
|
int m_pixelWidth;
|
|
|
|
int m_pixelHeight;
|
|
|
|
const unsigned char* m_rgbColorData;//3*m_pixelWidth*m_pixelHeight bytes
|
2016-08-12 20:55:37 +00:00
|
|
|
const float* m_depthValues;//m_pixelWidth*m_pixelHeight floats
|
2016-08-11 21:55:30 +00:00
|
|
|
const int* m_segmentationMaskValues;//m_pixelWidth*m_pixelHeight ints
|
2016-05-18 06:57:19 +00:00
|
|
|
};
|
|
|
|
|
2017-04-10 18:03:41 +00:00
|
|
|
struct b3OpenGLVisualizerCameraInfo
|
|
|
|
{
|
|
|
|
int m_width;
|
|
|
|
int m_height;
|
|
|
|
float m_viewMatrix[16];
|
|
|
|
float m_projectionMatrix[16];
|
|
|
|
|
|
|
|
float m_camUp[3];
|
|
|
|
float m_camForward[3];
|
|
|
|
|
|
|
|
float m_horizontal[3];
|
|
|
|
float m_vertical[3];
|
2017-06-03 01:24:51 +00:00
|
|
|
|
|
|
|
float m_yaw;
|
|
|
|
float m_pitch;
|
|
|
|
float m_dist;
|
|
|
|
float m_target[3];
|
2017-04-10 18:03:41 +00:00
|
|
|
};
|
2016-09-01 20:30:07 +00:00
|
|
|
|
2017-10-19 02:15:35 +00:00
|
|
|
struct b3UserConstraintState
|
|
|
|
{
|
|
|
|
double m_appliedConstraintForces[6];
|
|
|
|
int m_numDofs;
|
|
|
|
};
|
|
|
|
|
2016-12-27 03:40:09 +00:00
|
|
|
enum b3VREventType
|
|
|
|
{
|
|
|
|
VR_CONTROLLER_MOVE_EVENT=1,
|
2017-04-08 05:53:36 +00:00
|
|
|
VR_CONTROLLER_BUTTON_EVENT=2,
|
|
|
|
VR_HMD_MOVE_EVENT=4,
|
|
|
|
VR_GENERIC_TRACKER_MOVE_EVENT=8,
|
2016-12-27 03:40:09 +00:00
|
|
|
};
|
|
|
|
|
2017-10-05 19:59:58 +00:00
|
|
|
#define MAX_VR_ANALOG_AXIS 5
|
2016-12-27 03:40:09 +00:00
|
|
|
#define MAX_VR_BUTTONS 64
|
|
|
|
#define MAX_VR_CONTROLLERS 8
|
2017-04-05 22:21:26 +00:00
|
|
|
|
2017-04-19 19:06:26 +00:00
|
|
|
#define MAX_RAY_INTERSECTION_BATCH_SIZE 256
|
2017-04-05 22:21:26 +00:00
|
|
|
#define MAX_RAY_HITS MAX_RAY_INTERSECTION_BATCH_SIZE
|
2017-03-02 20:33:22 +00:00
|
|
|
#define MAX_KEYBOARD_EVENTS 256
|
2017-06-17 20:29:14 +00:00
|
|
|
#define MAX_MOUSE_EVENTS 256
|
2017-04-05 22:21:26 +00:00
|
|
|
|
2017-11-20 19:05:31 +00:00
|
|
|
#define MAX_SDF_BODIES 512
|
2017-11-04 19:51:13 +00:00
|
|
|
|
2017-04-05 22:21:26 +00:00
|
|
|
|
2016-12-27 03:40:09 +00:00
|
|
|
enum b3VRButtonInfo
|
|
|
|
{
|
|
|
|
eButtonIsDown = 1,
|
|
|
|
eButtonTriggered = 2,
|
|
|
|
eButtonReleased = 4,
|
|
|
|
};
|
|
|
|
|
2017-04-08 05:53:36 +00:00
|
|
|
|
|
|
|
|
|
|
|
enum eVRDeviceTypeEnums
|
|
|
|
{
|
|
|
|
VR_DEVICE_CONTROLLER=1,
|
|
|
|
VR_DEVICE_HMD=2,
|
2017-04-08 17:37:32 +00:00
|
|
|
VR_DEVICE_GENERIC_TRACKER=4,
|
2017-04-08 05:53:36 +00:00
|
|
|
};
|
|
|
|
|
2017-05-18 02:29:12 +00:00
|
|
|
enum EVRCameraFlags
|
|
|
|
{
|
|
|
|
VR_CAMERA_TRACK_OBJECT_ORIENTATION=1,
|
|
|
|
};
|
|
|
|
|
2016-12-27 03:40:09 +00:00
|
|
|
struct b3VRControllerEvent
|
|
|
|
{
|
|
|
|
int m_controllerId;//valid for VR_CONTROLLER_MOVE_EVENT and VR_CONTROLLER_BUTTON_EVENT
|
2017-04-08 05:53:36 +00:00
|
|
|
int m_deviceType;
|
2016-12-27 03:40:09 +00:00
|
|
|
int m_numMoveEvents;
|
|
|
|
int m_numButtonEvents;
|
|
|
|
|
|
|
|
float m_pos[4];//valid for VR_CONTROLLER_MOVE_EVENT and VR_CONTROLLER_BUTTON_EVENT
|
|
|
|
float m_orn[4];//valid for VR_CONTROLLER_MOVE_EVENT and VR_CONTROLLER_BUTTON_EVENT
|
|
|
|
|
|
|
|
float m_analogAxis;//valid if VR_CONTROLLER_MOVE_EVENT
|
2017-10-05 19:59:58 +00:00
|
|
|
float m_auxAnalogAxis[MAX_VR_ANALOG_AXIS*2];//store x,y per axis, only valid if VR_CONTROLLER_MOVE_EVENT
|
2016-12-27 03:40:09 +00:00
|
|
|
int m_buttons[MAX_VR_BUTTONS];//valid if VR_CONTROLLER_BUTTON_EVENT, see b3VRButtonInfo
|
|
|
|
};
|
|
|
|
|
|
|
|
struct b3VREventsData
|
|
|
|
{
|
|
|
|
int m_numControllerEvents;
|
|
|
|
struct b3VRControllerEvent* m_controllerEvents;
|
2017-05-02 05:35:33 +00:00
|
|
|
|
2016-12-27 03:40:09 +00:00
|
|
|
};
|
|
|
|
|
|
|
|
|
2017-03-02 20:33:22 +00:00
|
|
|
struct b3KeyboardEvent
|
|
|
|
{
|
|
|
|
int m_keyCode;//ascii
|
|
|
|
int m_keyState;// see b3VRButtonInfo
|
|
|
|
};
|
|
|
|
|
|
|
|
struct b3KeyboardEventsData
|
|
|
|
{
|
|
|
|
int m_numKeyboardEvents;
|
|
|
|
struct b3KeyboardEvent* m_keyboardEvents;
|
|
|
|
};
|
|
|
|
|
2017-06-17 20:29:14 +00:00
|
|
|
|
|
|
|
enum eMouseEventTypeEnums
|
|
|
|
{
|
|
|
|
MOUSE_MOVE_EVENT=1,
|
|
|
|
MOUSE_BUTTON_EVENT=2,
|
|
|
|
};
|
|
|
|
|
|
|
|
struct b3MouseEvent
|
|
|
|
{
|
|
|
|
int m_eventType;
|
|
|
|
float m_mousePosX;
|
|
|
|
float m_mousePosY;
|
|
|
|
int m_buttonIndex;
|
|
|
|
int m_buttonState;
|
|
|
|
};
|
|
|
|
|
|
|
|
struct b3MouseEventsData
|
|
|
|
{
|
|
|
|
int m_numMouseEvents;
|
|
|
|
struct b3MouseEvent* m_mouseEvents;
|
|
|
|
};
|
|
|
|
|
2016-09-01 20:30:07 +00:00
|
|
|
struct b3ContactPointData
|
|
|
|
{
|
2016-09-02 01:28:39 +00:00
|
|
|
//todo: expose some contact flags, such as telling which fields below are valid
|
|
|
|
int m_contactFlags;
|
2016-09-01 20:30:07 +00:00
|
|
|
int m_bodyUniqueIdA;
|
|
|
|
int m_bodyUniqueIdB;
|
|
|
|
int m_linkIndexA;
|
|
|
|
int m_linkIndexB;
|
|
|
|
double m_positionOnAInWS[3];//contact point location on object A, in world space coordinates
|
|
|
|
double m_positionOnBInWS[3];//contact point location on object A, in world space coordinates
|
|
|
|
double m_contactNormalOnBInWS[3];//the separating contact normal, pointing from object B towards object A
|
|
|
|
double m_contactDistance;//negative number is penetration, positive is distance.
|
2016-09-02 01:28:39 +00:00
|
|
|
|
2016-09-01 20:30:07 +00:00
|
|
|
double m_normalForce;
|
2016-09-02 01:28:39 +00:00
|
|
|
|
|
|
|
//todo: expose the friction forces as well
|
|
|
|
// double m_linearFrictionDirection0[3];
|
|
|
|
// double m_linearFrictionForce0;
|
|
|
|
// double m_linearFrictionDirection1[3];
|
|
|
|
// double m_linearFrictionForce1;
|
|
|
|
// double m_angularFrictionDirection[3];
|
|
|
|
// double m_angularFrictionForce;
|
2016-09-01 20:30:07 +00:00
|
|
|
};
|
|
|
|
|
2016-11-10 05:01:04 +00:00
|
|
|
enum
|
|
|
|
{
|
|
|
|
CONTACT_QUERY_MODE_REPORT_EXISTING_CONTACT_POINTS = 0,
|
|
|
|
CONTACT_QUERY_MODE_COMPUTE_CLOSEST_POINTS = 1,
|
|
|
|
};
|
|
|
|
|
2017-02-24 23:34:11 +00:00
|
|
|
enum b3StateLoggingType
|
2017-02-17 18:47:55 +00:00
|
|
|
{
|
2017-02-17 22:25:53 +00:00
|
|
|
STATE_LOGGING_MINITAUR = 0,
|
|
|
|
STATE_LOGGING_GENERIC_ROBOT = 1,
|
|
|
|
STATE_LOGGING_VR_CONTROLLERS = 2,
|
2017-03-16 16:13:33 +00:00
|
|
|
STATE_LOGGING_VIDEO_MP4 = 3,
|
|
|
|
STATE_LOGGING_COMMANDS = 4,
|
2017-04-02 22:09:40 +00:00
|
|
|
STATE_LOGGING_CONTACT_POINTS = 5,
|
2017-05-05 00:51:40 +00:00
|
|
|
STATE_LOGGING_PROFILE_TIMINGS = 6,
|
2017-02-17 18:47:55 +00:00
|
|
|
};
|
2016-11-10 05:01:04 +00:00
|
|
|
|
2016-09-02 01:28:39 +00:00
|
|
|
|
2016-09-01 20:30:07 +00:00
|
|
|
struct b3ContactInformation
|
|
|
|
{
|
|
|
|
int m_numContactPoints;
|
|
|
|
struct b3ContactPointData* m_contactPointData;
|
|
|
|
};
|
|
|
|
|
2016-12-27 03:40:09 +00:00
|
|
|
struct b3RayHitInfo
|
|
|
|
{
|
|
|
|
double m_hitFraction;
|
|
|
|
int m_hitObjectUniqueId;
|
|
|
|
int m_hitObjectLinkIndex;
|
|
|
|
double m_hitPositionWorld[3];
|
|
|
|
double m_hitNormalWorld[3];
|
|
|
|
};
|
|
|
|
|
|
|
|
struct b3RaycastInformation
|
|
|
|
{
|
|
|
|
int m_numRayHits;
|
|
|
|
struct b3RayHitInfo* m_rayHits;
|
|
|
|
};
|
|
|
|
|
|
|
|
|
2017-05-25 17:56:01 +00:00
|
|
|
#define VISUAL_SHAPE_MAX_PATH_LEN 1024
|
2016-10-19 05:05:28 +00:00
|
|
|
|
|
|
|
struct b3VisualShapeData
|
|
|
|
{
|
|
|
|
int m_objectUniqueId;
|
|
|
|
int m_linkIndex;
|
|
|
|
int m_visualGeometryType;//box primitive, sphere primitive, triangle mesh
|
|
|
|
double m_dimensions[3];//meaning depends on m_visualGeometryType
|
|
|
|
char m_meshAssetFileName[VISUAL_SHAPE_MAX_PATH_LEN];
|
2017-01-25 16:29:45 +00:00
|
|
|
double m_localVisualFrame[7];//pos[3], orn[4]
|
2016-10-19 05:05:28 +00:00
|
|
|
//todo: add more data if necessary (material color etc, although material can be in asset file .obj file)
|
2016-11-14 15:39:34 +00:00
|
|
|
double m_rgbaColor[4];
|
2016-10-19 05:05:28 +00:00
|
|
|
};
|
|
|
|
|
|
|
|
struct b3VisualShapeInformation
|
|
|
|
{
|
|
|
|
int m_numVisualShapes;
|
|
|
|
struct b3VisualShapeData* m_visualShapeData;
|
|
|
|
};
|
|
|
|
|
2017-03-26 20:06:46 +00:00
|
|
|
enum eLinkStateFlags
|
|
|
|
{
|
2017-09-26 17:05:17 +00:00
|
|
|
ACTUAL_STATE_COMPUTE_LINKVELOCITY=1,
|
|
|
|
ACTUAL_STATE_COMPUTE_FORWARD_KINEMATICS=2,
|
2017-03-26 20:06:46 +00:00
|
|
|
};
|
|
|
|
|
2016-04-29 21:45:15 +00:00
|
|
|
///b3LinkState provides extra information such as the Cartesian world coordinates
|
|
|
|
///center of mass (COM) of the link, relative to the world reference frame.
|
|
|
|
///Orientation is a quaternion x,y,z,w
|
|
|
|
///Note: to compute the URDF link frame (which equals the joint frame at joint position 0)
|
|
|
|
///use URDF link frame = link COM frame * inertiaFrame.inverse()
|
2016-04-24 00:29:46 +00:00
|
|
|
struct b3LinkState
|
|
|
|
{
|
2017-01-12 05:39:22 +00:00
|
|
|
//m_worldPosition and m_worldOrientation of the Center Of Mass (COM)
|
2016-04-24 00:29:46 +00:00
|
|
|
double m_worldPosition[3];
|
|
|
|
double m_worldOrientation[4];
|
2016-04-29 21:45:15 +00:00
|
|
|
|
|
|
|
double m_localInertialPosition[3];
|
|
|
|
double m_localInertialOrientation[4];
|
2017-01-12 05:39:22 +00:00
|
|
|
|
|
|
|
///world position and orientation of the (URDF) link frame
|
|
|
|
double m_worldLinkFramePosition[3];
|
|
|
|
double m_worldLinkFrameOrientation[4];
|
2017-03-26 20:06:46 +00:00
|
|
|
|
|
|
|
double m_worldLinearVelocity[3]; //only valid when ACTUAL_STATE_COMPUTE_LINKVELOCITY is set (b3RequestActualStateCommandComputeLinkVelocity)
|
|
|
|
double m_worldAngularVelocity[3]; //only valid when ACTUAL_STATE_COMPUTE_LINKVELOCITY is set (b3RequestActualStateCommandComputeLinkVelocity)
|
|
|
|
|
2017-06-16 02:46:27 +00:00
|
|
|
double m_worldAABBMin[3];//world space bounding minium and maximum box corners.
|
|
|
|
double m_worldAABBMax[3];
|
2016-04-24 00:29:46 +00:00
|
|
|
};
|
|
|
|
|
2015-09-17 06:09:10 +00:00
|
|
|
//todo: discuss and decide about control mode and combinations
|
|
|
|
enum {
|
|
|
|
// POSITION_CONTROL=0,
|
|
|
|
CONTROL_MODE_VELOCITY=0,
|
|
|
|
CONTROL_MODE_TORQUE,
|
|
|
|
CONTROL_MODE_POSITION_VELOCITY_PD,
|
|
|
|
};
|
|
|
|
|
2016-06-27 01:18:30 +00:00
|
|
|
///flags for b3ApplyExternalTorque and b3ApplyExternalForce
|
|
|
|
enum EnumExternalForceFlags
|
|
|
|
{
|
|
|
|
EF_LINK_FRAME=1,
|
|
|
|
EF_WORLD_FRAME=2,
|
|
|
|
};
|
2016-05-18 06:57:19 +00:00
|
|
|
|
2016-07-13 01:16:13 +00:00
|
|
|
///flags to pick the renderer for synthetic camera
|
|
|
|
enum EnumRenderer
|
|
|
|
{
|
|
|
|
ER_TINY_RENDERER=(1<<16),
|
|
|
|
ER_BULLET_HARDWARE_OPENGL=(1<<17),
|
|
|
|
//ER_FIRE_RAYS=(1<<18),
|
|
|
|
};
|
|
|
|
|
2017-10-19 21:00:53 +00:00
|
|
|
///flags to pick the IK solver and other options
|
|
|
|
enum EnumCalculateInverseKinematicsFlags
|
|
|
|
{
|
|
|
|
IK_DLS=0,
|
|
|
|
IK_SDLS=1, //TODO: can add other IK solvers
|
|
|
|
IK_HAS_TARGET_POSITION=16,
|
|
|
|
IK_HAS_TARGET_ORIENTATION=32,
|
|
|
|
IK_HAS_NULL_SPACE_VELOCITY=64,
|
|
|
|
IK_HAS_JOINT_DAMPING=128,
|
|
|
|
//IK_HAS_CURRENT_JOINT_POSITIONS=256,//not used yet
|
|
|
|
};
|
|
|
|
|
2017-02-24 23:34:11 +00:00
|
|
|
enum b3ConfigureDebugVisualizerEnum
|
2017-02-22 01:36:54 +00:00
|
|
|
{
|
|
|
|
COV_ENABLE_GUI=1,
|
|
|
|
COV_ENABLE_SHADOWS,
|
|
|
|
COV_ENABLE_WIREFRAME,
|
2017-05-15 18:39:39 +00:00
|
|
|
COV_ENABLE_VR_TELEPORTING,
|
|
|
|
COV_ENABLE_VR_PICKING,
|
2017-05-16 19:19:03 +00:00
|
|
|
COV_ENABLE_VR_RENDER_CONTROLLERS,
|
|
|
|
COV_ENABLE_RENDERING,
|
|
|
|
COV_ENABLE_SYNC_RENDERING_INTERNAL,
|
2017-06-17 20:29:14 +00:00
|
|
|
COV_ENABLE_KEYBOARD_SHORTCUTS,
|
|
|
|
COV_ENABLE_MOUSE_PICKING,
|
2017-10-05 15:23:10 +00:00
|
|
|
COV_ENABLE_Y_AXIS_UP,
|
2017-10-06 20:46:24 +00:00
|
|
|
COV_ENABLE_TINY_RENDERER,
|
2017-11-17 21:33:27 +00:00
|
|
|
COV_ENABLE_RGB_BUFFER_PREVIEW,
|
|
|
|
COV_ENABLE_DEPTH_BUFFER_PREVIEW,
|
|
|
|
COV_ENABLE_SEGMENTATION_MARK_PREVIEW,
|
|
|
|
|
2017-02-22 01:36:54 +00:00
|
|
|
};
|
2017-02-24 23:34:11 +00:00
|
|
|
|
Improve debug text/line rendering, can be use to draw frames and text in local coordinate of an object / link.
example:
kuka = p.loadURDF("kuka_iiwa/model.urdf")
p.getNumJoints(kuka)
pybullet.addUserDebugLine([0,0,0],[0,0,0.1],[0,0,1],trackObjectUniqueId=2,trackLinkIndex=6)
pybullet.addUserDebugText("tip", [0,0,0.1],textColorRGB=[1,0,0],trackObjectUniqueId=2,trackLinkIndex=6)
Also allow to render text using a given orientation (instead of pointing to the camera), example:
pybullet.addUserDebugText("tip", [0,0,0.1],textColorRGB=[1,0,0],textOrientation=[0,0,0,1], trackObjectUniqueId=2,trackLinkIndex=6)
Add drawTexturedTriangleMesh, for drawing 3d text.
Expose readSingleInstanceTransformToCPU, to extract position/orientation from graphics index.
updateTexture: allow to not flip texels around up axis
2017-05-24 05:05:26 +00:00
|
|
|
enum b3AddUserDebugItemEnum
|
|
|
|
{
|
2017-10-11 05:11:32 +00:00
|
|
|
DEB_DEBUG_TEXT_ALWAYS_FACE_CAMERA=1,
|
Improve debug text/line rendering, can be use to draw frames and text in local coordinate of an object / link.
example:
kuka = p.loadURDF("kuka_iiwa/model.urdf")
p.getNumJoints(kuka)
pybullet.addUserDebugLine([0,0,0],[0,0,0.1],[0,0,1],trackObjectUniqueId=2,trackLinkIndex=6)
pybullet.addUserDebugText("tip", [0,0,0.1],textColorRGB=[1,0,0],trackObjectUniqueId=2,trackLinkIndex=6)
Also allow to render text using a given orientation (instead of pointing to the camera), example:
pybullet.addUserDebugText("tip", [0,0,0.1],textColorRGB=[1,0,0],textOrientation=[0,0,0,1], trackObjectUniqueId=2,trackLinkIndex=6)
Add drawTexturedTriangleMesh, for drawing 3d text.
Expose readSingleInstanceTransformToCPU, to extract position/orientation from graphics index.
updateTexture: allow to not flip texels around up axis
2017-05-24 05:05:26 +00:00
|
|
|
DEB_DEBUG_TEXT_USE_TRUE_TYPE_FONTS=2,
|
|
|
|
DEB_DEBUG_TEXT_HAS_TRACKING_OBJECT=4,
|
|
|
|
};
|
|
|
|
|
2017-02-24 23:34:11 +00:00
|
|
|
enum eCONNECT_METHOD {
|
|
|
|
eCONNECT_GUI = 1,
|
|
|
|
eCONNECT_DIRECT = 2,
|
|
|
|
eCONNECT_SHARED_MEMORY = 3,
|
|
|
|
eCONNECT_UDP = 4,
|
|
|
|
eCONNECT_TCP = 5,
|
2017-05-13 18:15:20 +00:00
|
|
|
eCONNECT_EXISTING_EXAMPLE_BROWSER=6,
|
2017-08-15 00:02:20 +00:00
|
|
|
eCONNECT_GUI_SERVER=7,
|
2017-02-24 23:34:11 +00:00
|
|
|
};
|
|
|
|
|
2017-03-27 15:30:20 +00:00
|
|
|
enum eURDF_Flags
|
|
|
|
{
|
|
|
|
URDF_USE_INERTIA_FROM_FILE=2,//sync with URDF2Bullet.h 'ConvertURDFFlags'
|
2017-04-04 19:47:34 +00:00
|
|
|
URDF_USE_SELF_COLLISION=8,//see CUF_USE_SELF_COLLISION
|
2017-05-10 22:01:25 +00:00
|
|
|
URDF_USE_SELF_COLLISION_EXCLUDE_PARENT=16,
|
|
|
|
URDF_USE_SELF_COLLISION_EXCLUDE_ALL_PARENTS=32,
|
2017-09-07 21:27:00 +00:00
|
|
|
URDF_RESERVED=64,
|
|
|
|
|
2017-03-27 15:30:20 +00:00
|
|
|
};
|
|
|
|
|
2017-06-03 17:57:56 +00:00
|
|
|
enum eUrdfGeomTypes //sync with UrdfParser UrdfGeomTypes
|
|
|
|
{
|
|
|
|
GEOM_SPHERE=2,
|
|
|
|
GEOM_BOX,
|
|
|
|
GEOM_CYLINDER,
|
|
|
|
GEOM_MESH,
|
|
|
|
GEOM_PLANE,
|
|
|
|
GEOM_CAPSULE, //non-standard URDF?
|
|
|
|
GEOM_UNKNOWN,
|
|
|
|
};
|
|
|
|
|
2017-06-19 17:14:26 +00:00
|
|
|
enum eUrdfCollisionFlags
|
|
|
|
{
|
|
|
|
GEOM_FORCE_CONCAVE_TRIMESH=1,
|
|
|
|
};
|
|
|
|
|
2017-10-08 01:50:23 +00:00
|
|
|
enum eUrdfVisualFlags
|
|
|
|
{
|
|
|
|
GEOM_VISUAL_HAS_RGBA_COLOR=1,
|
|
|
|
GEOM_VISUAL_HAS_SPECULAR_COLOR=2,
|
|
|
|
};
|
|
|
|
|
|
|
|
|
2017-08-31 02:41:15 +00:00
|
|
|
enum eStateLoggingFlags
|
|
|
|
{
|
|
|
|
STATE_LOG_JOINT_MOTOR_TORQUES=1,
|
|
|
|
STATE_LOG_JOINT_USER_TORQUES=2,
|
|
|
|
STATE_LOG_JOINT_TORQUES = STATE_LOG_JOINT_MOTOR_TORQUES+STATE_LOG_JOINT_USER_TORQUES,
|
|
|
|
};
|
2017-06-19 17:14:26 +00:00
|
|
|
|
2017-09-24 01:05:23 +00:00
|
|
|
#define B3_MAX_PLUGIN_ARG_SIZE 128
|
|
|
|
#define B3_MAX_PLUGIN_ARG_TEXT_LEN 1024
|
|
|
|
|
|
|
|
struct b3PluginArguments
|
|
|
|
{
|
|
|
|
char m_text[B3_MAX_PLUGIN_ARG_TEXT_LEN];
|
|
|
|
int m_numInts;
|
|
|
|
int m_ints[B3_MAX_PLUGIN_ARG_SIZE];
|
|
|
|
int m_numFloats;
|
2017-09-30 20:17:48 +00:00
|
|
|
double m_floats[B3_MAX_PLUGIN_ARG_SIZE];
|
2017-09-24 01:05:23 +00:00
|
|
|
};
|
2017-06-03 17:57:56 +00:00
|
|
|
|
2017-10-05 18:43:14 +00:00
|
|
|
struct b3PhysicsSimulationParameters
|
|
|
|
{
|
|
|
|
double m_deltaTime;
|
|
|
|
double m_gravityAcceleration[3];
|
|
|
|
int m_numSimulationSubSteps;
|
|
|
|
int m_numSolverIterations;
|
|
|
|
int m_useRealTimeSimulation;
|
|
|
|
int m_useSplitImpulse;
|
|
|
|
double m_splitImpulsePenetrationThreshold;
|
|
|
|
double m_contactBreakingThreshold;
|
|
|
|
int m_internalSimFlags;
|
|
|
|
double m_defaultContactERP;
|
|
|
|
int m_collisionFilterMode;
|
|
|
|
int m_enableFileCaching;
|
|
|
|
double m_restitutionVelocityThreshold;
|
|
|
|
double m_defaultNonContactERP;
|
|
|
|
double m_frictionERP;
|
2017-11-29 04:09:56 +00:00
|
|
|
int m_enableConeFriction;
|
2017-10-05 18:43:14 +00:00
|
|
|
};
|
|
|
|
|
2017-06-03 17:57:56 +00:00
|
|
|
|
2015-09-17 06:09:10 +00:00
|
|
|
#endif//SHARED_MEMORY_PUBLIC_H
|