1#![allow(non_camel_case_types, non_snake_case, clippy::upper_case_acronyms)]
3use std::ffi::c_void;
4use std::os::raw::{c_char, c_int, c_uchar};
5use std::ptr::NonNull;
6pub const SHARED_MEMORY_KEY: i32 = 12347;
7
8#[repr(C)]
9pub struct b3PhysicsClientHandle__ {
10 _unused: c_int,
11}
12pub type b3PhysicsClientHandle = NonNull<b3PhysicsClientHandle__>;
13
14#[repr(C)]
15pub struct b3SharedMemoryCommandHandle__ {
16 _unused: c_int,
17}
18pub type b3SharedMemoryCommandHandle = *mut b3SharedMemoryCommandHandle__;
19
20#[repr(C)]
21pub struct b3SharedMemoryStatusHandle__ {
22 _unused: c_int,
23}
24pub type b3SharedMemoryStatusHandle = *mut b3SharedMemoryStatusHandle__;
25pub const MAX_SDF_BODIES: u32 = 512;
26extern "C" {
27 pub fn b3ConnectPhysicsDirect() -> Option<b3PhysicsClientHandle>;
28 pub fn b3CreateInProcessPhysicsServerAndConnect(
29 argc: c_int,
30 argv: *mut *mut c_char,
31 ) -> Option<b3PhysicsClientHandle>;
32 pub fn b3CreateInProcessPhysicsServerAndConnectMainThread(
33 argc: c_int,
34 argv: *mut *mut c_char,
35 ) -> Option<b3PhysicsClientHandle>;
36 pub fn b3CreateInProcessGraphicsServerAndConnectMainThreadSharedMemory(
37 port: c_int,
38 ) -> Option<b3PhysicsClientHandle>;
39 pub fn b3CreateInProcessGraphicsServerAndConnectSharedMemory(
40 port: c_int,
41 ) -> Option<b3PhysicsClientHandle>;
42 pub fn b3CreateInProcessPhysicsServerFromExistingExampleBrowserAndConnectTCP(
43 host_name: *const c_char,
44 port: c_int,
45 ) -> Option<b3PhysicsClientHandle>;
46 pub fn b3CreateInProcessPhysicsServerAndConnectSharedMemory(
47 argc: c_int,
48 argv: *mut *mut c_char,
49 ) -> Option<b3PhysicsClientHandle>;
50 pub fn b3CreateInProcessPhysicsServerAndConnectMainThreadSharedMemory(
51 argc: c_int,
52 argv: *mut *mut c_char,
53 ) -> Option<b3PhysicsClientHandle>;
54 pub fn b3CreateInProcessPhysicsServerFromExistingExampleBrowserAndConnect3(
55 guiHelperPtr: *mut c_void,
56 sharedMemoryKey: c_int,
57 ) -> Option<b3PhysicsClientHandle>;
58 pub fn b3CreateInProcessPhysicsServerFromExistingExampleBrowserAndConnect4(
59 guiHelperPtr: *mut c_void,
60 sharedMemoryKey: c_int,
61 ) -> Option<b3PhysicsClientHandle>;
62
63 pub fn b3ConnectPhysicsUDP(
64 host_name: *const c_char,
65 port: c_int,
66 ) -> Option<b3PhysicsClientHandle>;
67 pub fn b3ConnectPhysicsTCP(
68 host_name: *const c_char,
69 port: c_int,
70 ) -> Option<b3PhysicsClientHandle>;
71
72 pub fn b3ConnectSharedMemory(sharedMemoryKey: c_int) -> Option<b3PhysicsClientHandle>;
73 pub fn b3DisconnectSharedMemory(physClient: b3PhysicsClientHandle);
74
75 pub fn b3InitConfigureOpenGLVisualizer(
76 physClient: b3PhysicsClientHandle,
77 ) -> b3SharedMemoryCommandHandle;
78 pub fn b3ConfigureOpenGLVisualizerSetVisualizationFlags(
79 commandHandle: b3SharedMemoryCommandHandle,
80 flag: c_int,
81 enabled: c_int,
82 );
83 pub fn b3CanSubmitCommand(physClient: b3PhysicsClientHandle) -> c_int;
84 pub fn b3SubmitClientCommandAndWaitStatus(
85 physClient: b3PhysicsClientHandle,
86 commandHandle: b3SharedMemoryCommandHandle,
87 ) -> b3SharedMemoryStatusHandle;
88
89 pub fn b3GetStatusType(statusHandle: b3SharedMemoryStatusHandle) -> c_int;
90
91 pub fn b3GetStatusActualState(
92 statusHandle: b3SharedMemoryStatusHandle,
93 bodyUniqueId: *mut c_int,
94 numDegreeOfFreedomQ: *mut c_int,
95 numDegreeOfFreedomU: *mut c_int,
96 rootLocalInertialFrame: *mut *const f64,
97 actualStateQ: *mut *const f64,
98 actualStateQdot: *mut *const f64,
99 jointReactionForces: *mut *const f64,
100 ) -> c_int;
101
102 pub fn b3GetStatusBodyIndices(
103 statusHandle: b3SharedMemoryStatusHandle,
104 bodyIndicesOut: *mut c_int,
105 bodyIndicesCapacity: c_int,
106 ) -> c_int;
107
108 pub fn b3GetStatusBodyIndex(statusHandle: b3SharedMemoryStatusHandle) -> c_int;
109
110 pub fn b3RequestCollisionInfoCommandInit(
111 physClient: b3PhysicsClientHandle,
112 bodyUniqueId: c_int,
113 ) -> b3SharedMemoryCommandHandle;
114
115 pub fn b3GetStatusAABB(
116 statusHandle: b3SharedMemoryStatusHandle,
117 linkIndex: c_int,
118 aabbMin: *mut f64,
119 aabbMax: *mut f64,
120 ) -> c_int;
121
122 pub fn b3InitSyncBodyInfoCommand(
123 physClient: b3PhysicsClientHandle,
124 ) -> b3SharedMemoryCommandHandle;
125 pub fn b3InitSyncUserDataCommand(
126 physClient: b3PhysicsClientHandle,
127 ) -> b3SharedMemoryCommandHandle;
128
129 pub fn b3InitStepSimulationCommand(
130 physClient: b3PhysicsClientHandle,
131 ) -> b3SharedMemoryCommandHandle;
132
133 pub fn b3InitResetSimulationCommand(
134 physClient: b3PhysicsClientHandle,
135 ) -> b3SharedMemoryCommandHandle;
136
137 pub fn b3InitResetSimulationCommand2(
138 commandHandle: b3SharedMemoryCommandHandle,
139 ) -> b3SharedMemoryCommandHandle;
140
141 pub fn b3InitResetSimulationSetFlags(
142 commandHandle: b3SharedMemoryCommandHandle,
143 flags: c_int,
144 ) -> c_int;
145
146 pub fn b3SetAdditionalSearchPath(
147 physClient: b3PhysicsClientHandle,
148 path: *const c_char,
149 ) -> b3SharedMemoryCommandHandle;
150
151 pub fn b3LoadUrdfCommandInit(
152 physClient: b3PhysicsClientHandle,
153 urdfFileName: *const c_char,
154 ) -> b3SharedMemoryCommandHandle;
155 pub fn b3LoadUrdfCommandSetFlags(
156 commandHandle: b3SharedMemoryCommandHandle,
157 flags: c_int,
158 ) -> c_int;
159 pub fn b3LoadUrdfCommandSetStartPosition(
160 commandHandle: b3SharedMemoryCommandHandle,
161 startPosX: f64,
162 startPosY: f64,
163 startPosZ: f64,
164 ) -> c_int;
165 pub fn b3LoadUrdfCommandSetStartOrientation(
166 commandHandle: b3SharedMemoryCommandHandle,
167 startOrnX: f64,
168 startOrnY: f64,
169 startOrnZ: f64,
170 startOrnW: f64,
171 ) -> c_int;
172 pub fn b3LoadUrdfCommandSetUseMultiBody(
173 commandHandle: b3SharedMemoryCommandHandle,
174 useMultiBody: c_int,
175 ) -> c_int;
176 pub fn b3LoadUrdfCommandSetUseFixedBase(
177 commandHandle: b3SharedMemoryCommandHandle,
178 useFixedBase: c_int,
179 ) -> c_int;
180 pub fn b3LoadUrdfCommandSetGlobalScaling(
181 commandHandle: b3SharedMemoryCommandHandle,
182 globalScaling: f64,
183 ) -> c_int;
184
185 pub fn b3RequestActualStateCommandInit(
186 physClient: b3PhysicsClientHandle,
187 bodyUniqueId: c_int,
188 ) -> b3SharedMemoryCommandHandle;
189 pub fn b3RequestActualStateCommandComputeLinkVelocity(
190 commandHandle: b3SharedMemoryCommandHandle,
191 computeLinkVelocity: c_int,
192 ) -> c_int;
193 pub fn b3RequestActualStateCommandComputeForwardKinematics(
194 commandHandle: b3SharedMemoryCommandHandle,
195 computeForwardKinematics: c_int,
196 ) -> c_int;
197 pub fn b3GetJointState(
198 physClient: b3PhysicsClientHandle,
199 statusHandle: b3SharedMemoryStatusHandle,
200 jointIndex: c_int,
201 state: *mut b3JointSensorState,
202 ) -> c_int;
203 pub fn b3GetJointStateMultiDof(
204 physClient: b3PhysicsClientHandle,
205 statusHandle: b3SharedMemoryStatusHandle,
206 jointIndex: c_int,
207 state: *mut b3JointSensorState2,
208 ) -> c_int;
209 pub fn b3GetLinkState(
210 physClient: b3PhysicsClientHandle,
211 statusHandle: b3SharedMemoryStatusHandle,
212 linkIndex: c_int,
213 state: *mut b3LinkState,
214 ) -> c_int;
215 pub fn b3GetDynamicsInfoCommandInit(
216 physClient: b3PhysicsClientHandle,
217 bodyUniqueId: c_int,
218 linkIndex: c_int,
219 ) -> b3SharedMemoryCommandHandle;
220
221 #[doc = "given a body unique id and link index, return the dynamics information. See b3DynamicsInfo in SharedMemoryPublic.h"]
222 pub fn b3GetDynamicsInfo(
223 statusHandle: b3SharedMemoryStatusHandle,
224 info: *mut b3DynamicsInfo,
225 ) -> c_int;
226 pub fn b3InitChangeDynamicsInfo(
227 physClient: b3PhysicsClientHandle,
228 ) -> b3SharedMemoryCommandHandle;
229 pub fn b3ChangeDynamicsInfoSetMass(
230 commandHandle: b3SharedMemoryCommandHandle,
231 bodyUniqueId: c_int,
232 linkIndex: c_int,
233 mass: f64,
234 ) -> c_int;
235
236 pub fn b3ChangeDynamicsInfoSetLocalInertiaDiagonal(
237 commandHandle: b3SharedMemoryCommandHandle,
238 bodyUniqueId: c_int,
239 linkIndex: c_int,
240 localInertiaDiagonal: *const f64,
241 ) -> c_int;
242
243 pub fn b3ChangeDynamicsInfoSetAnisotropicFriction(
244 commandHandle: b3SharedMemoryCommandHandle,
245 bodyUniqueId: c_int,
246 linkIndex: c_int,
247 anisotropicFriction: *const f64,
248 ) -> c_int;
249
250 pub fn b3ChangeDynamicsInfoSetJointLimit(
251 commandHandle: b3SharedMemoryCommandHandle,
252 bodyUniqueId: c_int,
253 linkIndex: c_int,
254 jointLowerLimit: f64,
255 jointUpperLimit: f64,
256 ) -> c_int;
257
258 pub fn b3ChangeDynamicsInfoSetJointLimitForce(
259 commandHandle: b3SharedMemoryCommandHandle,
260 bodyUniqueId: c_int,
261 linkIndex: c_int,
262 jointLimitForce: f64,
263 ) -> c_int;
264
265 pub fn b3ChangeDynamicsInfoSetDynamicType(
266 commandHandle: b3SharedMemoryCommandHandle,
267 bodyUniqueId: c_int,
268 linkIndex: c_int,
269 dynamicType: c_int,
270 ) -> c_int;
271
272 pub fn b3ChangeDynamicsInfoSetLateralFriction(
273 commandHandle: b3SharedMemoryCommandHandle,
274 bodyUniqueId: c_int,
275 linkIndex: c_int,
276 lateralFriction: f64,
277 ) -> c_int;
278
279 pub fn b3ChangeDynamicsInfoSetSpinningFriction(
280 commandHandle: b3SharedMemoryCommandHandle,
281 bodyUniqueId: c_int,
282 linkIndex: c_int,
283 friction: f64,
284 ) -> c_int;
285
286 pub fn b3ChangeDynamicsInfoSetRollingFriction(
287 commandHandle: b3SharedMemoryCommandHandle,
288 bodyUniqueId: c_int,
289 linkIndex: c_int,
290 friction: f64,
291 ) -> c_int;
292
293 pub fn b3ChangeDynamicsInfoSetRestitution(
294 commandHandle: b3SharedMemoryCommandHandle,
295 bodyUniqueId: c_int,
296 linkIndex: c_int,
297 restitution: f64,
298 ) -> c_int;
299
300 pub fn b3ChangeDynamicsInfoSetLinearDamping(
301 commandHandle: b3SharedMemoryCommandHandle,
302 bodyUniqueId: c_int,
303 linearDamping: f64,
304 ) -> c_int;
305
306 pub fn b3ChangeDynamicsInfoSetAngularDamping(
307 commandHandle: b3SharedMemoryCommandHandle,
308 bodyUniqueId: c_int,
309 angularDamping: f64,
310 ) -> c_int;
311
312 pub fn b3ChangeDynamicsInfoSetJointDamping(
313 commandHandle: b3SharedMemoryCommandHandle,
314 bodyUniqueId: c_int,
315 linkIndex: c_int,
316 jointDamping: f64,
317 ) -> c_int;
318
319 pub fn b3ChangeDynamicsInfoSetContactStiffnessAndDamping(
320 commandHandle: b3SharedMemoryCommandHandle,
321 bodyUniqueId: c_int,
322 linkIndex: c_int,
323 contactStiffness: f64,
324 contactDamping: f64,
325 ) -> c_int;
326
327 pub fn b3ChangeDynamicsInfoSetFrictionAnchor(
328 commandHandle: b3SharedMemoryCommandHandle,
329 bodyUniqueId: c_int,
330 linkIndex: c_int,
331 frictionAnchor: c_int,
332 ) -> c_int;
333
334 pub fn b3ChangeDynamicsInfoSetCcdSweptSphereRadius(
335 commandHandle: b3SharedMemoryCommandHandle,
336 bodyUniqueId: c_int,
337 linkIndex: c_int,
338 ccdSweptSphereRadius: f64,
339 ) -> c_int;
340
341 pub fn b3ChangeDynamicsInfoSetContactProcessingThreshold(
342 commandHandle: b3SharedMemoryCommandHandle,
343 bodyUniqueId: c_int,
344 linkIndex: c_int,
345 contactProcessingThreshold: f64,
346 ) -> c_int;
347
348 pub fn b3ChangeDynamicsInfoSetActivationState(
349 commandHandle: b3SharedMemoryCommandHandle,
350 bodyUniqueId: c_int,
351 activationState: c_int,
352 ) -> c_int;
353
354 pub fn b3ChangeDynamicsInfoSetMaxJointVelocity(
355 commandHandle: b3SharedMemoryCommandHandle,
356 bodyUniqueId: c_int,
357 maxJointVelocity: f64,
358 ) -> c_int;
359
360 pub fn b3ChangeDynamicsInfoSetCollisionMargin(
361 commandHandle: b3SharedMemoryCommandHandle,
362 bodyUniqueId: c_int,
363 collisionMargin: f64,
364 ) -> c_int;
365
366 pub fn b3InitRemoveBodyCommand(
367 physClient: b3PhysicsClientHandle,
368 bodyUniqueId: c_int,
369 ) -> b3SharedMemoryCommandHandle;
370
371 #[doc = "return the total number of bodies in the simulation"]
372 pub fn b3GetNumBodies(physClient: b3PhysicsClientHandle) -> c_int;
373
374 #[doc = " return the body unique id, given the index in range [0 , b3GetNumBodies() )"]
375 pub fn b3GetBodyUniqueId(physClient: b3PhysicsClientHandle, serialIndex: c_int) -> c_int;
376
377 #[doc = "given a body unique id, return the body information. See b3BodyInfo in SharedMemoryPublic.h"]
378 pub fn b3GetBodyInfo(
379 physClient: b3PhysicsClientHandle,
380 bodyUniqueId: c_int,
381 info: *mut b3BodyInfo,
382 ) -> c_int;
383
384 pub fn b3GetNumJoints(physClient: b3PhysicsClientHandle, bodyUniqueId: c_int) -> c_int;
385 pub fn b3GetJointInfo(
386 physClient: b3PhysicsClientHandle,
387 bodyUniqueId: c_int,
388 jointIndex: c_int,
389 jointInfo: *mut b3JointInfo,
390 );
391 pub fn b3CreatePoseCommandInit(
392 physClient: b3PhysicsClientHandle,
393 bodyUniqueId: c_int,
394 ) -> b3SharedMemoryCommandHandle;
395 pub fn b3CreatePoseCommandSetBasePosition(
396 commandHandle: b3SharedMemoryCommandHandle,
397 startPosX: f64,
398 startPosY: f64,
399 startPosZ: f64,
400 ) -> c_int;
401
402 pub fn b3CreatePoseCommandSetBaseOrientation(
403 commandHandle: b3SharedMemoryCommandHandle,
404 startOrnX: f64,
405 startOrnY: f64,
406 startOrnZ: f64,
407 startOrnW: f64,
408 ) -> c_int;
409 pub fn b3CreatePoseCommandSetBaseLinearVelocity(
410 commandHandle: b3SharedMemoryCommandHandle,
411 linVel: *const f64,
412 ) -> c_int;
413
414 pub fn b3CreatePoseCommandSetBaseAngularVelocity(
415 commandHandle: b3SharedMemoryCommandHandle,
416 angVel: *const f64,
417 ) -> c_int;
418 pub fn b3CreatePoseCommandSetJointPosition(
419 physClient: b3PhysicsClientHandle,
420 commandHandle: b3SharedMemoryCommandHandle,
421 jointIndex: c_int,
422 jointPosition: f64,
423 ) -> c_int;
424 pub fn b3CreatePoseCommandSetJointVelocity(
425 physClient: b3PhysicsClientHandle,
426 commandHandle: b3SharedMemoryCommandHandle,
427 jointIndex: c_int,
428 jointVelocity: f64,
429 ) -> c_int;
430
431 pub fn b3ComputeDofCount(physClient: b3PhysicsClientHandle, bodyUniqueId: c_int) -> c_int;
432 pub fn b3SaveStateCommandInit(physClient: b3PhysicsClientHandle)
433 -> b3SharedMemoryCommandHandle;
434
435 pub fn b3InitRemoveStateCommand(
436 physClient: b3PhysicsClientHandle,
437 stateId: c_int,
438 ) -> b3SharedMemoryCommandHandle;
439
440 pub fn b3GetStatusGetStateId(statusHandle: b3SharedMemoryStatusHandle) -> c_int;
441
442 pub fn b3LoadStateCommandInit(physClient: b3PhysicsClientHandle)
443 -> b3SharedMemoryCommandHandle;
444
445 pub fn b3LoadStateSetStateId(
446 commandHandle: b3SharedMemoryCommandHandle,
447 stateId: c_int,
448 ) -> c_int;
449
450 pub fn b3LoadStateSetFileName(
451 commandHandle: b3SharedMemoryCommandHandle,
452 fileName: *const c_char,
453 ) -> c_int;
454
455 pub fn b3LoadBulletCommandInit(
456 physClient: b3PhysicsClientHandle,
457 fileName: *const c_char,
458 ) -> b3SharedMemoryCommandHandle;
459
460 pub fn b3SaveBulletCommandInit(
461 physClient: b3PhysicsClientHandle,
462 fileName: *const c_char,
463 ) -> b3SharedMemoryCommandHandle;
464
465 pub fn b3LoadMJCFCommandInit(
466 physClient: b3PhysicsClientHandle,
467 fileName: *const c_char,
468 ) -> b3SharedMemoryCommandHandle;
469
470 pub fn b3LoadMJCFCommandInit2(
471 commandHandle: b3SharedMemoryCommandHandle,
472 fileName: *const c_char,
473 ) -> b3SharedMemoryCommandHandle;
474
475 pub fn b3LoadMJCFCommandSetFlags(commandHandle: b3SharedMemoryCommandHandle, flags: c_int);
476
477 pub fn b3CalculateInverseDynamicsCommandInit2(
478 physClient: b3PhysicsClientHandle,
479 bodyUniqueId: c_int,
480 jointPositionsQ: *const f64,
481 dofCountQ: c_int,
482 jointVelocitiesQdot: *const f64,
483 jointAccelerations: *const f64,
484 dofCountQdot: c_int,
485 ) -> b3SharedMemoryCommandHandle;
486
487 pub fn b3CalculateInverseDynamicsSetFlags(
488 commandHandle: b3SharedMemoryCommandHandle,
489 flags: c_int,
490 );
491 pub fn b3GetStatusInverseDynamicsJointForces(
492 statusHandle: b3SharedMemoryStatusHandle,
493 bodyUniqueId: *mut c_int,
494 dofCount: *mut c_int,
495 jointForces: *mut f64,
496 ) -> c_int;
497
498 pub fn b3CalculateMassMatrixCommandInit(
499 physClient: b3PhysicsClientHandle,
500 bodyUniqueId: c_int,
501 jointPositionsQ: *const f64,
502 dofCountQ: c_int,
503 ) -> b3SharedMemoryCommandHandle;
504
505 pub fn b3CalculateMassMatrixSetFlags(commandHandle: b3SharedMemoryCommandHandle, flags: c_int);
506
507 #[doc = "the mass matrix is stored in column-major layout of size dofCount*dofCount"]
508 pub fn b3GetStatusMassMatrix(
509 physClient: b3PhysicsClientHandle,
510 statusHandle: b3SharedMemoryStatusHandle,
511 dofCount: *mut c_int,
512 massMatrix: *mut f64,
513 ) -> c_int;
514
515 pub fn b3CalculateInverseKinematicsCommandInit(
516 physClient: b3PhysicsClientHandle,
517 bodyUniqueId: c_int,
518 ) -> b3SharedMemoryCommandHandle;
519 pub fn b3CalculateInverseKinematicsAddTargetPurePosition(
520 commandHandle: b3SharedMemoryCommandHandle,
521 endEffectorLinkIndex: c_int,
522 targetPosition: *const f64,
523 );
524 pub fn b3CalculateInverseKinematicsAddTargetsPurePosition(
525 commandHandle: b3SharedMemoryCommandHandle,
526 numEndEffectorLinkIndices: c_int,
527 endEffectorIndices: *const c_int,
528 targetPositions: *const f64,
529 );
530 pub fn b3CalculateInverseKinematicsAddTargetPositionWithOrientation(
531 commandHandle: b3SharedMemoryCommandHandle,
532 endEffectorLinkIndex: c_int,
533 targetPosition: *const f64,
534 targetOrientation: *const f64,
535 );
536 pub fn b3CalculateInverseKinematicsPosWithNullSpaceVel(
537 commandHandle: b3SharedMemoryCommandHandle,
538 numDof: c_int,
539 endEffectorLinkIndex: c_int,
540 targetPosition: *const f64,
541 lowerLimit: *const f64,
542 upperLimit: *const f64,
543 jointRange: *const f64,
544 restPose: *const f64,
545 );
546 pub fn b3CalculateInverseKinematicsPosOrnWithNullSpaceVel(
547 commandHandle: b3SharedMemoryCommandHandle,
548 numDof: c_int,
549 endEffectorLinkIndex: c_int,
550 targetPosition: *const f64,
551 targetOrientation: *const f64,
552 lowerLimit: *const f64,
553 upperLimit: *const f64,
554 jointRange: *const f64,
555 restPose: *const f64,
556 );
557 pub fn b3CalculateInverseKinematicsSetJointDamping(
558 commandHandle: b3SharedMemoryCommandHandle,
559 numDof: c_int,
560 jointDampingCoeff: *const f64,
561 );
562 pub fn b3CalculateInverseKinematicsSelectSolver(
563 commandHandle: b3SharedMemoryCommandHandle,
564 solver: c_int,
565 );
566 pub fn b3GetStatusInverseKinematicsJointPositions(
567 commandHandle: b3SharedMemoryStatusHandle,
568 bodyUniqueId: *mut c_int,
569 dofCount: *mut c_int,
570 jointPositions: *mut f64,
571 ) -> c_int;
572
573 pub fn b3CalculateInverseKinematicsSetCurrentPositions(
574 commandHandle: b3SharedMemoryCommandHandle,
575 numDof: c_int,
576 currentJointPositions: *const f64,
577 );
578 pub fn b3CalculateInverseKinematicsSetMaxNumIterations(
579 commandHandle: b3SharedMemoryCommandHandle,
580 maxNumIterations: c_int,
581 );
582 pub fn b3CalculateInverseKinematicsSetResidualThreshold(
583 commandHandle: b3SharedMemoryCommandHandle,
584 residualThreshold: f64,
585 );
586 pub fn b3CollisionFilterCommandInit(
587 physClient: b3PhysicsClientHandle,
588 ) -> b3SharedMemoryCommandHandle;
589
590 pub fn b3SetCollisionFilterPair(
591 commandHandle: b3SharedMemoryCommandHandle,
592 bodyUniqueIdA: c_int,
593 bodyUniqueIdB: c_int,
594 linkIndexA: c_int,
595 linkIndexB: c_int,
596 enableCollision: c_int,
597 );
598
599 pub fn b3SetCollisionFilterGroupMask(
600 commandHandle: b3SharedMemoryCommandHandle,
601 bodyUniqueIdA: c_int,
602 linkIndexA: c_int,
603 collisionFilterGroup: c_int,
604 collisionFilterMask: c_int,
605 );
606
607 pub fn b3CalculateJacobianCommandInit(
608 physClient: b3PhysicsClientHandle,
609 bodyUniqueId: c_int,
610 linkIndex: c_int,
611 localPosition: *const f64,
612 jointPositionsQ: *const f64,
613 jointVelocitiesQdot: *const f64,
614 jointAccelerations: *const f64,
615 ) -> b3SharedMemoryCommandHandle;
616 pub fn b3GetStatusJacobian(
617 statusHandle: b3SharedMemoryStatusHandle,
618 dofCount: *mut c_int,
619 linearJacobian: *mut f64,
620 angularJacobian: *mut f64,
621 ) -> c_int;
622 pub fn b3JointControlCommandInit2(
623 physClient: b3PhysicsClientHandle,
624 bodyUniqueId: c_int,
625 controlMode: c_int,
626 ) -> b3SharedMemoryCommandHandle;
627
628 pub fn b3JointControlSetDesiredPosition(
629 commandHandle: b3SharedMemoryCommandHandle,
630 qIndex: c_int,
631 value: f64,
632 ) -> c_int;
633 pub fn b3JointControlSetKp(
634 commandHandle: b3SharedMemoryCommandHandle,
635 dofIndex: c_int,
636 value: f64,
637 ) -> c_int;
638 pub fn b3JointControlSetKd(
639 commandHandle: b3SharedMemoryCommandHandle,
640 dofIndex: c_int,
641 value: f64,
642 ) -> c_int;
643 pub fn b3JointControlSetMaximumVelocity(
644 commandHandle: b3SharedMemoryCommandHandle,
645 dofIndex: c_int,
646 maximumVelocity: f64,
647 ) -> c_int;
648
649 pub fn b3JointControlSetDesiredVelocity(
650 commandHandle: b3SharedMemoryCommandHandle,
651 dofIndex: c_int,
652 value: f64,
653 ) -> c_int;
654 pub fn b3JointControlSetMaximumForce(
655 commandHandle: b3SharedMemoryCommandHandle,
656 dofIndex: c_int,
657 value: f64,
658 ) -> c_int;
659 pub fn b3JointControlSetDesiredForceTorque(
660 commandHandle: b3SharedMemoryCommandHandle,
661 dofIndex: c_int,
662 value: f64,
663 ) -> c_int;
664 #[doc = "request an image from a simulated camera, using a software renderer."]
665 pub fn b3InitRequestCameraImage(
666 physClient: b3PhysicsClientHandle,
667 ) -> b3SharedMemoryCommandHandle;
668
669 pub fn b3InitRequestCameraImage2(
670 commandHandle: b3SharedMemoryCommandHandle,
671 ) -> b3SharedMemoryCommandHandle;
672
673 pub fn b3RequestCameraImageSetCameraMatrices(
674 commandHandle: b3SharedMemoryCommandHandle,
675 viewMatrix: *mut f32,
676 projectionMatrix: *mut f32,
677 );
678
679 pub fn b3RequestCameraImageSetPixelResolution(
680 commandHandle: b3SharedMemoryCommandHandle,
681 width: c_int,
682 height: c_int,
683 );
684
685 pub fn b3RequestCameraImageSetLightDirection(
686 commandHandle: b3SharedMemoryCommandHandle,
687 lightDirection: *const f32,
688 );
689
690 pub fn b3RequestCameraImageSetLightColor(
691 commandHandle: b3SharedMemoryCommandHandle,
692 lightColor: *const f32,
693 );
694
695 pub fn b3RequestCameraImageSetLightDistance(
696 commandHandle: b3SharedMemoryCommandHandle,
697 lightDistance: f32,
698 );
699
700 pub fn b3RequestCameraImageSetLightAmbientCoeff(
701 commandHandle: b3SharedMemoryCommandHandle,
702 lightAmbientCoeff: f32,
703 );
704
705 pub fn b3RequestCameraImageSetLightDiffuseCoeff(
706 commandHandle: b3SharedMemoryCommandHandle,
707 lightDiffuseCoeff: f32,
708 );
709
710 pub fn b3RequestCameraImageSetLightSpecularCoeff(
711 commandHandle: b3SharedMemoryCommandHandle,
712 lightSpecularCoeff: f32,
713 );
714
715 pub fn b3RequestCameraImageSetShadow(
716 commandHandle: b3SharedMemoryCommandHandle,
717 hasShadow: c_int,
718 );
719
720 pub fn b3RequestCameraImageSelectRenderer(
721 commandHandle: b3SharedMemoryCommandHandle,
722 renderer: c_int,
723 );
724
725 pub fn b3RequestCameraImageSetFlags(commandHandle: b3SharedMemoryCommandHandle, flags: c_int);
726
727 pub fn b3GetCameraImageData(
728 physClient: b3PhysicsClientHandle,
729 imageData: *mut b3CameraImageData,
730 );
731
732 #[doc = "set projective texture camera matrices."]
733 pub fn b3RequestCameraImageSetProjectiveTextureMatrices(
734 commandHandle: b3SharedMemoryCommandHandle,
735 viewMatrix: *mut f32,
736 projectionMatrix: *mut f32,
737 );
738
739 pub fn b3ComputeViewMatrixFromPositions(
740 cameraPosition: *const f32,
741 cameraTargetPosition: *const f32,
742 cameraUp: *const f32,
743 viewMatrix: *mut f32,
744 );
745 pub fn b3ComputeViewMatrixFromYawPitchRoll(
746 cameraTargetPosition: *const f32,
747 distance: f32,
748 yaw: f32,
749 pitch: f32,
750 roll: f32,
751 upAxis: c_int,
752 viewMatrix: *mut f32,
753 );
754 pub fn b3ComputePositionFromViewMatrix(
755 viewMatrix: *const f32,
756 cameraPosition: *mut f32,
757 cameraTargetPosition: *mut f32,
758 cameraUp: *mut f32,
759 );
760
761 pub fn b3ComputeProjectionMatrix(
762 left: f32,
763 right: f32,
764 bottom: f32,
765 top: f32,
766 nearVal: f32,
767 farVal: f32,
768 projectionMatrix: *mut f32,
769 );
770 pub fn b3ComputeProjectionMatrixFOV(
771 fov: f32,
772 aspect: f32,
773 nearVal: f32,
774 farVal: f32,
775 projectionMatrix: *mut f32,
776 );
777
778 pub fn b3InitUserDebugAddParameter(
779 physClient: b3PhysicsClientHandle,
780 txt: *const c_char,
781 rangeMin: f64,
782 rangeMax: f64,
783 startValue: f64,
784 ) -> b3SharedMemoryCommandHandle;
785
786 pub fn b3GetDebugItemUniqueId(statusHandle: b3SharedMemoryStatusHandle) -> c_int;
787
788 pub fn b3InitUserDebugReadParameter(
789 physClient: b3PhysicsClientHandle,
790 debugItemUniqueId: c_int,
791 ) -> b3SharedMemoryCommandHandle;
792
793 pub fn b3GetStatusDebugParameterValue(
794 statusHandle: b3SharedMemoryStatusHandle,
795 paramValue: *mut f64,
796 ) -> c_int;
797
798 pub fn b3ConfigureOpenGLVisualizerSetViewMatrix(
799 commandHandle: b3SharedMemoryCommandHandle,
800 cameraDistance: f32,
801 cameraPitch: f32,
802 cameraYaw: f32,
803 cameraTargetPosition: *const f32,
804 );
805
806 pub fn b3InitRequestOpenGLVisualizerCameraCommand(
807 physClient: b3PhysicsClientHandle,
808 ) -> b3SharedMemoryCommandHandle;
809
810 pub fn b3GetStatusOpenGLVisualizerCamera(
811 statusHandle: b3SharedMemoryStatusHandle,
812 camera: *mut b3OpenGLVisualizerCameraInfo,
813 ) -> c_int;
814
815 #[doc = " Add/remove user-specific debug lines and debug text messages"]
816 pub fn b3InitUserDebugDrawAddLine3D(
817 physClient: b3PhysicsClientHandle,
818 fromXYZ: *const f64,
819 toXYZ: *const f64,
820 colorRGB: *const f64,
821 lineWidth: f64,
822 lifeTime: f64,
823 ) -> b3SharedMemoryCommandHandle;
824 pub fn b3InitUserDebugDrawAddText3D(
825 physClient: b3PhysicsClientHandle,
826 txt: *const c_char,
827 positionXYZ: *const f64,
828 colorRGB: *const f64,
829 textSize: f64,
830 lifeTime: f64,
831 ) -> b3SharedMemoryCommandHandle;
832 pub fn b3UserDebugTextSetOptionFlags(
833 commandHandle: b3SharedMemoryCommandHandle,
834 optionFlags: c_int,
835 );
836 pub fn b3UserDebugTextSetOrientation(
837 commandHandle: b3SharedMemoryCommandHandle,
838 orientation: *const f64,
839 );
840 pub fn b3UserDebugItemSetReplaceItemUniqueId(
841 commandHandle: b3SharedMemoryCommandHandle,
842 replaceItem: c_int,
843 );
844
845 pub fn b3UserDebugItemSetParentObject(
846 commandHandle: b3SharedMemoryCommandHandle,
847 objectUniqueId: c_int,
848 linkIndex: c_int,
849 );
850 pub fn b3InitUserDebugDrawRemove(
851 physClient: b3PhysicsClientHandle,
852 debugItemUniqueId: c_int,
853 ) -> b3SharedMemoryCommandHandle;
854
855 pub fn b3InitUserDebugDrawRemoveAll(
856 physClient: b3PhysicsClientHandle,
857 ) -> b3SharedMemoryCommandHandle;
858
859 pub fn b3CreateRaycastCommandInit(
860 physClient: b3PhysicsClientHandle,
861 rayFromWorldX: f64,
862 rayFromWorldY: f64,
863 rayFromWorldZ: f64,
864 rayToWorldX: f64,
865 rayToWorldY: f64,
866 rayToWorldZ: f64,
867 ) -> b3SharedMemoryCommandHandle;
868
869 pub fn b3CreateRaycastBatchCommandInit(
870 physClient: b3PhysicsClientHandle,
871 ) -> b3SharedMemoryCommandHandle;
872
873 pub fn b3RaycastBatchSetNumThreads(
874 commandHandle: b3SharedMemoryCommandHandle,
875 numThreads: c_int,
876 );
877
878 pub fn b3RaycastBatchAddRay(
879 commandHandle: b3SharedMemoryCommandHandle,
880 rayFromWorld: *const f64,
881 rayToWorld: *const f64,
882 );
883
884 pub fn b3RaycastBatchAddRays(
885 physClient: b3PhysicsClientHandle,
886 commandHandle: b3SharedMemoryCommandHandle,
887 rayFromWorld: *const f64,
888 rayToWorld: *const f64,
889 numRays: c_int,
890 );
891
892 pub fn b3RaycastBatchSetParentObject(
893 commandHandle: b3SharedMemoryCommandHandle,
894 parentObjectUniqueId: c_int,
895 parentLinkIndex: c_int,
896 );
897
898 pub fn b3RaycastBatchSetReportHitNumber(
899 commandHandle: b3SharedMemoryCommandHandle,
900 reportHitNumber: c_int,
901 );
902
903 pub fn b3RaycastBatchSetCollisionFilterMask(
904 commandHandle: b3SharedMemoryCommandHandle,
905 collisionFilterMask: c_int,
906 );
907
908 pub fn b3RaycastBatchSetFractionEpsilon(
909 commandHandle: b3SharedMemoryCommandHandle,
910 fractionEpsilon: f64,
911 );
912
913 pub fn b3GetRaycastInformation(
914 physClient: b3PhysicsClientHandle,
915 raycastInfo: *mut b3RaycastInformation,
916 );
917
918 #[doc = " Apply external force at the body (or link) center of mass, in world space/Cartesian coordinates."]
919 pub fn b3ApplyExternalForceCommandInit(
920 physClient: b3PhysicsClientHandle,
921 ) -> b3SharedMemoryCommandHandle;
922
923 pub fn b3ApplyExternalForce(
924 commandHandle: b3SharedMemoryCommandHandle,
925 bodyUniqueId: c_int,
926 linkId: c_int,
927 force: *const f64,
928 position: *const f64,
929 flag: c_int,
930 );
931 pub fn b3ApplyExternalTorque(
932 commandHandle: b3SharedMemoryCommandHandle,
933 bodyUniqueId: c_int,
934 linkId: c_int,
935 torque: *const f64,
936 flag: c_int,
937 );
938
939 #[doc = "experiments of robots interacting with non-rigid objects (such as btSoftBody)"]
940 pub fn b3LoadSoftBodyCommandInit(
941 physClient: b3PhysicsClientHandle,
942 fileName: *const c_char,
943 ) -> b3SharedMemoryCommandHandle;
944
945 pub fn b3LoadSoftBodySetScale(commandHandle: b3SharedMemoryCommandHandle, scale: f64) -> c_int;
946
947 pub fn b3LoadSoftBodySetMass(commandHandle: b3SharedMemoryCommandHandle, mass: f64) -> c_int;
948
949 pub fn b3LoadSoftBodySetCollisionMargin(
950 commandHandle: b3SharedMemoryCommandHandle,
951 collisionMargin: f64,
952 ) -> c_int;
953
954 pub fn b3LoadSoftBodySetStartPosition(
955 commandHandle: b3SharedMemoryCommandHandle,
956 startPosX: f64,
957 startPosY: f64,
958 startPosZ: f64,
959 ) -> c_int;
960
961 pub fn b3LoadSoftBodySetStartOrientation(
962 commandHandle: b3SharedMemoryCommandHandle,
963 startOrnX: f64,
964 startOrnY: f64,
965 startOrnZ: f64,
966 startOrnW: f64,
967 ) -> c_int;
968
969 pub fn b3LoadSoftBodyUpdateSimMesh(
970 commandHandle: b3SharedMemoryCommandHandle,
971 filename: *const c_char,
972 ) -> c_int;
973
974 pub fn b3LoadSoftBodyAddCorotatedForce(
975 commandHandle: b3SharedMemoryCommandHandle,
976 corotatedMu: f64,
977 corotatedLambda: f64,
978 ) -> c_int;
979
980 pub fn b3LoadSoftBodyAddNeoHookeanForce(
981 commandHandle: b3SharedMemoryCommandHandle,
982 NeoHookeanMu: f64,
983 NeoHookeanLambda: f64,
984 NeoHookeanDamping: f64,
985 ) -> c_int;
986
987 pub fn b3LoadSoftBodyAddMassSpringForce(
988 commandHandle: b3SharedMemoryCommandHandle,
989 springElasticStiffness: f64,
990 springDampingStiffness: f64,
991 ) -> c_int;
992
993 pub fn b3LoadSoftBodyAddGravityForce(
994 commandHandle: b3SharedMemoryCommandHandle,
995 gravityX: f64,
996 gravityY: f64,
997 gravityZ: f64,
998 ) -> c_int;
999
1000 pub fn b3LoadSoftBodySetCollisionHardness(
1001 commandHandle: b3SharedMemoryCommandHandle,
1002 collisionHardness: f64,
1003 ) -> c_int;
1004
1005 pub fn b3LoadSoftBodySetSelfCollision(
1006 commandHandle: b3SharedMemoryCommandHandle,
1007 useSelfCollision: c_int,
1008 ) -> c_int;
1009
1010 pub fn b3LoadSoftBodySetRepulsionStiffness(
1011 commandHandle: b3SharedMemoryCommandHandle,
1012 stiffness: f64,
1013 ) -> c_int;
1014
1015 pub fn b3LoadSoftBodyUseFaceContact(
1016 commandHandle: b3SharedMemoryCommandHandle,
1017 useFaceContact: c_int,
1018 ) -> c_int;
1019
1020 pub fn b3LoadSoftBodySetFrictionCoefficient(
1021 commandHandle: b3SharedMemoryCommandHandle,
1022 frictionCoefficient: f64,
1023 ) -> c_int;
1024
1025 pub fn b3LoadSoftBodyUseBendingSprings(
1026 commandHandle: b3SharedMemoryCommandHandle,
1027 useBendingSprings: c_int,
1028 bendingStiffness: f64,
1029 ) -> c_int;
1030
1031 pub fn b3LoadSoftBodyUseAllDirectionDampingSprings(
1032 commandHandle: b3SharedMemoryCommandHandle,
1033 useAllDirectionDamping: c_int,
1034 ) -> c_int;
1035
1036 pub fn b3InitCreateSoftBodyAnchorConstraintCommand(
1037 physClient: b3PhysicsClientHandle,
1038 softBodyUniqueId: c_int,
1039 nodeIndex: c_int,
1040 bodyUniqueId: c_int,
1041 linkIndex: c_int,
1042 bodyFramePosition: *const f64,
1043 ) -> b3SharedMemoryCommandHandle;
1044
1045 pub fn b3RequestKeyboardEventsCommandInit(
1046 physClient: b3PhysicsClientHandle,
1047 ) -> b3SharedMemoryCommandHandle;
1048
1049 pub fn b3GetKeyboardEventsData(
1050 physClient: b3PhysicsClientHandle,
1051 keyboardEventsData: *mut b3KeyboardEventsData,
1052 );
1053
1054 pub fn b3RequestMouseEventsCommandInit(
1055 physClient: b3PhysicsClientHandle,
1056 ) -> b3SharedMemoryCommandHandle;
1057
1058 pub fn b3GetMouseEventsData(
1059 physClient: b3PhysicsClientHandle,
1060 mouseEventsData: *mut b3MouseEventsData,
1061 );
1062 pub fn b3StateLoggingCommandInit(
1063 physClient: b3PhysicsClientHandle,
1064 ) -> b3SharedMemoryCommandHandle;
1065
1066 pub fn b3StateLoggingStart(
1067 commandHandle: b3SharedMemoryCommandHandle,
1068 loggingType: c_int,
1069 fileName: *const c_char,
1070 ) -> c_int;
1071
1072 pub fn b3StateLoggingAddLoggingObjectUniqueId(
1073 commandHandle: b3SharedMemoryCommandHandle,
1074 objectUniqueId: c_int,
1075 ) -> c_int;
1076
1077 pub fn b3StateLoggingSetMaxLogDof(
1078 commandHandle: b3SharedMemoryCommandHandle,
1079 maxLogDof: c_int,
1080 ) -> c_int;
1081
1082 pub fn b3StateLoggingSetLinkIndexA(
1083 commandHandle: b3SharedMemoryCommandHandle,
1084 linkIndexA: c_int,
1085 ) -> c_int;
1086
1087 pub fn b3StateLoggingSetLinkIndexB(
1088 commandHandle: b3SharedMemoryCommandHandle,
1089 linkIndexB: c_int,
1090 ) -> c_int;
1091
1092 pub fn b3StateLoggingSetBodyAUniqueId(
1093 commandHandle: b3SharedMemoryCommandHandle,
1094 bodyAUniqueId: c_int,
1095 ) -> c_int;
1096
1097 pub fn b3StateLoggingSetBodyBUniqueId(
1098 commandHandle: b3SharedMemoryCommandHandle,
1099 bodyBUniqueId: c_int,
1100 ) -> c_int;
1101
1102 pub fn b3StateLoggingSetDeviceTypeFilter(
1103 commandHandle: b3SharedMemoryCommandHandle,
1104 deviceTypeFilter: c_int,
1105 ) -> c_int;
1106
1107 pub fn b3StateLoggingSetLogFlags(
1108 commandHandle: b3SharedMemoryCommandHandle,
1109 logFlags: c_int,
1110 ) -> c_int;
1111
1112 pub fn b3GetStatusLoggingUniqueId(statusHandle: b3SharedMemoryStatusHandle) -> c_int;
1113
1114 pub fn b3StateLoggingStop(
1115 commandHandle: b3SharedMemoryCommandHandle,
1116 loggingUid: c_int,
1117 ) -> c_int;
1118
1119 pub fn b3ProfileTimingCommandInit(
1120 physClient: b3PhysicsClientHandle,
1121 name: *const c_char,
1122 ) -> b3SharedMemoryCommandHandle;
1123
1124 pub fn b3SetProfileTimingDuractionInMicroSeconds(
1125 commandHandle: b3SharedMemoryCommandHandle,
1126 duration: c_int,
1127 );
1128
1129 pub fn b3SetProfileTimingType(commandHandle: b3SharedMemoryCommandHandle, type_: c_int);
1130
1131 pub fn b3PushProfileTiming(physClient: b3PhysicsClientHandle, timingName: *const c_char);
1132
1133 pub fn b3PopProfileTiming(physClient: b3PhysicsClientHandle);
1134
1135 pub fn b3SetTimeOut(physClient: b3PhysicsClientHandle, timeOutInSeconds: f64);
1136
1137 pub fn b3GetTimeOut(physClient: b3PhysicsClientHandle) -> f64;
1138 #[doc = "We are currently not reading the sensor information from the URDF file, and programmatically assign sensors."]
1139 #[doc = "This is rather inconsistent, to mix programmatical creation with loading from file."]
1140 pub fn b3CreateSensorCommandInit(
1141 physClient: b3PhysicsClientHandle,
1142 bodyUniqueId: c_int,
1143 ) -> b3SharedMemoryCommandHandle;
1144
1145 pub fn b3CreateSensorEnable6DofJointForceTorqueSensor(
1146 commandHandle: b3SharedMemoryCommandHandle,
1147 jointIndex: c_int,
1148 enable: c_int,
1149 ) -> c_int;
1150 pub fn b3InitDebugDrawingCommand(
1151 physClient: b3PhysicsClientHandle,
1152 ) -> b3SharedMemoryCommandHandle;
1153
1154 pub fn b3SetDebugObjectColor(
1155 commandHandle: b3SharedMemoryCommandHandle,
1156 objectUniqueId: c_int,
1157 linkIndex: c_int,
1158 objectColorRGB: *const f64,
1159 );
1160 pub fn b3RemoveDebugObjectColor(
1161 commandHandle: b3SharedMemoryCommandHandle,
1162 objectUniqueId: c_int,
1163 linkIndex: c_int,
1164 );
1165
1166 #[doc = "the creation of collision shapes and rigid bodies etc is likely going to change,"]
1167 #[doc = "but good to have a b3CreateBoxShapeCommandInit for now"]
1168 pub fn b3CreateCollisionShapeCommandInit(
1169 physClient: b3PhysicsClientHandle,
1170 ) -> b3SharedMemoryCommandHandle;
1171
1172 pub fn b3CreateCollisionShapeAddSphere(
1173 commandHandle: b3SharedMemoryCommandHandle,
1174 radius: f64,
1175 ) -> c_int;
1176 pub fn b3CreateCollisionShapeAddBox(
1177 commandHandle: b3SharedMemoryCommandHandle,
1178 halfExtents: *const f64,
1179 ) -> c_int;
1180
1181 pub fn b3CreateCollisionShapeAddCapsule(
1182 commandHandle: b3SharedMemoryCommandHandle,
1183 radius: f64,
1184 height: f64,
1185 ) -> c_int;
1186
1187 pub fn b3CreateCollisionShapeAddCylinder(
1188 commandHandle: b3SharedMemoryCommandHandle,
1189 radius: f64,
1190 height: f64,
1191 ) -> c_int;
1192
1193 pub fn b3CreateCollisionShapeAddHeightfield(
1194 commandHandle: b3SharedMemoryCommandHandle,
1195 fileName: *const c_char,
1196 meshScale: *const f64,
1197 textureScaling: f64,
1198 ) -> c_int;
1199
1200 pub fn b3CreateCollisionShapeAddHeightfield2(
1201 physClient: b3PhysicsClientHandle,
1202 commandHandle: b3SharedMemoryCommandHandle,
1203 meshScale: *const f64,
1204 textureScaling: f64,
1205 heightfieldData: *mut f32,
1206 numHeightfieldRows: c_int,
1207 numHeightfieldColumns: c_int,
1208 replaceHeightfieldIndex: c_int,
1209 ) -> c_int;
1210
1211 pub fn b3CreateCollisionShapeAddPlane(
1212 commandHandle: b3SharedMemoryCommandHandle,
1213 planeNormal: *const f64,
1214 planeConstant: f64,
1215 ) -> c_int;
1216
1217 pub fn b3CreateCollisionShapeAddMesh(
1218 commandHandle: b3SharedMemoryCommandHandle,
1219 fileName: *const c_char,
1220 meshScale: *const f64,
1221 ) -> c_int;
1222
1223 pub fn b3CreateCollisionShapeAddConvexMesh(
1224 physClient: b3PhysicsClientHandle,
1225 commandHandle: b3SharedMemoryCommandHandle,
1226 meshScale: *const f64,
1227 vertices: *const f64,
1228 numVertices: c_int,
1229 ) -> c_int;
1230
1231 pub fn b3CreateCollisionShapeAddConcaveMesh(
1232 physClient: b3PhysicsClientHandle,
1233 commandHandle: b3SharedMemoryCommandHandle,
1234 meshScale: *const f64,
1235 vertices: *const f64,
1236 numVertices: c_int,
1237 indices: *const c_int,
1238 numIndices: c_int,
1239 ) -> c_int;
1240
1241 pub fn b3CreateCollisionSetFlag(
1242 commandHandle: b3SharedMemoryCommandHandle,
1243 shapeIndex: c_int,
1244 flags: c_int,
1245 );
1246
1247 pub fn b3CreateCollisionShapeSetChildTransform(
1248 commandHandle: b3SharedMemoryCommandHandle,
1249 shapeIndex: c_int,
1250 childPosition: *const f64,
1251 childOrientation: *const f64,
1252 );
1253 pub fn b3GetStatusCollisionShapeUniqueId(statusHandle: b3SharedMemoryStatusHandle) -> c_int;
1254
1255 pub fn b3InitRemoveCollisionShapeCommand(
1256 physClient: b3PhysicsClientHandle,
1257 collisionShapeId: c_int,
1258 ) -> b3SharedMemoryCommandHandle;
1259 pub fn b3CreateVisualShapeCommandInit(
1260 physClient: b3PhysicsClientHandle,
1261 ) -> b3SharedMemoryCommandHandle;
1262
1263 pub fn b3CreateVisualShapeAddSphere(
1264 commandHandle: b3SharedMemoryCommandHandle,
1265 radius: f64,
1266 ) -> c_int;
1267 pub fn b3CreateVisualShapeAddBox(
1268 commandHandle: b3SharedMemoryCommandHandle,
1269 halfExtents: *const f64,
1270 ) -> c_int;
1271
1272 pub fn b3CreateVisualShapeAddCapsule(
1273 commandHandle: b3SharedMemoryCommandHandle,
1274 radius: f64,
1275 height: f64,
1276 ) -> c_int;
1277
1278 pub fn b3CreateVisualShapeAddCylinder(
1279 commandHandle: b3SharedMemoryCommandHandle,
1280 radius: f64,
1281 height: f64,
1282 ) -> c_int;
1283
1284 pub fn b3CreateVisualShapeAddPlane(
1285 commandHandle: b3SharedMemoryCommandHandle,
1286 planeNormal: *const f64,
1287 planeConstant: f64,
1288 ) -> c_int;
1289
1290 pub fn b3CreateVisualShapeAddMesh(
1291 commandHandle: b3SharedMemoryCommandHandle,
1292 fileName: *const c_char,
1293 meshScale: *const f64,
1294 ) -> c_int;
1295
1296 pub fn b3CreateVisualShapeAddMesh2(
1297 physClient: b3PhysicsClientHandle,
1298 commandHandle: b3SharedMemoryCommandHandle,
1299 meshScale: *const f64,
1300 vertices: *const f64,
1301 numVertices: c_int,
1302 indices: *const c_int,
1303 numIndices: c_int,
1304 normals: *const f64,
1305 numNormals: c_int,
1306 uvs: *const f64,
1307 numUVs: c_int,
1308 ) -> c_int;
1309
1310 pub fn b3CreateVisualSetFlag(
1311 commandHandle: b3SharedMemoryCommandHandle,
1312 shapeIndex: c_int,
1313 flags: c_int,
1314 );
1315
1316 pub fn b3CreateVisualShapeSetChildTransform(
1317 commandHandle: b3SharedMemoryCommandHandle,
1318 shapeIndex: c_int,
1319 childPosition: *const f64,
1320 childOrientation: *const f64,
1321 );
1322
1323 pub fn b3CreateVisualShapeSetSpecularColor(
1324 commandHandle: b3SharedMemoryCommandHandle,
1325 shapeIndex: c_int,
1326 specularColor: *const f64,
1327 );
1328
1329 pub fn b3CreateVisualShapeSetRGBAColor(
1330 commandHandle: b3SharedMemoryCommandHandle,
1331 shapeIndex: c_int,
1332 rgbaColor: *const f64,
1333 );
1334
1335 pub fn b3GetStatusVisualShapeUniqueId(statusHandle: b3SharedMemoryStatusHandle) -> c_int;
1336
1337 pub fn b3CreateMultiBodyCommandInit(
1338 physClient: b3PhysicsClientHandle,
1339 ) -> b3SharedMemoryCommandHandle;
1340
1341 pub fn b3CreateMultiBodyBase(
1342 commandHandle: b3SharedMemoryCommandHandle,
1343 mass: f64,
1344 collisionShapeUnique: c_int,
1345 visualShapeUniqueId: c_int,
1346 basePosition: *const f64,
1347 baseOrientation: *const f64,
1348 baseInertialFramePosition: *const f64,
1349 baseInertialFrameOrientation: *const f64,
1350 ) -> c_int;
1351
1352 pub fn b3CreateMultiBodyLink(
1353 commandHandle: b3SharedMemoryCommandHandle,
1354 linkMass: f64,
1355 linkCollisionShapeIndex: f64,
1356 linkVisualShapeIndex: f64,
1357 linkPosition: *const f64,
1358 linkOrientation: *const f64,
1359 linkInertialFramePosition: *const f64,
1360 linkInertialFrameOrientation: *const f64,
1361 linkParentIndex: c_int,
1362 linkJointType: c_int,
1363 linkJointAxis: *const f64,
1364 ) -> c_int;
1365
1366 pub fn b3CreateMultiBodySetBatchPositions(
1367 physClient: b3PhysicsClientHandle,
1368 commandHandle: b3SharedMemoryCommandHandle,
1369 batchPositions: *mut f64,
1370 numBatchObjects: c_int,
1371 ) -> c_int;
1372
1373 pub fn b3CreateMultiBodyUseMaximalCoordinates(commandHandle: b3SharedMemoryCommandHandle);
1374
1375 pub fn b3CreateMultiBodySetFlags(commandHandle: b3SharedMemoryCommandHandle, flags: c_int);
1376
1377 #[doc = "request an contact point information"]
1378 pub fn b3InitRequestContactPointInformation(
1379 physClient: b3PhysicsClientHandle,
1380 ) -> b3SharedMemoryCommandHandle;
1381
1382 pub fn b3SetContactFilterBodyA(
1383 commandHandle: b3SharedMemoryCommandHandle,
1384 bodyUniqueIdA: c_int,
1385 );
1386
1387 pub fn b3SetContactFilterBodyB(
1388 commandHandle: b3SharedMemoryCommandHandle,
1389 bodyUniqueIdB: c_int,
1390 );
1391
1392 pub fn b3SetContactFilterLinkA(commandHandle: b3SharedMemoryCommandHandle, linkIndexA: c_int);
1393
1394 pub fn b3SetContactFilterLinkB(commandHandle: b3SharedMemoryCommandHandle, linkIndexB: c_int);
1395
1396 pub fn b3GetContactPointInformation(
1397 physClient: b3PhysicsClientHandle,
1398 contactPointData: *mut b3ContactInformation,
1399 );
1400
1401 #[doc = "compute the closest points between two bodies"]
1402 pub fn b3InitClosestDistanceQuery(
1403 physClient: b3PhysicsClientHandle,
1404 ) -> b3SharedMemoryCommandHandle;
1405
1406 pub fn b3SetClosestDistanceFilterBodyA(
1407 commandHandle: b3SharedMemoryCommandHandle,
1408 bodyUniqueIdA: c_int,
1409 );
1410
1411 pub fn b3SetClosestDistanceFilterLinkA(
1412 commandHandle: b3SharedMemoryCommandHandle,
1413 linkIndexA: c_int,
1414 );
1415
1416 pub fn b3SetClosestDistanceFilterBodyB(
1417 commandHandle: b3SharedMemoryCommandHandle,
1418 bodyUniqueIdB: c_int,
1419 );
1420
1421 pub fn b3SetClosestDistanceFilterLinkB(
1422 commandHandle: b3SharedMemoryCommandHandle,
1423 linkIndexB: c_int,
1424 );
1425
1426 pub fn b3SetClosestDistanceThreshold(commandHandle: b3SharedMemoryCommandHandle, distance: f64);
1427
1428 pub fn b3SetClosestDistanceFilterCollisionShapeA(
1429 commandHandle: b3SharedMemoryCommandHandle,
1430 collisionShapeA: c_int,
1431 );
1432
1433 pub fn b3SetClosestDistanceFilterCollisionShapeB(
1434 commandHandle: b3SharedMemoryCommandHandle,
1435 collisionShapeB: c_int,
1436 );
1437
1438 pub fn b3SetClosestDistanceFilterCollisionShapePositionA(
1439 commandHandle: b3SharedMemoryCommandHandle,
1440 collisionShapePositionA: *const f64,
1441 );
1442
1443 pub fn b3SetClosestDistanceFilterCollisionShapePositionB(
1444 commandHandle: b3SharedMemoryCommandHandle,
1445 collisionShapePositionB: *const f64,
1446 );
1447
1448 pub fn b3SetClosestDistanceFilterCollisionShapeOrientationA(
1449 commandHandle: b3SharedMemoryCommandHandle,
1450 collisionShapeOrientationA: *const f64,
1451 );
1452
1453 pub fn b3SetClosestDistanceFilterCollisionShapeOrientationB(
1454 commandHandle: b3SharedMemoryCommandHandle,
1455 collisionShapeOrientationB: *const f64,
1456 );
1457
1458 pub fn b3GetClosestPointInformation(
1459 physClient: b3PhysicsClientHandle,
1460 contactPointInfo: *mut b3ContactInformation,
1461 );
1462
1463 #[doc = "get all the bodies that touch a given axis aligned bounding box specified in world space (min and max coordinates)"]
1464 pub fn b3InitAABBOverlapQuery(
1465 physClient: b3PhysicsClientHandle,
1466 aabbMin: *const f64,
1467 aabbMax: *const f64,
1468 ) -> b3SharedMemoryCommandHandle;
1469
1470 pub fn b3GetAABBOverlapResults(physClient: b3PhysicsClientHandle, data: *mut b3AABBOverlapData);
1471 pub fn b3InitRequestVisualShapeInformation(
1472 physClient: b3PhysicsClientHandle,
1473 bodyUniqueIdA: c_int,
1474 ) -> b3SharedMemoryCommandHandle;
1475
1476 pub fn b3GetVisualShapeInformation(
1477 physClient: b3PhysicsClientHandle,
1478 visualShapeInfo: *mut b3VisualShapeInformation,
1479 );
1480
1481 pub fn b3InitRequestCollisionShapeInformation(
1482 physClient: b3PhysicsClientHandle,
1483 bodyUniqueId: c_int,
1484 linkIndex: c_int,
1485 ) -> b3SharedMemoryCommandHandle;
1486
1487 pub fn b3InitLoadTexture(
1493 physClient: b3PhysicsClientHandle,
1494 filename: *const c_char,
1495 ) -> b3SharedMemoryCommandHandle;
1496
1497 pub fn b3GetStatusTextureUniqueId(statusHandle: b3SharedMemoryStatusHandle) -> c_int;
1498
1499 pub fn b3CreateChangeTextureCommandInit(
1500 physClient: b3PhysicsClientHandle,
1501 textureUniqueId: c_int,
1502 width: c_int,
1503 height: c_int,
1504 rgbPixels: *const c_char,
1505 ) -> b3SharedMemoryCommandHandle;
1506
1507 pub fn b3InitUpdateVisualShape(
1508 physClient: b3PhysicsClientHandle,
1509 bodyUniqueId: c_int,
1510 jointIndex: c_int,
1511 shapeIndex: c_int,
1512 textureUniqueId: c_int,
1513 ) -> b3SharedMemoryCommandHandle;
1514
1515 pub fn b3InitUpdateVisualShape2(
1516 physClient: b3PhysicsClientHandle,
1517 bodyUniqueId: c_int,
1518 jointIndex: c_int,
1519 shapeIndex: c_int,
1520 ) -> b3SharedMemoryCommandHandle;
1521
1522 pub fn b3UpdateVisualShapeTexture(
1523 commandHandle: b3SharedMemoryCommandHandle,
1524 textureUniqueId: c_int,
1525 );
1526
1527 pub fn b3UpdateVisualShapeRGBAColor(
1528 commandHandle: b3SharedMemoryCommandHandle,
1529 rgbaColor: *const f64,
1530 );
1531
1532 pub fn b3UpdateVisualShapeFlags(commandHandle: b3SharedMemoryCommandHandle, flags: c_int);
1533
1534 pub fn b3UpdateVisualShapeSpecularColor(
1535 commandHandle: b3SharedMemoryCommandHandle,
1536 specularColor: *const f64,
1537 );
1538
1539 pub fn b3InitPhysicsParamCommand(
1540 physClient: b3PhysicsClientHandle,
1541 ) -> b3SharedMemoryCommandHandle;
1542
1543 pub fn b3InitPhysicsParamCommand2(
1544 commandHandle: b3SharedMemoryCommandHandle,
1545 ) -> b3SharedMemoryCommandHandle;
1546
1547 pub fn b3PhysicsParamSetGravity(
1548 commandHandle: b3SharedMemoryCommandHandle,
1549 gravx: f64,
1550 gravy: f64,
1551 gravz: f64,
1552 ) -> c_int;
1553
1554 pub fn b3PhysicsParamSetTimeStep(
1555 commandHandle: b3SharedMemoryCommandHandle,
1556 timeStep: f64,
1557 ) -> c_int;
1558
1559 pub fn b3PhysicsParamSetDefaultContactERP(
1560 commandHandle: b3SharedMemoryCommandHandle,
1561 defaultContactERP: f64,
1562 ) -> c_int;
1563
1564 pub fn b3PhysicsParamSetDefaultNonContactERP(
1565 commandHandle: b3SharedMemoryCommandHandle,
1566 defaultNonContactERP: f64,
1567 ) -> c_int;
1568
1569 pub fn b3PhysicsParamSetDefaultFrictionERP(
1570 commandHandle: b3SharedMemoryCommandHandle,
1571 frictionERP: f64,
1572 ) -> c_int;
1573
1574 pub fn b3PhysicsParamSetDefaultGlobalCFM(
1575 commandHandle: b3SharedMemoryCommandHandle,
1576 defaultGlobalCFM: f64,
1577 ) -> c_int;
1578
1579 pub fn b3PhysicsParamSetDefaultFrictionCFM(
1580 commandHandle: b3SharedMemoryCommandHandle,
1581 frictionCFM: f64,
1582 ) -> c_int;
1583
1584 pub fn b3PhysicsParamSetNumSubSteps(
1585 commandHandle: b3SharedMemoryCommandHandle,
1586 numSubSteps: c_int,
1587 ) -> c_int;
1588
1589 pub fn b3PhysicsParamSetRealTimeSimulation(
1590 commandHandle: b3SharedMemoryCommandHandle,
1591 enableRealTimeSimulation: c_int,
1592 ) -> c_int;
1593
1594 pub fn b3PhysicsParamSetNumSolverIterations(
1595 commandHandle: b3SharedMemoryCommandHandle,
1596 numSolverIterations: c_int,
1597 ) -> c_int;
1598
1599 pub fn b3PhysicsParamSetNumNonContactInnerIterations(
1600 commandHandle: b3SharedMemoryCommandHandle,
1601 numMotorIterations: c_int,
1602 ) -> c_int;
1603
1604 pub fn b3PhysicsParamSetWarmStartingFactor(
1605 commandHandle: b3SharedMemoryCommandHandle,
1606 warmStartingFactor: f64,
1607 ) -> c_int;
1608
1609 pub fn b3PhysicsParamSetArticulatedWarmStartingFactor(
1610 commandHandle: b3SharedMemoryCommandHandle,
1611 warmStartingFactor: f64,
1612 ) -> c_int;
1613
1614 pub fn b3PhysicsParamSetCollisionFilterMode(
1615 commandHandle: b3SharedMemoryCommandHandle,
1616 filterMode: c_int,
1617 ) -> c_int;
1618
1619 pub fn b3PhysicsParamSetUseSplitImpulse(
1620 commandHandle: b3SharedMemoryCommandHandle,
1621 useSplitImpulse: c_int,
1622 ) -> c_int;
1623
1624 pub fn b3PhysicsParamSetSplitImpulsePenetrationThreshold(
1625 commandHandle: b3SharedMemoryCommandHandle,
1626 splitImpulsePenetrationThreshold: f64,
1627 ) -> c_int;
1628
1629 pub fn b3PhysicsParamSetContactBreakingThreshold(
1630 commandHandle: b3SharedMemoryCommandHandle,
1631 contactBreakingThreshold: f64,
1632 ) -> c_int;
1633
1634 pub fn b3PhysicsParamSetMaxNumCommandsPer1ms(
1635 commandHandle: b3SharedMemoryCommandHandle,
1636 maxNumCmdPer1ms: c_int,
1637 ) -> c_int;
1638
1639 pub fn b3PhysicsParamSetEnableFileCaching(
1640 commandHandle: b3SharedMemoryCommandHandle,
1641 enableFileCaching: c_int,
1642 ) -> c_int;
1643
1644 pub fn b3PhysicsParamSetRestitutionVelocityThreshold(
1645 commandHandle: b3SharedMemoryCommandHandle,
1646 restitutionVelocityThreshold: f64,
1647 ) -> c_int;
1648
1649 pub fn b3PhysicsParamSetEnableConeFriction(
1650 commandHandle: b3SharedMemoryCommandHandle,
1651 enableConeFriction: c_int,
1652 ) -> c_int;
1653
1654 pub fn b3PhysicsParameterSetDeterministicOverlappingPairs(
1655 commandHandle: b3SharedMemoryCommandHandle,
1656 deterministicOverlappingPairs: c_int,
1657 ) -> c_int;
1658
1659 pub fn b3PhysicsParameterSetAllowedCcdPenetration(
1660 commandHandle: b3SharedMemoryCommandHandle,
1661 allowedCcdPenetration: f64,
1662 ) -> c_int;
1663
1664 pub fn b3PhysicsParameterSetJointFeedbackMode(
1665 commandHandle: b3SharedMemoryCommandHandle,
1666 jointFeedbackMode: c_int,
1667 ) -> c_int;
1668
1669 pub fn b3PhysicsParamSetSolverResidualThreshold(
1670 commandHandle: b3SharedMemoryCommandHandle,
1671 solverResidualThreshold: f64,
1672 ) -> c_int;
1673
1674 pub fn b3PhysicsParamSetContactSlop(
1675 commandHandle: b3SharedMemoryCommandHandle,
1676 contactSlop: f64,
1677 ) -> c_int;
1678
1679 pub fn b3PhysicsParameterSetEnableSAT(
1680 commandHandle: b3SharedMemoryCommandHandle,
1681 enableSAT: c_int,
1682 ) -> c_int;
1683
1684 pub fn b3PhysicsParameterSetConstraintSolverType(
1685 commandHandle: b3SharedMemoryCommandHandle,
1686 constraintSolverType: c_int,
1687 ) -> c_int;
1688
1689 pub fn b3PhysicsParameterSetMinimumSolverIslandSize(
1690 commandHandle: b3SharedMemoryCommandHandle,
1691 minimumSolverIslandSize: c_int,
1692 ) -> c_int;
1693
1694 pub fn b3PhysicsParamSetSolverAnalytics(
1695 commandHandle: b3SharedMemoryCommandHandle,
1696 reportSolverAnalytics: c_int,
1697 ) -> c_int;
1698
1699 pub fn b3PhysicsParameterSetSparseSdfVoxelSize(
1700 commandHandle: b3SharedMemoryCommandHandle,
1701 sparseSdfVoxelSize: f64,
1702 ) -> c_int;
1703
1704 pub fn b3InitRequestPhysicsParamCommand(
1705 physClient: b3PhysicsClientHandle,
1706 ) -> b3SharedMemoryCommandHandle;
1707
1708 pub fn b3GetStatusPhysicsSimulationParameters(
1709 statusHandle: b3SharedMemoryStatusHandle,
1710 params: *mut b3PhysicsSimulationParameters,
1711 ) -> c_int;
1712
1713 pub fn b3PhysicsParamSetInternalSimFlags(
1714 commandHandle: b3SharedMemoryCommandHandle,
1715 flags: c_int,
1716 ) -> c_int;
1717
1718 pub fn b3LoadSdfCommandInit(
1719 physClient: b3PhysicsClientHandle,
1720 sdfFileName: *const c_char,
1721 ) -> b3SharedMemoryCommandHandle;
1722
1723 pub fn b3LoadSdfCommandSetUseMultiBody(
1724 commandHandle: b3SharedMemoryCommandHandle,
1725 useMultiBody: c_int,
1726 ) -> c_int;
1727
1728 pub fn b3LoadSdfCommandSetUseGlobalScaling(
1729 commandHandle: b3SharedMemoryCommandHandle,
1730 globalScaling: f64,
1731 ) -> c_int;
1732
1733 pub fn b3SaveWorldCommandInit(
1734 physClient: b3PhysicsClientHandle,
1735 sdfFileName: *const c_char,
1736 ) -> b3SharedMemoryCommandHandle;
1737
1738 pub fn b3InitCreateUserConstraintCommand(
1739 physClient: b3PhysicsClientHandle,
1740 parentBodyUniqueId: c_int,
1741 parentJointIndex: c_int,
1742 childBodyUniqueId: c_int,
1743 childJointIndex: c_int,
1744 info: *mut b3JointInfo,
1745 ) -> b3SharedMemoryCommandHandle;
1746
1747 #[doc = "return a unique id for the user constraint, after successful creation, or -1 for an invalid constraint id"]
1748 pub fn b3GetStatusUserConstraintUniqueId(statusHandle: b3SharedMemoryStatusHandle) -> c_int;
1749
1750 #[doc = "change parameters of an existing user constraint"]
1751 pub fn b3InitChangeUserConstraintCommand(
1752 physClient: b3PhysicsClientHandle,
1753 userConstraintUniqueId: c_int,
1754 ) -> b3SharedMemoryCommandHandle;
1755
1756 pub fn b3InitChangeUserConstraintSetPivotInB(
1757 commandHandle: b3SharedMemoryCommandHandle,
1758 jointChildPivot: *const f64,
1759 ) -> c_int;
1760
1761 pub fn b3InitChangeUserConstraintSetFrameInB(
1762 commandHandle: b3SharedMemoryCommandHandle,
1763 jointChildFrameOrn: *const f64,
1764 ) -> c_int;
1765
1766 pub fn b3InitChangeUserConstraintSetMaxForce(
1767 commandHandle: b3SharedMemoryCommandHandle,
1768 maxAppliedForce: f64,
1769 ) -> c_int;
1770
1771 pub fn b3InitChangeUserConstraintSetGearRatio(
1772 commandHandle: b3SharedMemoryCommandHandle,
1773 gearRatio: f64,
1774 ) -> c_int;
1775
1776 pub fn b3InitChangeUserConstraintSetGearAuxLink(
1777 commandHandle: b3SharedMemoryCommandHandle,
1778 gearAuxLink: c_int,
1779 ) -> c_int;
1780
1781 pub fn b3InitChangeUserConstraintSetRelativePositionTarget(
1782 commandHandle: b3SharedMemoryCommandHandle,
1783 relativePositionTarget: f64,
1784 ) -> c_int;
1785
1786 pub fn b3InitChangeUserConstraintSetERP(
1787 commandHandle: b3SharedMemoryCommandHandle,
1788 erp: f64,
1789 ) -> c_int;
1790
1791 pub fn b3InitRemoveUserConstraintCommand(
1792 physClient: b3PhysicsClientHandle,
1793 userConstraintUniqueId: c_int,
1794 ) -> b3SharedMemoryCommandHandle;
1795
1796 pub fn b3GetNumUserConstraints(physClient: b3PhysicsClientHandle) -> c_int;
1797
1798 pub fn b3InitGetUserConstraintStateCommand(
1799 physClient: b3PhysicsClientHandle,
1800 constraintUniqueId: c_int,
1801 ) -> b3SharedMemoryCommandHandle;
1802
1803 pub fn b3GetStatusUserConstraintState(
1804 statusHandle: b3SharedMemoryStatusHandle,
1805 constraintState: *mut b3UserConstraintState,
1806 ) -> c_int;
1807
1808 pub fn b3GetUserConstraintInfo(
1809 physClient: b3PhysicsClientHandle,
1810 constraintUniqueId: c_int,
1811 info: *mut b3UserConstraint,
1812 ) -> c_int;
1813 #[doc = " return the user constraint id, given the index in range [0 , b3GetNumUserConstraints() )"]
1814 pub fn b3GetUserConstraintId(physClient: b3PhysicsClientHandle, serialIndex: c_int) -> c_int;
1815}
1816
1817#[repr(C)]
1818#[derive(Clone, Copy)]
1819pub enum eURDF_Flags {
1820 URDF_USE_INERTIA_FROM_FILE = 2,
1821 URDF_USE_SELF_COLLISION = 8,
1822 URDF_USE_SELF_COLLISION_EXCLUDE_PARENT = 16,
1823 URDF_USE_SELF_COLLISION_EXCLUDE_ALL_PARENTS = 32,
1824 URDF_RESERVED = 64,
1825 URDF_USE_IMPLICIT_CYLINDER = 128,
1826 URDF_GLOBAL_VELOCITIES_MB = 256,
1827 MJCF_COLORS_FROM_FILE = 512,
1828 URDF_ENABLE_CACHED_GRAPHICS_SHAPES = 1024,
1829 URDF_ENABLE_SLEEPING = 2048,
1830 URDF_INITIALIZE_SAT_FEATURES = 4096,
1831 URDF_USE_SELF_COLLISION_INCLUDE_PARENT = 8192,
1832 URDF_PARSE_SENSORS = 16384,
1833 URDF_USE_MATERIAL_COLORS_FROM_MTL = 32768,
1834 URDF_USE_MATERIAL_TRANSPARANCY_FROM_MTL = 65536,
1835 URDF_MAINTAIN_LINK_ORDER = 131072,
1836 URDF_ENABLE_WAKEUP = 262144,
1837}
1838
1839#[repr(C)]
1840pub enum EnumSharedMemoryServerStatus {
1841 CMD_SHARED_MEMORY_NOT_INITIALIZED = 0,
1842 CMD_WAITING_FOR_CLIENT_COMMAND,
1843 CMD_CLIENT_COMMAND_COMPLETED,
1844 CMD_UNKNOWN_COMMAND_FLUSHED,
1845 CMD_SDF_LOADING_COMPLETED,
1846 CMD_SDF_LOADING_FAILED,
1847 CMD_URDF_LOADING_COMPLETED,
1848 CMD_URDF_LOADING_FAILED,
1849 CMD_BULLET_LOADING_COMPLETED,
1850 CMD_BULLET_LOADING_FAILED,
1851 CMD_BULLET_SAVING_COMPLETED,
1852 CMD_BULLET_SAVING_FAILED,
1853 CMD_MJCF_LOADING_COMPLETED,
1854 CMD_MJCF_LOADING_FAILED,
1855 CMD_REQUEST_INTERNAL_DATA_COMPLETED,
1856 CMD_REQUEST_INTERNAL_DATA_FAILED,
1857 CMD_BULLET_DATA_STREAM_RECEIVED_COMPLETED,
1858 CMD_BULLET_DATA_STREAM_RECEIVED_FAILED,
1859 CMD_BOX_COLLISION_SHAPE_CREATION_COMPLETED,
1860 CMD_RIGID_BODY_CREATION_COMPLETED,
1861 CMD_SET_JOINT_FEEDBACK_COMPLETED,
1862 CMD_ACTUAL_STATE_UPDATE_COMPLETED,
1863 CMD_ACTUAL_STATE_UPDATE_FAILED,
1864 CMD_DEBUG_LINES_COMPLETED,
1865 CMD_DEBUG_LINES_OVERFLOW_FAILED,
1866 CMD_DESIRED_STATE_RECEIVED_COMPLETED,
1867 CMD_STEP_FORWARD_SIMULATION_COMPLETED,
1868 CMD_RESET_SIMULATION_COMPLETED,
1869 CMD_CAMERA_IMAGE_COMPLETED,
1870 CMD_CAMERA_IMAGE_FAILED,
1871 CMD_BODY_INFO_COMPLETED,
1872 CMD_BODY_INFO_FAILED,
1873 CMD_INVALID_STATUS,
1874 CMD_CALCULATED_INVERSE_DYNAMICS_COMPLETED,
1875 CMD_CALCULATED_INVERSE_DYNAMICS_FAILED,
1876 CMD_CALCULATED_JACOBIAN_COMPLETED,
1877 CMD_CALCULATED_JACOBIAN_FAILED,
1878 CMD_CALCULATED_MASS_MATRIX_COMPLETED,
1879 CMD_CALCULATED_MASS_MATRIX_FAILED,
1880 CMD_CONTACT_POINT_INFORMATION_COMPLETED,
1881 CMD_CONTACT_POINT_INFORMATION_FAILED,
1882 CMD_REQUEST_AABB_OVERLAP_COMPLETED,
1883 CMD_REQUEST_AABB_OVERLAP_FAILED,
1884 CMD_CALCULATE_INVERSE_KINEMATICS_COMPLETED,
1885 CMD_CALCULATE_INVERSE_KINEMATICS_FAILED,
1886 CMD_SAVE_WORLD_COMPLETED,
1887 CMD_SAVE_WORLD_FAILED,
1888 CMD_VISUAL_SHAPE_INFO_COMPLETED,
1889 CMD_VISUAL_SHAPE_INFO_FAILED,
1890 CMD_VISUAL_SHAPE_UPDATE_COMPLETED,
1891 CMD_VISUAL_SHAPE_UPDATE_FAILED,
1892 CMD_LOAD_TEXTURE_COMPLETED,
1893 CMD_LOAD_TEXTURE_FAILED,
1894 CMD_USER_DEBUG_DRAW_COMPLETED,
1895 CMD_USER_DEBUG_DRAW_PARAMETER_COMPLETED,
1896 CMD_USER_DEBUG_DRAW_FAILED,
1897 CMD_USER_CONSTRAINT_COMPLETED,
1898 CMD_USER_CONSTRAINT_INFO_COMPLETED,
1899 CMD_USER_CONSTRAINT_REQUEST_STATE_COMPLETED,
1900 CMD_REMOVE_USER_CONSTRAINT_COMPLETED,
1901 CMD_CHANGE_USER_CONSTRAINT_COMPLETED,
1902 CMD_REMOVE_USER_CONSTRAINT_FAILED,
1903 CMD_CHANGE_USER_CONSTRAINT_FAILED,
1904 CMD_USER_CONSTRAINT_FAILED,
1905 CMD_REQUEST_VR_EVENTS_DATA_COMPLETED,
1906 CMD_REQUEST_RAY_CAST_INTERSECTIONS_COMPLETED,
1907 CMD_SYNC_BODY_INFO_COMPLETED,
1908 CMD_SYNC_BODY_INFO_FAILED,
1909 CMD_STATE_LOGGING_COMPLETED,
1910 CMD_STATE_LOGGING_START_COMPLETED,
1911 CMD_STATE_LOGGING_FAILED,
1912 CMD_REQUEST_KEYBOARD_EVENTS_DATA_COMPLETED,
1913 CMD_REQUEST_KEYBOARD_EVENTS_DATA_FAILED,
1914 CMD_REQUEST_OPENGL_VISUALIZER_CAMERA_FAILED,
1915 CMD_REQUEST_OPENGL_VISUALIZER_CAMERA_COMPLETED,
1916 CMD_REMOVE_BODY_COMPLETED,
1917 CMD_REMOVE_BODY_FAILED,
1918 CMD_GET_DYNAMICS_INFO_COMPLETED,
1919 CMD_GET_DYNAMICS_INFO_FAILED,
1920 CMD_CREATE_COLLISION_SHAPE_FAILED,
1921 CMD_CREATE_COLLISION_SHAPE_COMPLETED,
1922 CMD_CREATE_VISUAL_SHAPE_FAILED,
1923 CMD_CREATE_VISUAL_SHAPE_COMPLETED,
1924 CMD_CREATE_MULTI_BODY_FAILED,
1925 CMD_CREATE_MULTI_BODY_COMPLETED,
1926 CMD_REQUEST_COLLISION_INFO_COMPLETED,
1927 CMD_REQUEST_COLLISION_INFO_FAILED,
1928 CMD_REQUEST_MOUSE_EVENTS_DATA_COMPLETED,
1929 CMD_CHANGE_TEXTURE_COMMAND_FAILED,
1930 CMD_CUSTOM_COMMAND_COMPLETED,
1931 CMD_CUSTOM_COMMAND_FAILED,
1932 CMD_REQUEST_PHYSICS_SIMULATION_PARAMETERS_COMPLETED,
1933 CMD_SAVE_STATE_FAILED,
1934 CMD_SAVE_STATE_COMPLETED,
1935 CMD_RESTORE_STATE_FAILED,
1936 CMD_RESTORE_STATE_COMPLETED,
1937 CMD_COLLISION_SHAPE_INFO_COMPLETED,
1938 CMD_COLLISION_SHAPE_INFO_FAILED,
1939 CMD_LOAD_SOFT_BODY_FAILED,
1940 CMD_LOAD_SOFT_BODY_COMPLETED,
1941
1942 CMD_SYNC_USER_DATA_COMPLETED,
1943 CMD_SYNC_USER_DATA_FAILED,
1944 CMD_REQUEST_USER_DATA_COMPLETED,
1945 CMD_REQUEST_USER_DATA_FAILED,
1946 CMD_ADD_USER_DATA_COMPLETED,
1947 CMD_ADD_USER_DATA_FAILED,
1948 CMD_REMOVE_USER_DATA_COMPLETED,
1949 CMD_REMOVE_USER_DATA_FAILED,
1950 CMD_REMOVE_STATE_COMPLETED,
1951 CMD_REMOVE_STATE_FAILED,
1952
1953 CMD_REQUEST_MESH_DATA_COMPLETED,
1954 CMD_REQUEST_MESH_DATA_FAILED,
1955
1956 CMD_MAX_SERVER_COMMANDS,
1957}
1958
1959#[repr(C)]
1960#[derive(Debug)]
1961pub struct b3JointInfo {
1962 pub m_link_name: [c_char; 1024],
1963 pub m_joint_name: [c_char; 1024],
1964 pub m_joint_type: i32,
1965 pub m_q_index: i32,
1966 pub m_u_index: i32,
1967 pub m_joint_index: i32,
1968 pub m_flags: i32,
1969 pub m_joint_damping: f64,
1970 pub m_joint_friction: f64,
1971 pub m_joint_lower_limit: f64,
1972 pub m_joint_upper_limit: f64,
1973 pub m_joint_max_force: f64,
1974 pub m_joint_max_velocity: f64,
1975 pub m_parent_frame: [f64; 7],
1976 pub m_child_frame: [f64; 7],
1977 pub m_joint_axis: [f64; 3],
1978 pub m_parent_index: i32,
1979 pub m_q_size: i32,
1980 pub m_u_size: i32,
1981}
1982impl Default for b3JointInfo {
1983 fn default() -> Self {
1984 b3JointInfo {
1985 m_link_name: [2; 1024],
1986 m_joint_name: [2; 1024],
1987 m_joint_type: 0,
1988 m_q_index: 0,
1989 m_u_index: 0,
1990 m_joint_index: 0,
1991 m_flags: 0,
1992 m_joint_damping: 0.0,
1993 m_joint_friction: 0.0,
1994 m_joint_lower_limit: 0.0,
1995 m_joint_upper_limit: 0.0,
1996 m_joint_max_force: 0.0,
1997 m_joint_max_velocity: 0.0,
1998 m_parent_frame: [0.; 7],
1999 m_child_frame: [0.; 7],
2000 m_joint_axis: [0.; 3],
2001 m_parent_index: 0,
2002 m_q_size: 0,
2003 m_u_size: 0,
2004 }
2005 }
2006}
2007
2008#[repr(C)]
2009#[derive(Debug, Default, Copy, Clone)]
2010pub struct b3JointSensorState {
2011 pub m_joint_position: f64,
2012 pub m_joint_velocity: f64,
2013 pub m_joint_force_torque: [f64; 6],
2014 pub m_joint_motor_torque: f64,
2015}
2016
2017#[repr(C)]
2018#[derive(Debug, Default)]
2019pub struct b3JointSensorState2 {
2020 pub m_joint_position: [f64; 4],
2021 pub m_joint_velocity: [f64; 3],
2022 pub m_joint_reaction_force_torque: [f64; 6],
2023 pub m_joint_motor_torque_multi_dof: [f64; 3],
2024 pub m_q_dof_size: c_int,
2025 pub m_u_dof_size: c_int,
2026}
2027
2028#[repr(C)]
2029#[derive(Debug, Default)]
2030pub struct b3LinkState {
2031 pub m_world_position: [f64; 3],
2032 pub m_world_orientation: [f64; 4],
2033 pub m_local_inertial_position: [f64; 3],
2034 pub m_local_inertial_orientation: [f64; 4],
2035 pub m_world_link_frame_position: [f64; 3],
2036 pub m_world_link_frame_orientation: [f64; 4],
2037 pub m_world_linear_velocity: [f64; 3],
2039 pub m_world_angular_velocity: [f64; 3],
2041
2042 pub m_world_aabb_min: [f64; 3],
2043 pub m_world_aabb_max: [f64; 3],
2044}
2045
2046#[repr(C)]
2047#[derive(Copy, Clone)]
2048pub struct b3BodyInfo {
2049 pub m_baseName: [c_char; 1024usize],
2050 pub m_bodyName: [c_char; 1024usize],
2051}
2052#[repr(C)]
2053#[derive(Debug)]
2054pub struct b3CameraImageData {
2055 pub m_pixel_width: c_int,
2056 pub m_pixel_height: c_int,
2057 pub m_rgb_color_data: *const c_uchar,
2058 pub m_depth_values: *const f32,
2059 pub m_segmentation_mask_values: *const c_int,
2060}
2061
2062impl Default for b3CameraImageData {
2063 fn default() -> Self {
2064 b3CameraImageData {
2065 m_pixel_width: 0,
2066 m_pixel_height: 0,
2067 m_rgb_color_data: &(0_u8),
2068 m_depth_values: &(0_f32),
2069 m_segmentation_mask_values: &0,
2070 }
2071 }
2072}
2073
2074#[repr(C)]
2075#[derive(Debug, Copy, Clone)]
2076pub struct b3KeyboardEventsData {
2077 pub m_numKeyboardEvents: c_int,
2078 pub m_keyboardEvents: *mut b3KeyboardEvent,
2079}
2080
2081impl Default for b3KeyboardEventsData {
2082 fn default() -> Self {
2083 b3KeyboardEventsData {
2084 m_numKeyboardEvents: 0,
2085 m_keyboardEvents: [].as_mut_ptr(),
2086 }
2087 }
2088}
2089
2090#[repr(C)]
2091#[derive(Debug, Copy, Clone, Default)]
2092pub struct b3KeyboardEvent {
2093 pub m_keyCode: c_int,
2094 pub m_keyState: c_int,
2095}
2096
2097#[repr(C)]
2098#[derive(Debug, Copy, Clone)]
2099pub struct b3MouseEventsData {
2100 pub m_numMouseEvents: c_int,
2101 pub m_mouseEvents: *mut b3MouseEvent,
2102}
2103
2104impl Default for b3MouseEventsData {
2105 fn default() -> Self {
2106 b3MouseEventsData {
2107 m_numMouseEvents: 0,
2108 m_mouseEvents: [].as_mut_ptr(),
2109 }
2110 }
2111}
2112
2113#[repr(C)]
2114#[derive(Debug, Copy, Clone)]
2115pub struct b3MouseEvent {
2116 pub m_eventType: c_int,
2117 pub m_mousePosX: f32,
2118 pub m_mousePosY: f32,
2119 pub m_buttonIndex: c_int,
2120 pub m_buttonState: c_int,
2121}
2122
2123pub const B3_MAX_NUM_INDICES: usize = if cfg!(target_os = "macos") {
2124 32768
2125} else {
2126 524288
2127};
2128pub const B3_MAX_NUM_VERTICES: usize = if cfg!(target_os = "macos") {
2129 8192
2130} else {
2131 131072
2132};
2133#[repr(C)]
2134#[derive(Debug, Copy, Clone)]
2135pub struct b3VisualShapeInformation {
2136 pub m_numVisualShapes: c_int,
2137 pub m_visualShapeData: *mut b3VisualShapeData,
2138}
2139impl Default for b3VisualShapeInformation {
2140 fn default() -> Self {
2141 b3VisualShapeInformation {
2142 m_numVisualShapes: 0,
2143 m_visualShapeData: [].as_mut_ptr(),
2144 }
2145 }
2146}
2147impl Default for b3VisualShapeData {
2148 fn default() -> Self {
2149 b3VisualShapeData {
2150 m_objectUniqueId: 0,
2151 m_linkIndex: 0,
2152 m_visualGeometryType: 0,
2153 m_dimensions: [0.; 3],
2154 m_meshAssetFileName: [0; 1024],
2155 m_localVisualFrame: [0.; 7],
2156 m_rgbaColor: [0.; 4],
2157 m_tinyRendererTextureId: 0,
2158 m_textureUniqueId: 0,
2159 m_openglTextureId: 0,
2160 }
2161 }
2162}
2163#[repr(C)]
2164#[derive(Copy, Clone)]
2165pub struct b3VisualShapeData {
2166 pub m_objectUniqueId: c_int,
2167 pub m_linkIndex: c_int,
2168 pub m_visualGeometryType: c_int,
2169 pub m_dimensions: [f64; 3usize],
2170 pub m_meshAssetFileName: [c_char; 1024usize],
2171 pub m_localVisualFrame: [f64; 7usize],
2172 pub m_rgbaColor: [f64; 4usize],
2173 pub m_tinyRendererTextureId: c_int,
2174 pub m_textureUniqueId: c_int,
2175 pub m_openglTextureId: c_int,
2176}
2177#[repr(C)]
2178#[derive(Debug, Copy, Clone)]
2179pub struct b3UserConstraint {
2180 pub m_parentBodyIndex: c_int,
2181 pub m_parentJointIndex: c_int,
2182 pub m_childBodyIndex: c_int,
2183 pub m_childJointIndex: c_int,
2184 pub m_parentFrame: [f64; 7usize],
2185 pub m_childFrame: [f64; 7usize],
2186 pub m_jointAxis: [f64; 3usize],
2187 pub m_jointType: c_int,
2188 pub m_maxAppliedForce: f64,
2189 pub m_userConstraintUniqueId: c_int,
2190 pub m_gearRatio: f64,
2191 pub m_gearAuxLink: c_int,
2192 pub m_relativePositionTarget: f64,
2193 pub m_erp: f64,
2194}
2195impl Default for b3UserConstraint {
2196 fn default() -> Self {
2197 b3UserConstraint {
2198 m_parentBodyIndex: 0,
2199 m_parentJointIndex: 0,
2200 m_childBodyIndex: 0,
2201 m_childJointIndex: 0,
2202 m_parentFrame: [0.; 7],
2203 m_childFrame: [0.; 7],
2204 m_jointAxis: [0.; 3],
2205 m_jointType: 0,
2206 m_maxAppliedForce: 0.0,
2207 m_userConstraintUniqueId: 0,
2208 m_gearRatio: 0.0,
2209 m_gearAuxLink: 0,
2210 m_relativePositionTarget: 0.0,
2211 m_erp: 0.0,
2212 }
2213 }
2214}
2215#[repr(C)]
2216#[derive(Debug, Copy, Clone)]
2217pub struct b3UserConstraintState {
2218 pub m_appliedConstraintForces: [f64; 6usize],
2219 pub m_numDofs: c_int,
2220}
2221impl Default for b3UserConstraintState {
2222 fn default() -> Self {
2223 b3UserConstraintState {
2224 m_appliedConstraintForces: [0.; 6],
2225 m_numDofs: 0,
2226 }
2227 }
2228}
2229#[repr(C)]
2230#[derive(Debug, Copy, Clone)]
2231pub struct b3DynamicsInfo {
2232 pub m_mass: f64,
2233 pub m_localInertialDiagonal: [f64; 3usize],
2234 pub m_localInertialFrame: [f64; 7usize],
2235 pub m_lateralFrictionCoeff: f64,
2236 pub m_rollingFrictionCoeff: f64,
2237 pub m_spinningFrictionCoeff: f64,
2238 pub m_restitution: f64,
2239 pub m_contactStiffness: f64,
2240 pub m_contactDamping: f64,
2241 pub m_activationState: c_int,
2242 pub m_bodyType: c_int,
2243 pub m_angularDamping: f64,
2244 pub m_linearDamping: f64,
2245 pub m_ccdSweptSphereRadius: f64,
2246 pub m_contactProcessingThreshold: f64,
2247 pub m_frictionAnchor: c_int,
2248 pub m_collisionMargin: f64,
2249 pub m_dynamicType: c_int,
2250}
2251#[repr(C)]
2252#[derive(Debug, Copy, Clone)]
2253pub struct b3AABBOverlapData {
2254 pub m_numOverlappingObjects: c_int,
2255 pub m_overlappingObjects: *mut b3OverlappingObject,
2256}
2257#[repr(C)]
2258#[derive(Debug, Copy, Clone)]
2259pub struct b3OverlappingObject {
2260 pub m_objectUniqueId: c_int,
2261 pub m_linkIndex: c_int,
2262}
2263#[repr(C)]
2264#[derive(Debug, Copy, Clone)]
2265pub struct b3ContactInformation {
2266 pub m_numContactPoints: c_int,
2267 pub m_contactPointData: *mut b3ContactPointData,
2268}
2269#[repr(C)]
2270#[derive(Debug, Copy, Clone)]
2271pub struct b3ContactPointData {
2272 pub m_contactFlags: c_int,
2273 pub m_bodyUniqueIdA: c_int,
2274 pub m_bodyUniqueIdB: c_int,
2275 pub m_linkIndexA: c_int,
2276 pub m_linkIndexB: c_int,
2277 pub m_positionOnAInWS: [f64; 3usize],
2278 pub m_positionOnBInWS: [f64; 3usize],
2279 pub m_contactNormalOnBInWS: [f64; 3usize],
2280 pub m_contactDistance: f64,
2281 pub m_normalForce: f64,
2282 pub m_linearFrictionForce1: f64,
2283 pub m_linearFrictionForce2: f64,
2284 pub m_linearFrictionDirection1: [f64; 3usize],
2285 pub m_linearFrictionDirection2: [f64; 3usize],
2286}
2287
2288#[repr(C)]
2289#[derive(Debug, Default, Copy, Clone)]
2290pub struct b3PhysicsSimulationParameters {
2291 pub m_deltaTime: f64,
2292 pub m_simulationTimestamp: f64,
2293 pub m_gravityAcceleration: [f64; 3usize],
2294 pub m_numSimulationSubSteps: c_int,
2295 pub m_numSolverIterations: c_int,
2296 pub m_warmStartingFactor: f64,
2297 pub m_articulatedWarmStartingFactor: f64,
2298 pub m_useRealTimeSimulation: c_int,
2299 pub m_useSplitImpulse: c_int,
2300 pub m_splitImpulsePenetrationThreshold: f64,
2301 pub m_contactBreakingThreshold: f64,
2302 pub m_internalSimFlags: c_int,
2303 pub m_defaultContactERP: f64,
2304 pub m_collisionFilterMode: c_int,
2305 pub m_enableFileCaching: c_int,
2306 pub m_restitutionVelocityThreshold: f64,
2307 pub m_defaultNonContactERP: f64,
2308 pub m_frictionERP: f64,
2309 pub m_defaultGlobalCFM: f64,
2310 pub m_frictionCFM: f64,
2311 pub m_enableConeFriction: c_int,
2312 pub m_deterministicOverlappingPairs: c_int,
2313 pub m_allowedCcdPenetration: f64,
2314 pub m_jointFeedbackMode: c_int,
2315 pub m_solverResidualThreshold: f64,
2316 pub m_contactSlop: f64,
2317 pub m_enableSAT: c_int,
2318 pub m_constraintSolverType: c_int,
2319 pub m_minimumSolverIslandSize: c_int,
2320 pub m_reportSolverAnalytics: c_int,
2321 pub m_sparseSdfVoxelSize: f64,
2322 pub m_numNonContactInnerIterations: c_int,
2323}
2324
2325#[repr(C)]
2326#[derive(Debug, Default, Copy, Clone)]
2327pub struct b3OpenGLVisualizerCameraInfo {
2328 pub m_width: c_int,
2329 pub m_height: c_int,
2330 pub m_viewMatrix: [f32; 16usize],
2331 pub m_projectionMatrix: [f32; 16usize],
2332 pub m_camUp: [f32; 3usize],
2333 pub m_camForward: [f32; 3usize],
2334 pub m_horizontal: [f32; 3usize],
2335 pub m_vertical: [f32; 3usize],
2336 pub m_yaw: f32,
2337 pub m_pitch: f32,
2338 pub m_dist: f32,
2339 pub m_target: [f32; 3usize],
2340}
2341
2342#[repr(C)]
2343#[derive(Debug, Copy, Clone)]
2344pub struct b3RaycastInformation {
2345 pub m_numRayHits: c_int,
2346 pub m_rayHits: *mut b3RayHitInfo,
2347}
2348impl Default for b3RaycastInformation {
2349 fn default() -> Self {
2350 b3RaycastInformation {
2351 m_numRayHits: 0,
2352 m_rayHits: [].as_mut_ptr(),
2353 }
2354 }
2355}
2356#[repr(C)]
2357#[derive(Debug, Default, Copy, Clone)]
2358pub struct b3RayHitInfo {
2359 pub m_hitFraction: f64,
2360 pub m_hitObjectUniqueId: c_int,
2361 pub m_hitObjectLinkIndex: c_int,
2362 pub m_hitPositionWorld: [f64; 3usize],
2363 pub m_hitNormalWorld: [f64; 3usize],
2364}
2365pub const MAX_RAY_INTERSECTION_BATCH_SIZE_STREAMING: usize = 16384;