1 #ifndef SHARED_MEMORY_COMMANDS_H 2 #define SHARED_MEMORY_COMMANDS_H 3 4 //this is a very experimental draft of commands. We will iterate on this API (commands, arguments etc) 5 6 #include "SharedMemoryPublic.h" 7 8 #ifdef __GNUC__ 9 #include <stdint.h> 10 typedef int32_t smInt32_t; 11 typedef int64_t smInt64_t; 12 typedef uint32_t smUint32_t; 13 typedef uint64_t smUint64_t; 14 #elif defined(_MSC_VER) 15 typedef __int32 smInt32_t; 16 typedef __int64 smInt64_t; 17 typedef unsigned __int32 smUint32_t; 18 typedef unsigned __int64 smUint64_t; 19 #else 20 typedef int smInt32_t; 21 typedef long long int smInt64_t; 22 typedef unsigned int smUint32_t; 23 typedef unsigned long long int smUint64_t; 24 #endif 25 26 #ifdef __APPLE__ 27 #define SHARED_MEMORY_MAX_STREAM_CHUNK_SIZE (1024 * 1024) 28 #else 29 #define SHARED_MEMORY_MAX_STREAM_CHUNK_SIZE (8 * 1024 * 1024) 30 #endif 31 32 #define SHARED_MEMORY_SERVER_TEST_C 33 #define MAX_DEGREE_OF_FREEDOM 128 34 #define MAX_NUM_SENSORS 256 35 #define MAX_URDF_FILENAME_LENGTH 1024 36 #define MAX_SDF_FILENAME_LENGTH 1024 37 #define MAX_FILENAME_LENGTH MAX_URDF_FILENAME_LENGTH 38 #define MAX_NUM_LINKS MAX_DEGREE_OF_FREEDOM 39 40 41 struct TmpFloat3 42 { 43 float m_x; 44 float m_y; 45 float m_z; 46 }; 47 48 #ifdef _WIN32 49 __inline 50 #else 51 inline 52 #endif 53 TmpFloat3 CreateTmpFloat3(float x,float y,float z)54 CreateTmpFloat3(float x, float y, float z) 55 { 56 TmpFloat3 tmp; 57 tmp.m_x = x; 58 tmp.m_y = y; 59 tmp.m_z = z; 60 return tmp; 61 } 62 63 enum EnumSdfArgsUpdateFlags 64 { 65 SDF_ARGS_FILE_NAME = 1, 66 }; 67 68 struct SdfArgs 69 { 70 char m_sdfFileName[MAX_URDF_FILENAME_LENGTH]; 71 int m_useMultiBody; 72 double m_globalScaling; 73 }; 74 75 struct FileArgs 76 { 77 char m_fileName[MAX_URDF_FILENAME_LENGTH]; 78 int m_stateId; 79 }; 80 81 enum EnumLoadStateArgsUpdateFlags 82 { 83 CMD_LOAD_STATE_HAS_STATEID = 1, 84 CMD_LOAD_STATE_HAS_FILENAME = 2, 85 }; 86 87 enum EnumUrdfArgsUpdateFlags 88 { 89 URDF_ARGS_FILE_NAME = 1, 90 URDF_ARGS_INITIAL_POSITION = 2, 91 URDF_ARGS_INITIAL_ORIENTATION = 4, 92 URDF_ARGS_USE_MULTIBODY = 8, 93 URDF_ARGS_USE_FIXED_BASE = 16, 94 URDF_ARGS_HAS_CUSTOM_URDF_FLAGS = 32, 95 URDF_ARGS_USE_GLOBAL_SCALING = 64, 96 }; 97 98 struct UrdfArgs 99 { 100 char m_urdfFileName[MAX_URDF_FILENAME_LENGTH]; 101 double m_initialPosition[3]; 102 double m_initialOrientation[4]; 103 int m_useMultiBody; 104 int m_useFixedBase; 105 int m_urdfFlags; 106 double m_globalScaling; 107 }; 108 109 struct MjcfArgs 110 { 111 char m_mjcfFileName[MAX_URDF_FILENAME_LENGTH]; 112 int m_useMultiBody; 113 int m_flags; 114 }; 115 116 struct b3SearchPathfArgs 117 { 118 char m_path[MAX_FILENAME_LENGTH]; 119 }; 120 121 enum CustomCommandEnum 122 { 123 CMD_CUSTOM_COMMAND_LOAD_PLUGIN = 1, 124 CMD_CUSTOM_COMMAND_UNLOAD_PLUGIN = 2, 125 CMD_CUSTOM_COMMAND_EXECUTE_PLUGIN_COMMAND = 4, 126 CMD_CUSTOM_COMMAND_LOAD_PLUGIN_POSTFIX = 8, 127 }; 128 129 struct b3CustomCommand 130 { 131 int m_pluginUniqueId; 132 b3PluginArguments m_arguments; 133 char m_pluginPath[MAX_FILENAME_LENGTH]; 134 char m_postFix[MAX_FILENAME_LENGTH]; 135 int m_startingReturnBytes; 136 }; 137 138 struct b3CustomCommandResultArgs 139 { 140 int m_pluginUniqueId; 141 int m_executeCommandResult; 142 int m_returnDataType; 143 int m_returnDataSizeInBytes; 144 int m_returnDataStart; 145 }; 146 147 struct BulletDataStreamArgs 148 { 149 char m_bulletFileName[MAX_FILENAME_LENGTH]; 150 int m_bodyUniqueId; 151 char m_bodyName[MAX_FILENAME_LENGTH]; 152 }; 153 154 enum EnumChangeDynamicsInfoFlags 155 { 156 CHANGE_DYNAMICS_INFO_SET_MASS = 1, 157 CHANGE_DYNAMICS_INFO_SET_COM = 2, 158 CHANGE_DYNAMICS_INFO_SET_LATERAL_FRICTION = 4, 159 CHANGE_DYNAMICS_INFO_SET_SPINNING_FRICTION = 8, 160 CHANGE_DYNAMICS_INFO_SET_ROLLING_FRICTION = 16, 161 CHANGE_DYNAMICS_INFO_SET_RESTITUTION = 32, 162 CHANGE_DYNAMICS_INFO_SET_LINEAR_DAMPING = 64, 163 CHANGE_DYNAMICS_INFO_SET_ANGULAR_DAMPING = 128, 164 CHANGE_DYNAMICS_INFO_SET_CONTACT_STIFFNESS_AND_DAMPING = 256, 165 CHANGE_DYNAMICS_INFO_SET_FRICTION_ANCHOR = 512, 166 CHANGE_DYNAMICS_INFO_SET_LOCAL_INERTIA_DIAGONAL = 1024, 167 CHANGE_DYNAMICS_INFO_SET_CCD_SWEPT_SPHERE_RADIUS = 2048, 168 CHANGE_DYNAMICS_INFO_SET_CONTACT_PROCESSING_THRESHOLD = 4096, 169 CHANGE_DYNAMICS_INFO_SET_ACTIVATION_STATE = 8192, 170 CHANGE_DYNAMICS_INFO_SET_JOINT_DAMPING = 16384, 171 CHANGE_DYNAMICS_INFO_SET_ANISOTROPIC_FRICTION = 32768, 172 CHANGE_DYNAMICS_INFO_SET_MAX_JOINT_VELOCITY = 1<<16, 173 CHANGE_DYNAMICS_INFO_SET_COLLISION_MARGIN = 1 << 17, 174 CHANGE_DYNAMICS_INFO_SET_JOINT_LIMITS = 1 << 18, 175 CHANGE_DYNAMICS_INFO_SET_JOINT_LIMIT_MAX_FORCE = 1 << 19, 176 CHANGE_DYNAMICS_INFO_SET_DYNAMIC_TYPE = 1 << 20, 177 CHANGE_DYNAMICS_INFO_SET_SLEEP_THRESHOLD = 1 << 21, 178 }; 179 180 struct ChangeDynamicsInfoArgs 181 { 182 int m_bodyUniqueId; 183 int m_linkIndex; 184 double m_mass; 185 double m_COM[3]; 186 double m_lateralFriction; 187 double m_spinningFriction; 188 double m_rollingFriction; 189 double m_restitution; 190 double m_linearDamping; 191 double m_angularDamping; 192 double m_contactStiffness; 193 double m_contactDamping; 194 double m_localInertiaDiagonal[3]; 195 int m_frictionAnchor; 196 double m_ccdSweptSphereRadius; 197 double m_contactProcessingThreshold; 198 int m_activationState; 199 double m_jointDamping; 200 double m_anisotropicFriction[3]; 201 double m_maxJointVelocity; 202 double m_collisionMargin; 203 204 double m_jointLowerLimit; 205 double m_jointUpperLimit; 206 double m_jointLimitForce; 207 208 int m_dynamicType; 209 210 double m_sleepThreshold; 211 212 }; 213 214 struct GetDynamicsInfoArgs 215 { 216 int m_bodyUniqueId; 217 int m_linkIndex; 218 }; 219 220 struct SetJointFeedbackArgs 221 { 222 int m_bodyUniqueId; 223 int m_linkId; 224 int m_isEnabled; 225 }; 226 227 enum EnumInitPoseFlags 228 { 229 INIT_POSE_HAS_INITIAL_POSITION = 1, 230 INIT_POSE_HAS_INITIAL_ORIENTATION = 2, 231 INIT_POSE_HAS_JOINT_STATE = 4, 232 INIT_POSE_HAS_BASE_LINEAR_VELOCITY = 8, 233 INIT_POSE_HAS_BASE_ANGULAR_VELOCITY = 16, 234 INIT_POSE_HAS_JOINT_VELOCITY = 32, 235 INIT_POSE_HAS_SCALING=64, 236 }; 237 238 ///InitPoseArgs is mainly to initialize (teleport) the robot in a particular position 239 ///No motors or controls are needed to initialize the pose. It is similar to 240 ///moving a robot to a starting place, while it is switched off. It is only called 241 ///at the start of a robot control session. All velocities and control forces are cleared to zero. 242 struct InitPoseArgs 243 { 244 int m_bodyUniqueId; 245 int m_hasInitialStateQ[MAX_DEGREE_OF_FREEDOM]; 246 double m_initialStateQ[MAX_DEGREE_OF_FREEDOM]; 247 int m_hasInitialStateQdot[MAX_DEGREE_OF_FREEDOM]; 248 double m_initialStateQdot[MAX_DEGREE_OF_FREEDOM]; 249 double m_scaling[3]; 250 }; 251 252 struct RequestDebugLinesArgs 253 { 254 int m_debugMode; 255 int m_startingLineIndex; 256 }; 257 258 struct RequestPixelDataArgs 259 { 260 float m_viewMatrix[16]; 261 float m_projectionMatrix[16]; 262 int m_startPixelIndex; 263 int m_pixelWidth; 264 int m_pixelHeight; 265 float m_lightDirection[3]; 266 float m_lightColor[3]; 267 float m_lightDistance; 268 float m_lightAmbientCoeff; 269 float m_lightDiffuseCoeff; 270 float m_lightSpecularCoeff; 271 int m_hasShadow; 272 int m_flags; 273 float m_projectiveTextureViewMatrix[16]; 274 float m_projectiveTextureProjectionMatrix[16]; 275 }; 276 277 enum EnumRequestPixelDataUpdateFlags 278 { 279 REQUEST_PIXEL_ARGS_HAS_CAMERA_MATRICES = 1, 280 REQUEST_PIXEL_ARGS_SET_PIXEL_WIDTH_HEIGHT = 2, 281 REQUEST_PIXEL_ARGS_SET_LIGHT_DIRECTION = 4, 282 REQUEST_PIXEL_ARGS_SET_LIGHT_COLOR = 8, 283 REQUEST_PIXEL_ARGS_SET_LIGHT_DISTANCE = 16, 284 REQUEST_PIXEL_ARGS_SET_SHADOW = 32, 285 REQUEST_PIXEL_ARGS_SET_AMBIENT_COEFF = 64, 286 REQUEST_PIXEL_ARGS_SET_DIFFUSE_COEFF = 128, 287 REQUEST_PIXEL_ARGS_SET_SPECULAR_COEFF = 256, 288 REQUEST_PIXEL_ARGS_HAS_FLAGS = 512, 289 REQUEST_PIXEL_ARGS_HAS_PROJECTIVE_TEXTURE_MATRICES = 1024, 290 291 //don't exceed (1<<15), because this enum is shared with EnumRenderer in SharedMemoryPublic.h 292 293 }; 294 295 enum EnumRequestContactDataUpdateFlags 296 { 297 CMD_REQUEST_CONTACT_POINT_HAS_QUERY_MODE = 1, 298 CMD_REQUEST_CONTACT_POINT_HAS_CLOSEST_DISTANCE_THRESHOLD = 2, 299 CMD_REQUEST_CONTACT_POINT_HAS_LINK_INDEX_A_FILTER = 4, 300 CMD_REQUEST_CONTACT_POINT_HAS_LINK_INDEX_B_FILTER = 8, 301 302 CMD_REQUEST_CONTACT_POINT_HAS_COLLISION_SHAPE_A = 16, 303 CMD_REQUEST_CONTACT_POINT_HAS_COLLISION_SHAPE_B = 32, 304 CMD_REQUEST_CONTACT_POINT_HAS_COLLISION_SHAPE_POSITION_A = 64, 305 CMD_REQUEST_CONTACT_POINT_HAS_COLLISION_SHAPE_POSITION_B = 128, 306 CMD_REQUEST_CONTACT_POINT_HAS_COLLISION_SHAPE_ORIENTATION_A = 256, 307 CMD_REQUEST_CONTACT_POINT_HAS_COLLISION_SHAPE_ORIENTATION_B = 512, 308 309 }; 310 311 struct RequestRaycastIntersections 312 { 313 // The number of threads that Bullet may use to perform the ray casts. 314 // 0: Let Bullet decide 315 // 1: Use a single thread (i.e. no multi-threading) 316 // 2 or more: Number of threads to use. 317 int m_numThreads; 318 int m_numCommandRays; 319 //m_numCommandRays command rays are stored in m_fromToRays 320 b3RayData m_fromToRays[MAX_RAY_INTERSECTION_BATCH_SIZE]; 321 322 int m_numStreamingRays; 323 //optional m_parentObjectUniqueId (-1 for unused) 324 int m_parentObjectUniqueId; 325 int m_parentLinkIndex; 326 int m_reportHitNumber; 327 int m_collisionFilterMask; 328 double m_fractionEpsilon; 329 //streaming ray data stored in shared memory streaming part. (size m_numStreamingRays ) 330 }; 331 332 struct SendRaycastHits 333 { 334 int m_numRaycastHits; 335 // Actual ray result data stored in shared memory streaming part. 336 }; 337 338 struct RequestContactDataArgs 339 { 340 int m_startingContactPointIndex; 341 int m_objectAIndexFilter; 342 int m_objectBIndexFilter; 343 int m_linkIndexAIndexFilter; 344 int m_linkIndexBIndexFilter; 345 double m_closestDistanceThreshold; 346 347 int m_collisionShapeA; 348 int m_collisionShapeB; 349 double m_collisionShapePositionA[3]; 350 double m_collisionShapePositionB[3]; 351 double m_collisionShapeOrientationA[4]; 352 double m_collisionShapeOrientationB[4]; 353 354 int m_mode; 355 }; 356 357 struct RequestOverlappingObjectsArgs 358 { 359 int m_startingOverlappingObjectIndex; 360 double m_aabbQueryMin[3]; 361 double m_aabbQueryMax[3]; 362 }; 363 364 struct RequestVisualShapeDataArgs 365 { 366 int m_bodyUniqueId; 367 int m_startingVisualShapeIndex; 368 }; 369 370 struct RequestCollisionShapeDataArgs 371 { 372 int m_bodyUniqueId; 373 int m_linkIndex; 374 }; 375 376 enum EnumUpdateVisualShapeData 377 { 378 CMD_UPDATE_VISUAL_SHAPE_TEXTURE = 1, 379 CMD_UPDATE_VISUAL_SHAPE_RGBA_COLOR = 2, 380 CMD_UPDATE_VISUAL_SHAPE_SPECULAR_COLOR = 4, 381 CMD_UPDATE_VISUAL_SHAPE_FLAGS = 8, 382 }; 383 384 385 386 struct UpdateVisualShapeDataArgs 387 { 388 int m_bodyUniqueId; 389 int m_jointIndex; 390 int m_shapeIndex; 391 int m_textureUniqueId; 392 double m_rgbaColor[4]; 393 double m_specularColor[3]; 394 int m_flags; 395 }; 396 397 struct LoadTextureArgs 398 { 399 char m_textureFileName[MAX_FILENAME_LENGTH]; 400 }; 401 402 struct b3LoadTextureResultArgs 403 { 404 int m_textureUniqueId; 405 }; 406 407 struct SendVisualShapeDataArgs 408 { 409 int m_bodyUniqueId; 410 int m_startingVisualShapeIndex; 411 int m_numVisualShapesCopied; 412 int m_numRemainingVisualShapes; 413 }; 414 415 struct SendCollisionShapeDataArgs 416 { 417 int m_bodyUniqueId; 418 int m_linkIndex; 419 int m_numCollisionShapes; 420 }; 421 422 struct SendDebugLinesArgs 423 { 424 int m_startingLineIndex; 425 int m_numDebugLines; 426 int m_numRemainingDebugLines; 427 }; 428 429 struct SendPixelDataArgs 430 { 431 int m_imageWidth; 432 int m_imageHeight; 433 434 int m_startingPixelIndex; 435 int m_numPixelsCopied; 436 int m_numRemainingPixels; 437 }; 438 439 struct PickBodyArgs 440 { 441 double m_rayFromWorld[3]; 442 double m_rayToWorld[3]; 443 }; 444 445 ///Controlling a robot involves sending the desired state to its joint motor controllers. 446 ///The control mode determines the state variables used for motor control. 447 struct SendDesiredStateArgs 448 { 449 int m_bodyUniqueId; 450 int m_controlMode; 451 452 //PD parameters in case m_controlMode == CONTROL_MODE_POSITION_VELOCITY_PD 453 double m_Kp[MAX_DEGREE_OF_FREEDOM]; //indexed by degree of freedom, 6 for base, and then the dofs for each link 454 double m_Kd[MAX_DEGREE_OF_FREEDOM]; //indexed by degree of freedom, 6 for base, and then the dofs for each link 455 double m_rhsClamp[MAX_DEGREE_OF_FREEDOM]; 456 457 int m_hasDesiredStateFlags[MAX_DEGREE_OF_FREEDOM]; 458 459 //desired state is only written by the client, read-only access by server is expected 460 461 //m_desiredStateQ is indexed by position variables, 462 //starting with 3 base position variables, 4 base orientation variables (quaternion), then link position variables 463 double m_desiredStateQ[MAX_DEGREE_OF_FREEDOM]; 464 465 //m_desiredStateQdot is index by velocity degrees of freedom, 3 linear and 3 angular variables for the base and then link velocity variables 466 double m_desiredStateQdot[MAX_DEGREE_OF_FREEDOM]; 467 468 //m_desiredStateForceTorque is either the actual applied force/torque (in CONTROL_MODE_TORQUE) or 469 //or the maximum applied force/torque for the PD/motor/constraint to reach the desired velocity in CONTROL_MODE_VELOCITY and CONTROL_MODE_POSITION_VELOCITY_PD mode 470 //indexed by degree of freedom, 6 dof base, and then dofs for each link 471 double m_desiredStateForceTorque[MAX_DEGREE_OF_FREEDOM]; 472 473 double m_damping[MAX_DEGREE_OF_FREEDOM]; 474 }; 475 476 enum EnumSimDesiredStateUpdateFlags 477 { 478 SIM_DESIRED_STATE_HAS_Q = 1, 479 SIM_DESIRED_STATE_HAS_QDOT = 2, 480 SIM_DESIRED_STATE_HAS_KD = 4, 481 SIM_DESIRED_STATE_HAS_KP = 8, 482 SIM_DESIRED_STATE_HAS_MAX_FORCE = 16, 483 SIM_DESIRED_STATE_HAS_RHS_CLAMP = 32, 484 SIM_DESIRED_STATE_HAS_DAMPING = 64, 485 }; 486 487 enum EnumSimParamUpdateFlags 488 { 489 SIM_PARAM_UPDATE_DELTA_TIME = 1, 490 SIM_PARAM_UPDATE_GRAVITY = 1<<1, 491 SIM_PARAM_UPDATE_NUM_SOLVER_ITERATIONS = 1<<2, 492 SIM_PARAM_UPDATE_NUM_SIMULATION_SUB_STEPS = 1<<3, 493 SIM_PARAM_UPDATE_REAL_TIME_SIMULATION = 1<<4, 494 SIM_PARAM_UPDATE_DEFAULT_CONTACT_ERP = 1<<5, 495 SIM_PARAM_UPDATE_INTERNAL_SIMULATION_FLAGS = 1<<6, 496 SIM_PARAM_UPDATE_USE_SPLIT_IMPULSE = 1<<7, 497 SIM_PARAM_UPDATE_SPLIT_IMPULSE_PENETRATION_THRESHOLD = 1<<8, 498 SIM_PARAM_UPDATE_COLLISION_FILTER_MODE = 1 << 9, 499 SIM_PARAM_UPDATE_CONTACT_BREAKING_THRESHOLD = 1 << 10, 500 SIM_PARAM_ENABLE_CONE_FRICTION = 1 << 11, 501 SIM_PARAM_ENABLE_FILE_CACHING = 1 << 12, 502 SIM_PARAM_UPDATE_RESTITUTION_VELOCITY_THRESHOLD = 1 << 13, 503 SIM_PARAM_UPDATE_DEFAULT_NON_CONTACT_ERP = 1 << 14, 504 SIM_PARAM_UPDATE_DEFAULT_FRICTION_ERP = 1 << 15, 505 SIM_PARAM_UPDATE_DETERMINISTIC_OVERLAPPING_PAIRS = 1 << 16, 506 SIM_PARAM_UPDATE_CCD_ALLOWED_PENETRATION = 1 << 17, 507 SIM_PARAM_UPDATE_JOINT_FEEDBACK_MODE = 1 << 18, 508 SIM_PARAM_UPDATE_DEFAULT_GLOBAL_CFM = 1 << 19, 509 SIM_PARAM_UPDATE_DEFAULT_FRICTION_CFM = 1 << 20, 510 SIM_PARAM_UPDATE_SOLVER_RESIDULAL_THRESHOLD = 1 << 21, 511 SIM_PARAM_UPDATE_CONTACT_SLOP = 1 << 22, 512 SIM_PARAM_ENABLE_SAT = 1 << 23, 513 SIM_PARAM_CONSTRAINT_SOLVER_TYPE = 1 << 24, 514 SIM_PARAM_CONSTRAINT_MIN_SOLVER_ISLAND_SIZE = 1 << 25, 515 SIM_PARAM_REPORT_CONSTRAINT_SOLVER_ANALYTICS = 1 << 26, 516 SIM_PARAM_UPDATE_WARM_STARTING_FACTOR = 1 << 27, 517 SIM_PARAM_UPDATE_ARTICULATED_WARM_STARTING_FACTOR = 1 << 28, 518 SIM_PARAM_UPDATE_SPARSE_SDF = 1 << 29, 519 SIM_PARAM_UPDATE_NUM_NONCONTACT_INNER_ITERATIONS = 1 << 30, 520 }; 521 522 enum EnumLoadSoftBodyUpdateFlags 523 { 524 LOAD_SOFT_BODY_FILE_NAME = 1, 525 LOAD_SOFT_BODY_UPDATE_SCALE = 1<<1, 526 LOAD_SOFT_BODY_UPDATE_MASS = 1<<2, 527 LOAD_SOFT_BODY_UPDATE_COLLISION_MARGIN = 1<<3, 528 LOAD_SOFT_BODY_INITIAL_POSITION = 1<<4, 529 LOAD_SOFT_BODY_INITIAL_ORIENTATION = 1<<5, 530 LOAD_SOFT_BODY_ADD_COROTATED_FORCE = 1<<6, 531 LOAD_SOFT_BODY_ADD_MASS_SPRING_FORCE = 1<<7, 532 LOAD_SOFT_BODY_ADD_GRAVITY_FORCE = 1<<8, 533 LOAD_SOFT_BODY_SET_COLLISION_HARDNESS = 1<<9, 534 LOAD_SOFT_BODY_SET_FRICTION_COEFFICIENT = 1<<10, 535 LOAD_SOFT_BODY_ADD_BENDING_SPRINGS = 1<<11, 536 LOAD_SOFT_BODY_ADD_NEOHOOKEAN_FORCE = 1<<12, 537 LOAD_SOFT_BODY_USE_SELF_COLLISION = 1<<13, 538 LOAD_SOFT_BODY_USE_FACE_CONTACT = 1<<14, 539 LOAD_SOFT_BODY_SIM_MESH = 1<<15, 540 LOAD_SOFT_BODY_SET_REPULSION_STIFFNESS = 1<<16, 541 LOAD_SOFT_BODY_SET_DAMPING_SPRING_MODE = 1<<17, 542 LOAD_SOFT_BODY_SET_GRAVITY_FACTOR = 1<<18, 543 }; 544 545 enum EnumSimParamInternalSimFlags 546 { 547 SIM_PARAM_INTERNAL_CREATE_ROBOT_ASSETS = 1, 548 }; 549 550 ///Controlling a robot involves sending the desired state to its joint motor controllers. 551 ///The control mode determines the state variables used for motor control. 552 553 struct LoadSoftBodyArgs 554 { 555 char m_fileName[MAX_FILENAME_LENGTH]; 556 double m_scale; 557 double m_mass; 558 double m_collisionMargin; 559 double m_initialPosition[3]; 560 double m_initialOrientation[4]; 561 double m_springElasticStiffness; 562 double m_springDampingStiffness; 563 int m_dampAllDirections; 564 double m_springBendingStiffness; 565 double m_corotatedMu; 566 double m_corotatedLambda; 567 int m_useBendingSprings; 568 double m_collisionHardness; 569 int m_useSelfCollision; 570 double m_frictionCoeff; 571 double m_NeoHookeanMu; 572 double m_NeoHookeanLambda; 573 double m_NeoHookeanDamping; 574 int m_useFaceContact; 575 char m_simFileName[MAX_FILENAME_LENGTH]; 576 double m_repulsionStiffness; 577 double m_gravFactor; 578 }; 579 580 struct b3LoadSoftBodyResultArgs 581 { 582 int m_objectUniqueId; 583 }; 584 585 struct RequestActualStateArgs 586 { 587 int m_bodyUniqueId; 588 }; 589 590 struct SendActualStateArgs 591 { 592 int m_bodyUniqueId; 593 int m_numLinks; 594 int m_numDegreeOfFreedomQ; 595 int m_numDegreeOfFreedomU; 596 597 double m_rootLocalInertialFrame[7]; 598 struct SendActualStateSharedMemoryStorage* m_stateDetails; 599 600 }; 601 602 struct SendActualStateSharedMemoryStorage 603 { 604 //actual state is only written by the server, read-only access by client is expected 605 double m_actualStateQ[MAX_DEGREE_OF_FREEDOM]; 606 double m_actualStateQdot[MAX_DEGREE_OF_FREEDOM]; 607 608 //measured 6DOF force/torque sensors: force[x,y,z] and torque[x,y,z] 609 double m_jointReactionForces[6 * MAX_DEGREE_OF_FREEDOM]; 610 611 double m_jointMotorForce[MAX_DEGREE_OF_FREEDOM]; 612 double m_jointMotorForceMultiDof[MAX_DEGREE_OF_FREEDOM]; 613 614 double m_linkState[7 * MAX_NUM_LINKS]; 615 double m_linkWorldVelocities[6 * MAX_NUM_LINKS]; //linear velocity and angular velocity in world space (x/y/z each). 616 double m_linkLocalInertialFrames[7 * MAX_NUM_LINKS]; 617 }; 618 619 struct b3SendCollisionInfoArgs 620 { 621 int m_numLinks; 622 double m_rootWorldAABBMin[3]; 623 double m_rootWorldAABBMax[3]; 624 625 double m_linkWorldAABBsMin[3 * MAX_NUM_LINKS]; 626 double m_linkWorldAABBsMax[3 * MAX_NUM_LINKS]; 627 }; 628 629 struct b3RequestCollisionInfoArgs 630 { 631 int m_bodyUniqueId; 632 }; 633 634 enum EnumSensorTypes 635 { 636 SENSOR_FORCE_TORQUE = 1, 637 SENSOR_IMU = 2, 638 }; 639 640 struct CreateSensorArgs 641 { 642 int m_bodyUniqueId; 643 int m_numJointSensorChanges; 644 int m_sensorType[MAX_DEGREE_OF_FREEDOM]; 645 646 ///todo: clean up the duplication, make sure no-one else is using those members directly (use C-API header instead) 647 int m_jointIndex[MAX_DEGREE_OF_FREEDOM]; 648 int m_enableJointForceSensor[MAX_DEGREE_OF_FREEDOM]; 649 650 int m_linkIndex[MAX_DEGREE_OF_FREEDOM]; 651 int m_enableSensor[MAX_DEGREE_OF_FREEDOM]; 652 }; 653 654 typedef struct SharedMemoryCommand SharedMemoryCommand_t; 655 656 enum EnumBoxShapeFlags 657 { 658 BOX_SHAPE_HAS_INITIAL_POSITION = 1, 659 BOX_SHAPE_HAS_INITIAL_ORIENTATION = 2, 660 BOX_SHAPE_HAS_HALF_EXTENTS = 4, 661 BOX_SHAPE_HAS_MASS = 8, 662 BOX_SHAPE_HAS_COLLISION_SHAPE_TYPE = 16, 663 BOX_SHAPE_HAS_COLOR = 32, 664 }; 665 ///This command will be replaced to allow arbitrary collision shape types 666 struct CreateBoxShapeArgs 667 { 668 double m_halfExtentsX; 669 double m_halfExtentsY; 670 double m_halfExtentsZ; 671 672 double m_mass; 673 int m_collisionShapeType; //see SharedMemoryPublic.h 674 675 double m_initialPosition[3]; 676 double m_initialOrientation[4]; 677 double m_colorRGBA[4]; 678 }; 679 680 struct b3ObjectArgs 681 { 682 int m_numBodies; 683 int m_bodyUniqueIds[MAX_SDF_BODIES]; 684 int m_numUserConstraints; 685 int m_userConstraintUniqueIds[MAX_SDF_BODIES]; 686 int m_numUserCollisionShapes; 687 int m_userCollisionShapes[MAX_SDF_BODIES]; 688 }; 689 690 struct b3Profile 691 { 692 char m_name[MAX_FILENAME_LENGTH]; 693 int m_durationInMicroSeconds; 694 int m_type; 695 }; 696 697 struct SdfLoadedArgs 698 { 699 int m_numBodies; 700 int m_bodyUniqueIds[MAX_SDF_BODIES]; 701 int m_numUserConstraints; 702 int m_userConstraintUniqueIds[MAX_SDF_BODIES]; 703 704 ///@todo(erwincoumans) load cameras, lights etc 705 //int m_numCameras; 706 //int m_numLights; 707 }; 708 709 struct SdfRequestInfoArgs 710 { 711 int m_bodyUniqueId; 712 }; 713 714 ///flags for b3ApplyExternalTorque and b3ApplyExternalForce 715 enum EnumExternalForcePrivateFlags 716 { 717 // EF_LINK_FRAME=1, 718 // EF_WORLD_FRAME=2, 719 EF_TORQUE = 4, 720 EF_FORCE = 8, 721 }; 722 723 struct ExternalForceArgs 724 { 725 int m_numForcesAndTorques; 726 int m_bodyUniqueIds[MAX_SDF_BODIES]; 727 int m_linkIds[MAX_SDF_BODIES]; 728 double m_forcesAndTorques[3 * MAX_SDF_BODIES]; 729 double m_positions[3 * MAX_SDF_BODIES]; 730 int m_forceFlags[MAX_SDF_BODIES]; 731 }; 732 733 enum EnumSdfRequestInfoFlags 734 { 735 SDF_REQUEST_INFO_BODY = 1, 736 //SDF_REQUEST_INFO_CAMERA=2, 737 }; 738 739 struct CalculateInverseDynamicsArgs 740 { 741 int m_bodyUniqueId; 742 int m_dofCountQ; 743 int m_dofCountQdot; 744 double m_jointPositionsQ[MAX_DEGREE_OF_FREEDOM]; 745 double m_jointVelocitiesQdot[MAX_DEGREE_OF_FREEDOM]; 746 double m_jointAccelerations[MAX_DEGREE_OF_FREEDOM]; 747 int m_flags; 748 }; 749 750 struct CalculateInverseDynamicsResultArgs 751 { 752 int m_bodyUniqueId; 753 int m_dofCount; 754 double m_jointForces[MAX_DEGREE_OF_FREEDOM]; 755 }; 756 757 struct CalculateJacobianArgs 758 { 759 int m_bodyUniqueId; 760 int m_linkIndex; 761 double m_localPosition[3]; 762 double m_jointPositionsQ[MAX_DEGREE_OF_FREEDOM]; 763 double m_jointVelocitiesQdot[MAX_DEGREE_OF_FREEDOM]; 764 double m_jointAccelerations[MAX_DEGREE_OF_FREEDOM]; 765 }; 766 767 struct CalculateJacobianResultArgs 768 { 769 int m_dofCount; 770 double m_linearJacobian[3 * MAX_DEGREE_OF_FREEDOM]; 771 double m_angularJacobian[3 * MAX_DEGREE_OF_FREEDOM]; 772 }; 773 774 struct CalculateMassMatrixArgs 775 { 776 int m_bodyUniqueId; 777 double m_jointPositionsQ[MAX_DEGREE_OF_FREEDOM]; 778 int m_dofCountQ; 779 int m_flags; 780 }; 781 782 struct CalculateMassMatrixResultArgs 783 { 784 int m_dofCount; 785 }; 786 787 enum b3EnumCollisionFilterFlags 788 { 789 B3_COLLISION_FILTER_PAIR = 1, 790 B3_COLLISION_FILTER_GROUP_MASK = 2, 791 }; 792 793 struct b3CollisionFilterArgs 794 { 795 int m_bodyUniqueIdA; 796 int m_bodyUniqueIdB; 797 int m_linkIndexA; 798 int m_linkIndexB; 799 int m_enableCollision; 800 int m_collisionFilterGroup; 801 int m_collisionFilterMask; 802 }; 803 804 struct CalculateInverseKinematicsArgs 805 { 806 int m_bodyUniqueId; 807 // double m_jointPositionsQ[MAX_DEGREE_OF_FREEDOM]; 808 double m_targetPositions[MAX_DEGREE_OF_FREEDOM*3]; 809 int m_numEndEffectorLinkIndices; 810 double m_targetOrientation[MAX_DEGREE_OF_FREEDOM*4]; //orientation represented as quaternion, x,y,z,w 811 int m_endEffectorLinkIndices[MAX_DEGREE_OF_FREEDOM]; 812 double m_lowerLimit[MAX_DEGREE_OF_FREEDOM]; 813 double m_upperLimit[MAX_DEGREE_OF_FREEDOM]; 814 double m_jointRange[MAX_DEGREE_OF_FREEDOM]; 815 double m_restPose[MAX_DEGREE_OF_FREEDOM]; 816 double m_jointDamping[MAX_DEGREE_OF_FREEDOM]; 817 double m_currentPositions[MAX_DEGREE_OF_FREEDOM]; 818 int m_maxNumIterations; 819 double m_residualThreshold; 820 }; 821 822 struct CalculateInverseKinematicsResultArgs 823 { 824 int m_bodyUniqueId; 825 int m_dofCount; 826 double m_jointPositions[MAX_DEGREE_OF_FREEDOM]; 827 }; 828 829 830 enum EnumBodyChangeFlags 831 { 832 BODY_DELETE_FLAG = 1, 833 }; 834 835 enum EnumUserDebugDrawFlags 836 { 837 USER_DEBUG_HAS_LINE = 1, 838 USER_DEBUG_HAS_TEXT = 2, 839 USER_DEBUG_REMOVE_ONE_ITEM = 4, 840 USER_DEBUG_REMOVE_ALL = 8, 841 USER_DEBUG_SET_CUSTOM_OBJECT_COLOR = 16, 842 USER_DEBUG_REMOVE_CUSTOM_OBJECT_COLOR = 32, 843 USER_DEBUG_ADD_PARAMETER = 64, 844 USER_DEBUG_READ_PARAMETER = 128, 845 USER_DEBUG_HAS_OPTION_FLAGS = 256, 846 USER_DEBUG_HAS_TEXT_ORIENTATION = 512, 847 USER_DEBUG_HAS_PARENT_OBJECT = 1024, 848 USER_DEBUG_HAS_REPLACE_ITEM_UNIQUE_ID = 2048, 849 USER_DEBUG_REMOVE_ALL_PARAMETERS = 4096, 850 }; 851 852 struct UserDebugDrawArgs 853 { 854 double m_debugLineFromXYZ[3]; 855 double m_debugLineToXYZ[3]; 856 double m_debugLineColorRGB[3]; 857 double m_lineWidth; 858 859 double m_lifeTime; 860 int m_itemUniqueId; 861 862 char m_text[MAX_FILENAME_LENGTH]; 863 double m_textPositionXYZ[3]; 864 double m_textOrientation[4]; 865 int m_parentObjectUniqueId; 866 int m_parentLinkIndex; 867 double m_textColorRGB[3]; 868 double m_textSize; 869 int m_optionFlags; 870 int m_replaceItemUniqueId; 871 872 double m_rangeMin; 873 double m_rangeMax; 874 double m_startValue; 875 876 double m_objectDebugColorRGB[3]; 877 int m_objectUniqueId; 878 int m_linkIndex; 879 }; 880 881 struct UserDebugDrawResultArgs 882 { 883 int m_debugItemUniqueId; 884 double m_parameterValue; 885 }; 886 887 struct SendVREvents 888 { 889 int m_numVRControllerEvents; 890 b3VRControllerEvent m_controllerEvents[MAX_VR_CONTROLLERS]; 891 }; 892 893 struct SendKeyboardEvents 894 { 895 int m_numKeyboardEvents; 896 b3KeyboardEvent m_keyboardEvents[MAX_KEYBOARD_EVENTS]; 897 }; 898 899 struct SendMouseEvents 900 { 901 int m_numMouseEvents; 902 b3MouseEvent m_mouseEvents[MAX_MOUSE_EVENTS]; 903 }; 904 905 enum eVRCameraEnums 906 { 907 VR_CAMERA_ROOT_POSITION = 1, 908 VR_CAMERA_ROOT_ORIENTATION = 2, 909 VR_CAMERA_ROOT_TRACKING_OBJECT = 4, 910 VR_CAMERA_FLAG = 8, 911 }; 912 913 enum eStateLoggingEnums 914 { 915 STATE_LOGGING_START_LOG = 1, 916 STATE_LOGGING_STOP_LOG = 2, 917 STATE_LOGGING_FILTER_OBJECT_UNIQUE_ID = 4, 918 STATE_LOGGING_MAX_LOG_DOF = 8, 919 STATE_LOGGING_FILTER_LINK_INDEX_A = 16, 920 STATE_LOGGING_FILTER_LINK_INDEX_B = 32, 921 STATE_LOGGING_FILTER_BODY_UNIQUE_ID_A = 64, 922 STATE_LOGGING_FILTER_BODY_UNIQUE_ID_B = 128, 923 STATE_LOGGING_FILTER_DEVICE_TYPE = 256, 924 STATE_LOGGING_LOG_FLAGS = 512 925 }; 926 927 struct VRCameraState 928 { 929 double m_rootPosition[3]; 930 double m_rootOrientation[4]; 931 int m_trackingObjectUniqueId; 932 int m_trackingObjectFlag; 933 }; 934 935 struct StateLoggingRequest 936 { 937 char m_fileName[MAX_FILENAME_LENGTH]; 938 int m_logType; //Minitaur, generic robot, VR states, contact points 939 int m_numBodyUniqueIds; ////only if STATE_LOGGING_FILTER_OBJECT_UNIQUE_ID flag is set 940 int m_bodyUniqueIds[MAX_SDF_BODIES]; 941 int m_loggingUniqueId; 942 int m_maxLogDof; 943 int m_linkIndexA; // only if STATE_LOGGING_FILTER_LINK_INDEX_A flag is set 944 int m_linkIndexB; // only if STATE_LOGGING_FILTER_LINK_INDEX_B flag is set 945 int m_bodyUniqueIdA; // only if STATE_LOGGING_FILTER_BODY_UNIQUE_ID_A flag is set 946 int m_bodyUniqueIdB; // only if STATE_LOGGING_FILTER_BODY_UNIQUE_ID_B flag is set 947 int m_deviceFilterType; //user to select (filter) which VR devices to log 948 int m_logFlags; 949 }; 950 951 struct StateLoggingResultArgs 952 { 953 int m_loggingUniqueId; 954 }; 955 956 enum InternalOpenGLVisualizerUpdateFlags 957 { 958 COV_SET_CAMERA_VIEW_MATRIX = 1, 959 COV_SET_FLAGS = 2, 960 COV_SET_LIGHT_POSITION = 4, 961 COV_SET_SHADOWMAP_RESOLUTION = 8, 962 COV_SET_SHADOWMAP_WORLD_SIZE = 16, 963 COV_SET_REMOTE_SYNC_TRANSFORM_INTERVAL = 32, 964 COV_SET_SHADOWMAP_INTENSITY = 64, 965 COV_SET_RGB_BACKGROUND = 128, 966 }; 967 968 struct ConfigureOpenGLVisualizerRequest 969 { 970 double m_cameraDistance; 971 double m_cameraPitch; 972 double m_cameraYaw; 973 double m_cameraTargetPosition[3]; 974 double m_lightPosition[3]; 975 int m_shadowMapResolution; 976 int m_shadowMapWorldSize; 977 double m_remoteSyncTransformInterval; 978 int m_setFlag; 979 int m_setEnabled; 980 double m_shadowMapIntensity; 981 double m_rgbBackground[3]; 982 }; 983 984 enum 985 { 986 URDF_GEOM_HAS_RADIUS = 1, 987 }; 988 989 struct b3CreateUserShapeData 990 { 991 int m_type; //see UrdfGeomTypes 992 993 int m_hasChildTransform; 994 double m_childPosition[3]; 995 double m_childOrientation[4]; 996 997 double m_sphereRadius; 998 double m_boxHalfExtents[3]; 999 double m_capsuleRadius; 1000 double m_capsuleHeight; 1001 int m_hasFromTo; 1002 double m_capsuleFrom[3]; 1003 double m_capsuleTo[3]; 1004 double m_planeNormal[3]; 1005 double m_planeConstant; 1006 1007 int m_meshFileType; 1008 char m_meshFileName[VISUAL_SHAPE_MAX_PATH_LEN]; 1009 double m_meshScale[3]; 1010 int m_collisionFlags; 1011 int m_visualFlags; 1012 int m_numVertices; 1013 int m_numIndices; 1014 int m_numUVs; 1015 int m_numNormals; 1016 double m_heightfieldTextureScaling; 1017 int m_numHeightfieldRows; 1018 int m_numHeightfieldColumns; 1019 double m_rgbaColor[4]; 1020 double m_specularColor[3]; 1021 int m_replaceHeightfieldIndex; 1022 }; 1023 1024 #define MAX_COMPOUND_COLLISION_SHAPES 16 1025 1026 struct b3CreateUserShapeArgs 1027 { 1028 int m_numUserShapes; 1029 b3CreateUserShapeData m_shapes[MAX_COMPOUND_COLLISION_SHAPES]; 1030 }; 1031 1032 1033 1034 struct b3CreateUserShapeResultArgs 1035 { 1036 int m_userShapeUniqueId; 1037 }; 1038 1039 #define MAX_CREATE_MULTI_BODY_LINKS MAX_DEGREE_OF_FREEDOM 1040 enum eCreateMultiBodyEnum 1041 { 1042 MULTI_BODY_HAS_BASE = 1, 1043 MULT_BODY_USE_MAXIMAL_COORDINATES = 2, 1044 MULT_BODY_HAS_FLAGS = 4, 1045 }; 1046 struct b3CreateMultiBodyArgs 1047 { 1048 char m_bodyName[1024]; 1049 int m_baseLinkIndex; 1050 1051 double m_linkPositions[3 * MAX_CREATE_MULTI_BODY_LINKS]; 1052 double m_linkOrientations[4 * MAX_CREATE_MULTI_BODY_LINKS]; 1053 1054 int m_numLinks; 1055 double m_linkMasses[MAX_CREATE_MULTI_BODY_LINKS]; 1056 double m_linkInertias[MAX_CREATE_MULTI_BODY_LINKS * 3]; 1057 1058 double m_linkInertialFramePositions[MAX_CREATE_MULTI_BODY_LINKS * 3]; 1059 double m_linkInertialFrameOrientations[MAX_CREATE_MULTI_BODY_LINKS * 4]; 1060 1061 int m_linkCollisionShapeUniqueIds[MAX_CREATE_MULTI_BODY_LINKS]; 1062 int m_linkVisualShapeUniqueIds[MAX_CREATE_MULTI_BODY_LINKS]; 1063 int m_linkParentIndices[MAX_CREATE_MULTI_BODY_LINKS]; 1064 int m_linkJointTypes[MAX_CREATE_MULTI_BODY_LINKS]; 1065 double m_linkJointAxis[3 * MAX_CREATE_MULTI_BODY_LINKS]; 1066 int m_flags; 1067 int m_numBatchObjects; 1068 1069 }; 1070 1071 struct b3CreateMultiBodyResultArgs 1072 { 1073 int m_bodyUniqueId; 1074 }; 1075 1076 struct b3ChangeTextureArgs 1077 { 1078 int m_textureUniqueId; 1079 int m_width; 1080 int m_height; 1081 }; 1082 1083 struct b3StateSerializationArguments 1084 { 1085 char m_fileName[MAX_URDF_FILENAME_LENGTH]; 1086 int m_stateId; 1087 }; 1088 1089 struct SyncUserDataRequestArgs 1090 { 1091 // The number of bodies for which we'd like to sync the user data of. When 0, all bodies are synced. 1092 int m_numRequestedBodies; 1093 // The body IDs for which we'd like to sync the user data of. 1094 int m_requestedBodyIds[MAX_REQUESTED_BODIES_LENGTH]; 1095 }; 1096 1097 struct SyncUserDataArgs 1098 { 1099 // User data identifiers stored in m_bulletStreamDataServerToClientRefactor 1100 // as as array of integers. 1101 int m_numUserDataIdentifiers; 1102 // Whether the client should clear its user data cache. 1103 bool m_clearCachedUserDataEntries; 1104 }; 1105 1106 struct UserDataRequestArgs 1107 { 1108 int m_userDataId; 1109 }; 1110 1111 struct UserDataResponseArgs 1112 { 1113 int m_userDataId; 1114 int m_bodyUniqueId; 1115 int m_linkIndex; 1116 int m_visualShapeIndex; 1117 int m_valueType; 1118 int m_valueLength; 1119 char m_key[MAX_USER_DATA_KEY_LENGTH]; 1120 // Value data stored in m_bulletStreamDataServerToClientRefactor. 1121 }; 1122 1123 struct AddUserDataRequestArgs 1124 { 1125 int m_bodyUniqueId; 1126 int m_linkIndex; 1127 int m_visualShapeIndex; 1128 int m_valueType; 1129 int m_valueLength; 1130 char m_key[MAX_USER_DATA_KEY_LENGTH]; 1131 // Value data stored in m_bulletStreamDataServerToClientRefactor. 1132 }; 1133 1134 struct b3RequestMeshDataArgs 1135 { 1136 int m_bodyUniqueId; 1137 int m_linkIndex; 1138 int m_startingVertex; 1139 int m_collisionShapeIndex; 1140 int m_flags; 1141 }; 1142 1143 struct b3ResetMeshDataArgs 1144 { 1145 int m_bodyUniqueId; 1146 int m_numVertices; 1147 int m_flags; 1148 }; 1149 1150 struct b3SendMeshDataArgs 1151 { 1152 int m_numVerticesCopied; 1153 int m_startingVertex; 1154 int m_numVerticesRemaining; 1155 }; 1156 1157 struct SharedMemoryCommand 1158 { 1159 int m_type; 1160 smUint64_t m_timeStamp; 1161 int m_sequenceNumber; 1162 1163 //m_updateFlags is a bit fields to tell which parameters need updating 1164 //for example m_updateFlags = SIM_PARAM_UPDATE_DELTA_TIME | SIM_PARAM_UPDATE_NUM_SOLVER_ITERATIONS; 1165 int m_updateFlags; 1166 1167 union { 1168 struct UrdfArgs m_urdfArguments; 1169 struct SdfArgs m_sdfArguments; 1170 struct MjcfArgs m_mjcfArguments; 1171 struct FileArgs m_fileArguments; 1172 struct SdfRequestInfoArgs m_sdfRequestInfoArgs; 1173 struct ChangeDynamicsInfoArgs m_changeDynamicsInfoArgs; 1174 struct GetDynamicsInfoArgs m_getDynamicsInfoArgs; 1175 struct InitPoseArgs m_initPoseArgs; 1176 struct b3PhysicsSimulationParameters m_physSimParamArgs; 1177 struct BulletDataStreamArgs m_dataStreamArguments; 1178 struct SendDesiredStateArgs m_sendDesiredStateCommandArgument; 1179 struct RequestActualStateArgs m_requestActualStateInformationCommandArgument; 1180 struct CreateSensorArgs m_createSensorArguments; 1181 struct CreateBoxShapeArgs m_createBoxShapeArguments; 1182 struct RequestDebugLinesArgs m_requestDebugLinesArguments; 1183 struct RequestPixelDataArgs m_requestPixelDataArguments; 1184 struct PickBodyArgs m_pickBodyArguments; 1185 struct ExternalForceArgs m_externalForceArguments; 1186 struct CalculateInverseDynamicsArgs m_calculateInverseDynamicsArguments; 1187 struct CalculateJacobianArgs m_calculateJacobianArguments; 1188 struct CalculateMassMatrixArgs m_calculateMassMatrixArguments; 1189 struct b3UserConstraint m_userConstraintArguments; 1190 struct RequestContactDataArgs m_requestContactPointArguments; 1191 struct RequestOverlappingObjectsArgs m_requestOverlappingObjectsArgs; 1192 struct RequestVisualShapeDataArgs m_requestVisualShapeDataArguments; 1193 struct UpdateVisualShapeDataArgs m_updateVisualShapeDataArguments; 1194 struct LoadTextureArgs m_loadTextureArguments; 1195 struct CalculateInverseKinematicsArgs m_calculateInverseKinematicsArguments; 1196 struct UserDebugDrawArgs m_userDebugDrawArgs; 1197 struct RequestRaycastIntersections m_requestRaycastIntersections; 1198 struct LoadSoftBodyArgs m_loadSoftBodyArguments; 1199 struct VRCameraState m_vrCameraStateArguments; 1200 struct StateLoggingRequest m_stateLoggingArguments; 1201 struct ConfigureOpenGLVisualizerRequest m_configureOpenGLVisualizerArguments; 1202 struct b3ObjectArgs m_removeObjectArgs; 1203 struct b3Profile m_profile; 1204 struct b3CreateUserShapeArgs m_createUserShapeArgs; 1205 struct b3CreateMultiBodyArgs m_createMultiBodyArgs; 1206 struct b3RequestCollisionInfoArgs m_requestCollisionInfoArgs; 1207 struct b3ChangeTextureArgs m_changeTextureArgs; 1208 struct b3SearchPathfArgs m_searchPathArgs; 1209 struct b3CustomCommand m_customCommandArgs; 1210 struct b3StateSerializationArguments m_loadStateArguments; 1211 struct RequestCollisionShapeDataArgs m_requestCollisionShapeDataArguments; 1212 struct SyncUserDataRequestArgs m_syncUserDataRequestArgs; 1213 struct UserDataRequestArgs m_userDataRequestArgs; 1214 struct AddUserDataRequestArgs m_addUserDataRequestArgs; 1215 struct UserDataRequestArgs m_removeUserDataRequestArgs; 1216 struct b3CollisionFilterArgs m_collisionFilterArgs; 1217 struct b3RequestMeshDataArgs m_requestMeshDataArgs; 1218 struct b3ResetMeshDataArgs m_resetMeshDataArgs; 1219 1220 }; 1221 }; 1222 1223 struct RigidBodyCreateArgs 1224 { 1225 int m_bodyUniqueId; 1226 }; 1227 1228 struct SendContactDataArgs 1229 { 1230 int m_startingContactPointIndex; 1231 int m_numContactPointsCopied; 1232 int m_numRemainingContactPoints; 1233 }; 1234 1235 struct SendOverlappingObjectsArgs 1236 { 1237 int m_startingOverlappingObjectIndex; 1238 int m_numOverlappingObjectsCopied; 1239 int m_numRemainingOverlappingObjects; 1240 }; 1241 1242 struct SharedMemoryStatus 1243 { 1244 int m_type; 1245 1246 smUint64_t m_timeStamp; 1247 int m_sequenceNumber; 1248 1249 //m_streamBytes is only for internal purposes 1250 int m_numDataStreamBytes; 1251 char* m_dataStream; 1252 1253 //m_updateFlags is a bit fields to tell which parameters were updated, 1254 //m_updateFlags is ignored for most status messages 1255 int m_updateFlags; 1256 1257 union { 1258 struct BulletDataStreamArgs m_dataStreamArguments; 1259 struct SdfLoadedArgs m_sdfLoadedArgs; 1260 struct SendActualStateArgs m_sendActualStateArgs; 1261 struct SendDebugLinesArgs m_sendDebugLinesArgs; 1262 struct SendPixelDataArgs m_sendPixelDataArguments; 1263 struct RigidBodyCreateArgs m_rigidBodyCreateArgs; 1264 struct CalculateInverseDynamicsResultArgs m_inverseDynamicsResultArgs; 1265 struct CalculateJacobianResultArgs m_jacobianResultArgs; 1266 struct CalculateMassMatrixResultArgs m_massMatrixResultArgs; 1267 struct SendContactDataArgs m_sendContactPointArgs; 1268 struct SendOverlappingObjectsArgs m_sendOverlappingObjectsArgs; 1269 struct CalculateInverseKinematicsResultArgs m_inverseKinematicsResultArgs; 1270 struct SendVisualShapeDataArgs m_sendVisualShapeArgs; 1271 struct UserDebugDrawResultArgs m_userDebugDrawArgs; 1272 struct b3UserConstraint m_userConstraintResultArgs; 1273 struct b3UserConstraintState m_userConstraintStateResultArgs; 1274 struct SendVREvents m_sendVREvents; 1275 struct SendKeyboardEvents m_sendKeyboardEvents; 1276 struct SendRaycastHits m_raycastHits; 1277 struct StateLoggingResultArgs m_stateLoggingResultArgs; 1278 struct b3OpenGLVisualizerCameraInfo m_visualizerCameraResultArgs; 1279 struct b3ObjectArgs m_removeObjectArgs; 1280 struct b3DynamicsInfo m_dynamicsInfo; 1281 struct b3CreateUserShapeResultArgs m_createUserShapeResultArgs; 1282 struct b3CreateMultiBodyResultArgs m_createMultiBodyResultArgs; 1283 struct b3SendCollisionInfoArgs m_sendCollisionInfoArgs; 1284 struct SendMouseEvents m_sendMouseEvents; 1285 struct b3LoadTextureResultArgs m_loadTextureResultArguments; 1286 struct b3CustomCommandResultArgs m_customCommandResultArgs; 1287 struct b3PhysicsSimulationParameters m_simulationParameterResultArgs; 1288 struct b3StateSerializationArguments m_saveStateResultArgs; 1289 struct b3LoadSoftBodyResultArgs m_loadSoftBodyResultArguments; 1290 struct SendCollisionShapeDataArgs m_sendCollisionShapeArgs; 1291 struct SyncUserDataArgs m_syncUserDataArgs; 1292 struct UserDataResponseArgs m_userDataResponseArgs; 1293 struct UserDataRequestArgs m_removeUserDataResponseArgs; 1294 struct b3ForwardDynamicsAnalyticsArgs m_forwardDynamicsAnalyticsArgs; 1295 struct b3SendMeshDataArgs m_sendMeshDataArgs; 1296 }; 1297 }; 1298 1299 typedef struct SharedMemoryStatus SharedMemoryStatus_t; 1300 1301 #endif //SHARED_MEMORY_COMMANDS_H 1302