pub struct PhysicsClient { /* private fields */ }Implementations§
Source§impl PhysicsClient
! =====================================================================================================================================
impl PhysicsClient
! =====================================================================================================================================
§Connection & Session
| API | Status | Notes |
|---|---|---|
| connect | Implemented | PhysicsClient::connect covers all modes in scope |
| disconnect | Implemented | PhysicsClient::disconnectPhysicsServer + Drop |
| getConnectionInfo | Implemented | Requires client/server introspection |
| isConnected | Implemented | Uses b3CanSubmitCommand |
Sourcepub fn connect(mode: Mode) -> BulletResult<Self>
pub fn connect(mode: Mode) -> BulletResult<Self>
Connect to an existing physics server (using shared memory by default).
- connect(method,
key=SHARED_MEMORY_KEY, options=‘’) - connect(method, hostname=‘localhost’, port=1234, options=‘’)
pub fn get_connection_info(&mut self) -> BulletResult<String>
Sourcepub fn disconnect(self)
pub fn disconnect(self)
“Disconnect from the physics server.”
pub fn is_connected(&mut self) -> bool
Source§impl PhysicsClient
! =====================================================================================================================================
impl PhysicsClient
! =====================================================================================================================================
§Simulation Parameters
| API | Status | Notes |
|---|---|---|
| resetSimulation | Implemented | Core reset command |
| stepSimulation | Implemented | Core stepping command |
| performCollisionDetection | Implemented | Extra collision command |
| setGravity | Implemented | Physics param command |
| setTimeStep | Implemented | Physics param command |
| setDefaultContactERP | Implemented | Physics param command |
| setRealTimeSimulation | Implemented | Physics param command |
| setPhysicsEngineParameter | Implemented | Bulk physics-param configuration |
| getPhysicsEngineParameters | Implemented | Query mirror of above |
| setInternalSimFlags | Implemented | Expert-only flagging |
Sourcepub fn reset_simulation(&mut self) -> BulletResult<()>
pub fn reset_simulation(&mut self) -> BulletResult<()>
reset_simulation will remove all objects from the world and reset the world to initial conditions.
Sourcepub fn step_simulation(&mut self) -> BulletResult<()>
pub fn step_simulation(&mut self) -> BulletResult<()>
Performs all the actions in a single forward dynamics simulation step such as collision detection, constraint solving, and integration. TODO: Return analytics data?
pub fn perform_collision_detection(&mut self) -> BulletResult<()>
Sourcepub fn set_gravity(
&mut self,
grav: impl Into<[f64; 3]>,
) -> BulletResult<&mut Self>
pub fn set_gravity( &mut self, grav: impl Into<[f64; 3]>, ) -> BulletResult<&mut Self>
Sets the default gravity force for all objects.
By default, there is no gravitational force enabled.
§Arguments
gravity- a gravity vector. Can be a [f64;3]-array or anything else that can be converted into [f64; 3].
Sourcepub fn set_time_step(&mut self, time_step: Duration) -> BulletResult<&mut Self>
pub fn set_time_step(&mut self, time_step: Duration) -> BulletResult<&mut Self>
Warning: in many cases it is best to leave the timeStep to default, which is 240Hz. Several parameters are tuned with this value in mind. For example the number of solver iterations and the error reduction parameters (erp) for contact, friction and non-contact joints are related to the time step. If you change the time step, you may need to re-tune those values accordingly, especially the erp values.
You can set the physics engine timestep that is used when calling
step_simulation.
It is best to only call this method at the start of a simulation.
Don’t change this time step regularly.
Sourcepub fn set_default_contact_erp(
&mut self,
default_contact_erp: f64,
) -> BulletResult<&mut Self>
pub fn set_default_contact_erp( &mut self, default_contact_erp: f64, ) -> BulletResult<&mut Self>
Update the global default contact ERP (error reduction parameter).
Sourcepub fn set_real_time_simulation(
&mut self,
enable: bool,
) -> BulletResult<&mut Self>
pub fn set_real_time_simulation( &mut self, enable: bool, ) -> BulletResult<&mut Self>
By default, the physics server will not step the simulation, unless you explicitly send a
step_simulation command.
This way you can maintain control determinism of the simulation
It is possible to run the simulation in real-time by letting the physics server
automatically step the simulation according to its real-time-clock (RTC) using the
set_real_time_simulation command. If you enable the real-time simulation,
you don’t need to call step_simulation.
Note that set_real_time_simulation has no effect in
Direct mode :
in Direct mode mode the physics
server and client happen in the same thread and you trigger every command.
In Gui mode and in Virtual Reality mode, and TCP/UDP mode,
the physics server runs in a separate thread from the client (RuBullet),
and set_real_time_simulation allows the physics server thread
to add additional calls to step_simulation.
§Arguments
enable_real_time_simulation- activates or deactivates real-time simulation
Sourcepub fn set_physics_engine_parameter(
&mut self,
update: &PhysicsEngineParametersUpdate,
) -> BulletResult<&mut Self>
pub fn set_physics_engine_parameter( &mut self, update: &PhysicsEngineParametersUpdate, ) -> BulletResult<&mut Self>
Apply a batch of physics engine parameters, mirroring PyBullet’s setPhysicsEngineParameter.
Sourcepub fn get_physics_engine_parameters(
&mut self,
) -> BulletResult<PhysicsEngineParameters>
pub fn get_physics_engine_parameters( &mut self, ) -> BulletResult<PhysicsEngineParameters>
Query the current physics simulation parameters from the server.
Sourcepub fn set_internal_sim_flags(&mut self, flags: i32) -> BulletResult<&mut Self>
pub fn set_internal_sim_flags(&mut self, flags: i32) -> BulletResult<&mut Self>
Set internal simulation flags (expert-level API).
Source§impl PhysicsClient
impl PhysicsClient
Sourcepub fn load_urdf(
&mut self,
file: impl AsRef<Path>,
options: Option<impl Into<UrdfOptions>>,
) -> BulletResult<i32>
pub fn load_urdf( &mut self, file: impl AsRef<Path>, options: Option<impl Into<UrdfOptions>>, ) -> BulletResult<i32>
Sends a command to the physics server to load a physics model from a Unified Robot Description Format (URDF) model.
§Arguments
file- a relative or absolute path to the URDF file on the file system of the physics serveroptions- use additional options likeglobal_scalinganduse_maximal_coordinatesfor loading the URDF-file. SeeUrdfOptions.
§Example
use rsbullet_core::*;
fn main() -> BulletResult<&mut Self> {
let mut physics_client = PhysicsClient::connect(Mode::Direct)?;
physics_client.set_additional_search_path(PhysicsClient::bullet_data_path())?;
let cube = physics_client.load_urdf("cube.urdf", None)?;
assert_eq!("baseLink", physics_client.get_body_info(cube)?.base_name);
for i in 0..10 {
let _cube = physics_client.load_urdf(
"cube.urdf",
None,
)?;
}
assert_eq!(11, physics_client.get_num_bodies());
Ok(())
}Sourcepub fn load_sdf(
&mut self,
file: impl AsRef<Path>,
options: impl Into<Option<SdfOptions>>,
) -> BulletResult<Vec<i32>>
pub fn load_sdf( &mut self, file: impl AsRef<Path>, options: impl Into<Option<SdfOptions>>, ) -> BulletResult<Vec<i32>>
Sends a command to the physics server to load a physics model from a Simulation Description Format (SDF) model.
§Arguments
file- a relative or absolute path to the SDF file on the file system of the physics server.options- use additional options likeglobal_scalinganduse_maximal_coordinatesfor loading the SDF-file. SeeSdfOptions.
§Return
Returns a list of unique body id’s
§Example
use rsbullet_core::*;
fn main() -> BulletResult<&mut Self> {
let mut physics_client = PhysicsClient::connect(Mode::Direct)?;
physics_client.set_additional_search_path(PhysicsClient::bullet_data_path())?;
let cubes = physics_client.load_sdf("two_cubes.sdf", None)?;
assert_eq!(3, cubes.len()); // 2 cubes + 1 plane
Ok(())
}Sourcepub fn load_mjcf(
&mut self,
file: impl AsRef<Path>,
options: impl Into<Option<MjcfOptions>>,
) -> BulletResult<Vec<i32>>
pub fn load_mjcf( &mut self, file: impl AsRef<Path>, options: impl Into<Option<MjcfOptions>>, ) -> BulletResult<Vec<i32>>
Sends a command to the physics server to load a physics model from
a MuJoCo model.
§Arguments
file- a relative or absolute path to theMuJoCofile on the file system of the physics server.flags- Flags for loading the model. Set to None if you do not whish to provide any.
§Return
Returns a list of unique body id’s
§Example
use rsbullet_core::*;
fn main() -> BulletResult<&mut Self> {
let mut physics_client = PhysicsClient::connect(Mode::Direct)?;
physics_client.set_additional_search_path(PhysicsClient::bullet_data_path())?;
let stadium = physics_client.load_mjcf("mjcf/hello_mjcf.xml", None)?;
assert_eq!(2, stadium.len()); // 1 cube + 1 plane
let plane = physics_client.load_mjcf("mjcf/ground_plane.xml", LoadModelFlags::URDF_ENABLE_CACHED_GRAPHICS_SHAPES)?;
assert_eq!(1, plane.len());
Ok(())
}Sourcepub fn load_bullet(&mut self, file: impl AsRef<Path>) -> BulletResult<Vec<i32>>
pub fn load_bullet(&mut self, file: impl AsRef<Path>) -> BulletResult<Vec<i32>>
Loads Bodies from a .bullet file. These can be created with save_bullet.
Returns a list of BodyId’s.
§Arguments
bullet_filename- location of the.bullet
§Example
let points = physics_client.load_bullet("spider.bullet")?;See also save_and_restore.rs example.
Sourcepub fn save_bullet(&mut self, file: impl AsRef<Path>) -> BulletResult<()>
pub fn save_bullet(&mut self, file: impl AsRef<Path>) -> BulletResult<()>
Saves all bodies and the current state into a .bullet file which can then be read by
load_bullet or restore_state_from_file.
See also save_and_restore.rs example.
pub fn save_world(&mut self, file: impl AsRef<Path>) -> BulletResult<()>
Sourcepub fn restore_state(
&mut self,
state_id: Option<i32>,
file: Option<impl AsRef<Path>>,
) -> BulletResult<()>
pub fn restore_state( &mut self, state_id: Option<i32>, file: Option<impl AsRef<Path>>, ) -> BulletResult<()>
restores a state from memory using a state id which was created with save_state.
See save_and_restore.rs example.
Sourcepub fn save_state(&mut self) -> BulletResult<i32>
pub fn save_state(&mut self) -> BulletResult<i32>
Saves the current state in memory and returns a StateId which can be used by restore_state
to restore this state. Use save_bullet if you want to save a state
to a file.
See save_and_restore.rs example.
Sourcepub fn remove_state(&mut self, state_id: i32) -> BulletResult<()>
pub fn remove_state(&mut self, state_id: i32) -> BulletResult<()>
Removes a state from memory.
pub fn set_default_search_path(&mut self) -> BulletResult<&mut Self>
pub fn set_additional_search_path( &mut self, path: impl AsRef<Path>, ) -> BulletResult<&mut Self>
pub fn bullet_data_path() -> PathBuf
Source§impl PhysicsClient
! =====================================================================================================================================
impl PhysicsClient
! =====================================================================================================================================
§Asset Creation & Mutation
| API | Status | Notes |
|---|---|---|
| createCollisionShape | Implemented | Supports primitive/mesh geometry |
| createCollisionShapeArray | Implemented | Compound shape builder |
| removeCollisionShape | Implemented | Clean-up helper |
| getMeshData | Pending | Mesh inspection |
| getTetraMeshData | Pending | Soft-body mesh |
| resetMeshData | Optional | Deformable specific |
| createVisualShape | Implemented | Visual geometry authoring |
| createVisualShapeArray | Implemented | Bulk visual authoring |
| createMultiBody | Implemented | Procedural multibody build |
| createConstraint | Implemented | Constraint authoring |
| changeConstraint | Implemented | Constraint mutation |
| removeConstraint | Implemented | Constraint teardown |
| enableJointForceTorqueSensor | Implemented | Sensor toggle |
| removeBody | Implemented | Body teardown |
| getNumConstraints | Implemented | Constraint enumeration |
| getConstraintInfo | Implemented | Constraint query |
| getConstraintState | Implemented | Constraint forces |
| getConstraintUniqueId | Implemented | Constraint enumeration |
| changeVisualShape | Implemented | Visual mutation |
| resetVisualShapeData | Pending | Legacy alias |
| loadTexture | Implemented | Visual assets |
| changeTexture | Implemented | Visual assets |
Sourcepub fn create_collision_shape(
&mut self,
geometry: &CollisionGeometry<'_>,
options: Option<impl Into<CollisionShapeOptions>>,
) -> BulletResult<i32>
pub fn create_collision_shape( &mut self, geometry: &CollisionGeometry<'_>, options: Option<impl Into<CollisionShapeOptions>>, ) -> BulletResult<i32>
You can create a collision shape in a similar way to creating a visual shape. If you have
both you can use them to create objects in RuBullet.
§Arguments
shape- A geometric body from which to create the shapeframe_offset- offset of the shape with respect to the link frame. Default is no offset.
§Return
Returns a unique CollisionId which can then be used to create a body.
§See also
pub fn create_collision_shape_array( &mut self, options: &[(CollisionGeometry<'_>, impl Clone + Into<CollisionShapeOptions>)], ) -> BulletResult<i32>
pub fn remove_collision_shape( &mut self, collision_shape_id: i32, ) -> BulletResult<()>
Sourcepub fn create_visual_shape(
&mut self,
geometry: &VisualGeometry<'_>,
options: Option<impl Into<VisualShapeOptions>>,
) -> BulletResult<i32>
pub fn create_visual_shape( &mut self, geometry: &VisualGeometry<'_>, options: Option<impl Into<VisualShapeOptions>>, ) -> BulletResult<i32>
You can create a visual shape in a similar way to creating a collision shape, with some
additional arguments to control the visual appearance, such as diffuse and specular color.
When you use the GeometricVisualShape::MeshFile
type, you can point to a Wavefront OBJ file, and the
visual shape will parse some parameters from the material file (.mtl) and load a texture.
Note that large textures (above 1024x1024 pixels)
can slow down the loading and run-time performance.
§Arguments
shape- A geometric body from which to create the shapeoptions- additional options to specify, like colors. SeeVisualShapeOptionsfor details.
§Return
Returns a unique VisualId which can then be used to create a body.
§See also
pub fn create_visual_shape_array( &mut self, options: &[(VisualGeometry<'_>, Option<VisualShapeOptions>)], ) -> BulletResult<i32>
pub fn change_visual_shape( &mut self, body_unique_id: i32, link_index: i32, options: &ChangeVisualShapeOptions, ) -> BulletResult<&mut Self>
pub fn create_multi_body( &mut self, options: &MultiBodyCreateOptions<'_>, ) -> BulletResult<i32>
pub fn create_constraint( &mut self, options: &ConstraintCreateOptions, ) -> BulletResult<i32>
pub fn change_constraint( &mut self, constraint_id: i32, update: &ConstraintUpdate, ) -> BulletResult<&mut Self>
pub fn remove_constraint(&mut self, constraint_id: i32) -> BulletResult<()>
pub fn enable_joint_force_torque_sensor( &mut self, body_unique_id: i32, joint_index: i32, enable: bool, ) -> BulletResult<()>
pub fn remove_body(&mut self, body_unique_id: i32) -> BulletResult<()>
pub fn get_num_constraints(&self) -> i32
pub fn get_constraint_info( &self, constraint_id: i32, ) -> BulletResult<ConstraintInfo>
pub fn get_constraint_state( &mut self, constraint_id: i32, ) -> BulletResult<ConstraintState>
pub fn get_constraint_unique_id(&self, index: i32) -> Option<i32>
pub fn load_texture(&mut self, filename: &str) -> BulletResult<i32>
pub fn change_texture( &mut self, texture_id: i32, data: &TextureData<'_>, ) -> BulletResult<()>
Source§impl PhysicsClient
! =====================================================================================================================================
impl PhysicsClient
! =====================================================================================================================================
§Bodies, Joints & Base State
| API | Status | Notes |
|---|---|---|
| getNumBodies | Implemented | Enumeration helper |
| getBodyUniqueId | Implemented | Enumeration helper |
| getBodyInfo | Implemented | Names cached |
| computeDofCount | Implemented | Useful with dynamics |
| syncBodyInfo | Implemented | Multi-client support |
| syncUserData | Implemented | Multi-client support |
| addUserData | Implemented | User data authoring |
| getUserData | Implemented | User data query |
| removeUserData | Implemented | User data cleanup |
| getUserDataId | Implemented | User data query |
| getNumUserData | Implemented | User data query |
| getUserDataInfo | Implemented | User data query |
| getBasePositionAndOrientation | Implemented | Uses actual state request |
| getAABB | Implemented | Contact bounds |
| resetBasePositionAndOrientation | Implemented | World authoring priority |
| unsupportedChangeScaling | Optional | Rudimentary scaling |
| getBaseVelocity | Implemented | Uses actual state request |
| resetBaseVelocity | Implemented | Dynamics priority |
| getNumJoints | Implemented | Joint enumeration |
| getJointInfo | Implemented | Joint metadata |
| getJointState | Implemented | Single joint sensor |
| getJointStates | Implemented | Batch sensor support |
| getJointStateMultiDof | Implemented | Multi-DoF sensor |
| getJointStatesMultiDof | Implemented | Multi-DoF batch |
| getLinkState | Implemented | Forward kinematics |
| getLinkStates | Implemented | Batch link state |
| resetJointState | Implemented | World authoring priority |
| resetJointStateMultiDof | Implemented | Multi-DoF reset |
| resetJointStatesMultiDof | Implemented | Multi-DoF batch reset |
pub fn compute_dof_count(&self, body_unique_id: i32) -> i32
pub fn sync_body_info(&mut self) -> BulletResult<()>
pub fn sync_user_data( &mut self, body_unique_ids: Option<&[i32]>, ) -> BulletResult<()>
pub fn add_user_data( &mut self, body_unique_id: i32, key: &str, value: &str, link_index: Option<i32>, visual_shape_index: Option<i32>, ) -> BulletResult<i32>
pub fn remove_user_data(&mut self, user_data_id: i32) -> BulletResult<()>
pub fn get_user_data_id( &self, body_unique_id: i32, key: &str, link_index: Option<i32>, visual_shape_index: Option<i32>, ) -> BulletResult<Option<i32>>
pub fn get_user_data(&self, user_data_id: i32) -> BulletResult<Option<String>>
pub fn get_num_user_data(&self, body_unique_id: i32) -> BulletResult<i32>
pub fn get_user_data_info( &self, body_unique_id: i32, user_data_index: i32, ) -> BulletResult<UserDataInfo>
pub fn get_aabb( &mut self, body_unique_id: i32, link_index: i32, ) -> BulletResult<Aabb>
pub fn reset_base_position_and_orientation( &mut self, body_unique_id: i32, position: [f64; 3], orientation: [f64; 4], ) -> BulletResult<()>
pub fn reset_base_velocity( &mut self, body_unique_id: i32, linear_velocity: Option<[f64; 3]>, angular_velocity: Option<[f64; 3]>, ) -> BulletResult<()>
pub fn get_num_bodies(&self) -> i32
pub fn get_body_unique_id(&self, serial_index: i32) -> i32
pub fn get_body_info(&self, body_unique_id: i32) -> BulletResult<BodyInfo>
pub fn get_num_joints(&self, body_unique_id: i32) -> i32
pub fn get_joint_info( &self, body_unique_id: i32, joint_index: i32, ) -> BulletResult<JointInfo>
pub fn get_joint_state( &mut self, body_unique_id: i32, joint_index: i32, ) -> BulletResult<JointState>
pub fn get_joint_states( &mut self, body_unique_id: i32, joint_indices: &[i32], ) -> BulletResult<Vec<JointState>>
pub fn get_joint_state_multi_dof( &mut self, body_unique_id: i32, joint_index: i32, ) -> BulletResult<JointStateMultiDof>
pub fn get_joint_states_multi_dof( &mut self, body_unique_id: i32, joint_indices: &[i32], ) -> BulletResult<Vec<JointStateMultiDof>>
pub fn get_base_position_and_orientation( &mut self, body_unique_id: i32, ) -> BulletResult<Isometry3<f64>>
pub fn get_base_velocity( &mut self, body_unique_id: i32, ) -> BulletResult<[f64; 6]>
pub fn get_link_state( &mut self, body_unique_id: i32, link_index: i32, compute_forward_kinematics: bool, compute_link_velocity: bool, ) -> BulletResult<LinkState>
pub fn get_link_states( &mut self, body_unique_id: i32, link_indices: &[i32], compute_forward_kinematics: bool, compute_link_velocity: bool, ) -> BulletResult<Vec<LinkState>>
pub fn reset_joint_state( &mut self, body_unique_id: i32, joint_index: i32, target_position: f64, target_velocity: Option<f64>, ) -> BulletResult<()>
pub fn reset_joint_state_multi_dof( &mut self, body_unique_id: i32, joint_index: i32, positions: Option<&[f64]>, velocities: Option<&[f64]>, ) -> BulletResult<()>
pub fn reset_joint_states_multi_dof( &mut self, body_unique_id: i32, targets: &[MultiDofTarget<'_>], ) -> BulletResult<()>
Source§impl PhysicsClient
! =====================================================================================================================================
impl PhysicsClient
! =====================================================================================================================================
§Dynamics & Control
| API | Status | Notes |
|---|---|---|
| changeDynamics | Implemented | Mutation wrapper |
| getDynamicsInfo | Implemented | Mirrors Bullet query |
| setJointMotorControl | Optional | Legacy single-call (deprecated) |
| setJointMotorControl2 | Implemented | Primary motor control path |
| setJointMotorControlMultiDof | Implemented | Multi-DoF control |
| setJointMotorControlMultiDofArray | Implemented | Multi-DoF batch control |
| setJointMotorControlArray | Implemented | Batch joint control |
| applyExternalForce | Implemented | Core dynamics action |
| applyExternalTorque | Implemented | Core dynamics action |
| calculateInverseDynamics | Implemented | Advanced dynamics |
| calculateJacobian | Implemented | Advanced dynamics |
| calculateMassMatrix | Implemented | Advanced dynamics |
| calculateInverseKinematics | Implemented | Depends on jacobians |
| calculateInverseKinematics2 | Implemented | Multi-end-effector variant |
pub fn change_dynamics( &mut self, body_unique_id: i32, link_index: i32, update: &DynamicsUpdate, ) -> BulletResult<()>
pub fn get_dynamics_info( &mut self, body_unique_id: i32, link_index: i32, ) -> BulletResult<DynamicsInfo>
pub fn set_joint_motor_control( &mut self, body_unique_id: i32, joint_index: i32, control_mode: ControlMode, maximum_force: Option<f64>, ) -> BulletResult<()>
pub fn set_joint_motor_control_array( &mut self, body_unique_id: i32, joint_index: &[i32], control_mode: ControlModeArray<'_>, maximum_force: Option<&[f64]>, ) -> BulletResult<()>
pub fn set_joint_motor_control_multi_dof( &mut self, body_unique_id: i32, joint_index: i32, control: &MultiDofControl<'_>, ) -> BulletResult<()>
pub fn set_joint_motor_control_multi_dof_array( &mut self, body_unique_id: i32, entries: &[MultiDofControlEntry<'_>], ) -> BulletResult<()>
pub fn apply_external_force( &mut self, body_unique_id: i32, link_index: i32, force: impl Into<[f64; 3]>, position: impl Into<[f64; 3]>, frame: ForceFrame, ) -> BulletResult<()>
pub fn apply_external_torque( &mut self, body_unique_id: i32, link_index: i32, torque: impl Into<[f64; 3]>, frame: ForceFrame, ) -> BulletResult<()>
pub fn calculate_inverse_dynamics( &mut self, body_unique_id: i32, joint_positions: &[f64], joint_velocities: &[f64], joint_accelerations: &[f64], ) -> BulletResult<Vec<f64>>
pub fn calculate_jacobian( &mut self, body_unique_id: i32, link_index: i32, local_position: [f64; 3], joint_positions: &[f64], joint_velocities: &[f64], joint_accelerations: &[f64], ) -> BulletResult<Jacobian>
pub fn calculate_mass_matrix( &mut self, body_unique_id: i32, joint_positions: &[f64], ) -> BulletResult<MassMatrix>
pub fn calculate_inverse_kinematics( &mut self, body_unique_id: i32, end_effector_link_index: i32, target_position: impl Into<Isometry3<f64>>, options: &InverseKinematicsOptions<'_>, ) -> BulletResult<Vec<f64>>
pub fn calculate_inverse_kinematics2( &mut self, body_unique_id: i32, options: &InverseKinematicsMultiTargetOptions<'_>, ) -> BulletResult<Vec<f64>>
Source§impl PhysicsClient
! =====================================================================================================================================
impl PhysicsClient
! =====================================================================================================================================
§Collision Queries & Contact Data
| API | Status | Notes |
|---|---|---|
| getContactPoints | Implemented | Returns per-contact data |
| getClosestPoints | Implemented | Distance queries |
| getOverlappingObjects | Implemented | AABB queries |
| setCollisionFilterPair | Implemented | Collision filtering |
| setCollisionFilterGroupMask | Implemented | Collision filtering |
| rayTest | Implemented | Single raycast |
| rayTestBatch | Implemented | Batch raycasts |
pub fn get_contact_points( &mut self, body_a: Option<i32>, body_b: Option<i32>, link_a: Option<i32>, link_b: Option<i32>, ) -> BulletResult<Vec<ContactPoint>>
pub fn get_closest_points( &mut self, body_a: i32, body_b: i32, distance: f64, options: &ClosestPointsOptions, ) -> BulletResult<Vec<ClosestPoint>>
pub fn get_overlapping_objects( &mut self, aabb_min: [f64; 3], aabb_max: [f64; 3], ) -> BulletResult<Vec<OverlappingObject>>
pub fn set_collision_filter_pair( &mut self, body_a: i32, body_b: i32, link_a: i32, link_b: i32, enable_collision: bool, ) -> BulletResult<&mut Self>
pub fn set_collision_filter_group_mask( &mut self, body_unique_id: i32, link_index: i32, collision_filter_group: i32, collision_filter_mask: i32, ) -> BulletResult<&mut Self>
pub fn ray_test( &mut self, ray_from: [f64; 3], ray_to: [f64; 3], collision_filter_mask: Option<i32>, report_hit_number: Option<i32>, ) -> BulletResult<Vec<RayHit>>
pub fn ray_test_batch( &mut self, options: &RayTestBatchOptions<'_>, ) -> BulletResult<Vec<RayHit>>
Source§impl PhysicsClient
! =====================================================================================================================================
impl PhysicsClient
! =====================================================================================================================================
§Rendering, Debug & Visualization
| API | Status | Notes |
|---|---|---|
| renderImage | Pending | Obsolete; low priority |
| getCameraImage | Implemented | High effort (buffers) |
| isNumpyEnabled | Pending | Simple flag query |
| computeViewMatrix | Implemented | Math helper |
| computeViewMatrixFromYawPitchRoll | Implemented | Math helper |
| computeProjectionMatrix | Implemented | Math helper |
| computeProjectionMatrixFOV | Implemented | Math helper |
| addUserDebugLine | Implemented | Debug draw |
| addUserDebugPoints | Implemented | Debug draw |
| addUserDebugText | Implemented | Debug draw |
| addUserDebugParameter | Implemented | GUI slider/button |
| readUserDebugParameter | Implemented | GUI feedback |
| removeUserDebugItem | Implemented | Debug cleanup |
| removeAllUserDebugItems | Implemented | Debug cleanup |
| removeAllUserParameters | Implemented | Debug cleanup |
| setDebugObjectColor | Implemented | Debug override |
| getDebugVisualizerCamera | Implemented | Visualizer query |
| configureDebugVisualizer | Implemented | Visualizer toggle |
| resetDebugVisualizerCamera | Implemented | Visualizer camera |
| getVisualShapeData | Implemented | Visual query |
| getCollisionShapeData | Implemented | Collision query |
pub fn get_camera_image( &mut self, request: &CameraImageOptions, ) -> BulletResult<CameraImage>
pub fn compute_view_matrix( camera_eye_position: [f32; 3], camera_target_position: [f32; 3], camera_up_vector: [f32; 3], ) -> [f32; 16]
pub fn compute_view_matrix_from_yaw_pitch_roll( camera_target_position: [f32; 3], distance: f32, yaw: f32, pitch: f32, roll: f32, up_axis: i32, ) -> [f32; 16]
pub fn compute_projection_matrix( left: f32, right: f32, bottom: f32, top: f32, near_val: f32, far_val: f32, ) -> [f32; 16]
pub fn compute_projection_matrix_fov( fov: f32, aspect: f32, near_val: f32, far_val: f32, ) -> [f32; 16]
pub fn add_user_debug_line( &mut self, options: &DebugLineOptions, ) -> BulletResult<i32>
pub fn add_user_debug_points( &mut self, options: &DebugPointsOptions<'_>, ) -> BulletResult<i32>
pub fn add_user_debug_text( &mut self, options: &DebugTextOptions<'_>, ) -> BulletResult<i32>
pub fn add_user_debug_parameter( &mut self, options: &DebugParameterOptions<'_>, ) -> BulletResult<i32>
pub fn read_user_debug_parameter( &mut self, parameter_id: i32, ) -> BulletResult<f64>
pub fn remove_user_debug_item( &mut self, item_unique_id: i32, ) -> BulletResult<()>
pub fn remove_all_user_debug_items(&mut self) -> BulletResult<()>
pub fn remove_all_user_parameters(&mut self) -> BulletResult<()>
pub fn set_debug_object_color( &mut self, object_unique_id: i32, link_index: i32, color: Option<[f64; 3]>, ) -> BulletResult<&mut Self>
pub fn get_debug_visualizer_camera( &mut self, ) -> BulletResult<DebugVisualizerCamera>
pub fn configure_debug_visualizer( &mut self, options: &DebugVisualizerOptions, ) -> BulletResult<&mut Self>
pub fn reset_debug_visualizer_camera( &mut self, options: &ResetDebugVisualizerCameraOptions, ) -> BulletResult<&mut Self>
pub fn get_visual_shape_data( &mut self, object_unique_id: i32, ) -> BulletResult<Vec<VisualShapeData>>
pub fn get_collision_shape_data( &mut self, object_unique_id: i32, link_index: Option<i32>, ) -> BulletResult<Vec<CollisionShapeData>>
Source§impl PhysicsClient
! =====================================================================================================================================
impl PhysicsClient
! =====================================================================================================================================
§VR, Input, Logging, Plugins & Misc
| API | Status | Notes |
|---|---|---|
| getVREvents | Implemented | VR input |
| setVRCameraState | Implemented | VR camera |
| getKeyboardEvents | Implemented | Input polling |
| getMouseEvents | Implemented | Input polling |
| startStateLogging | Implemented | Logging |
| stopStateLogging | Implemented | Logging |
| loadPlugin | Implemented | Plugin system |
| unloadPlugin | Implemented | Plugin system |
| executePluginCommand | Implemented | Plugin system |
| submitProfileTiming | Implemented | Profiling |
| setTimeOut | Implemented | Client timeout |
| getAPIVersion | Implemented | Static constant |
pub fn get_vr_events( &mut self, options: &VrEventsOptions, ) -> BulletResult<Vec<VrControllerEvent>>
pub fn set_vr_camera_state( &mut self, options: &VrCameraStateOptions, ) -> BulletResult<&mut Self>
pub fn get_keyboard_events(&mut self) -> BulletResult<Vec<KeyboardEvent>>
pub fn get_mouse_events(&mut self) -> BulletResult<Vec<MouseEvent>>
pub fn start_state_logging( &mut self, logging_type: LoggingType, file_name: impl AsRef<Path>, options: Option<impl Into<StateLoggingOptions>>, ) -> BulletResult<i32>
pub fn stop_state_logging(&mut self, logging_id: i32) -> BulletResult<&mut Self>
pub fn load_plugin( &mut self, plugin_path: &str, postfix: Option<&str>, ) -> BulletResult<i32>
pub fn unload_plugin(&mut self, plugin_unique_id: i32) -> BulletResult<()>
pub fn execute_plugin_command( &mut self, options: &PluginCommandOptions<'_>, ) -> BulletResult<PluginCommandResult>
pub fn submit_profile_timing( &mut self, event_name: Option<&str>, ) -> BulletResult<()>
pub fn set_time_out(&mut self, time_out_seconds: f64) -> BulletResult<&mut Self>
pub fn get_api_version(&self) -> i32
Trait Implementations§
Auto Trait Implementations§
impl Freeze for PhysicsClient
impl RefUnwindSafe for PhysicsClient
impl !Send for PhysicsClient
impl !Sync for PhysicsClient
impl Unpin for PhysicsClient
impl UnwindSafe for PhysicsClient
Blanket Implementations§
Source§impl<T> BorrowMut<T> for Twhere
T: ?Sized,
impl<T> BorrowMut<T> for Twhere
T: ?Sized,
Source§fn borrow_mut(&mut self) -> &mut T
fn borrow_mut(&mut self) -> &mut T
Source§impl<X> Pipe for X
impl<X> Pipe for X
Source§fn pipe_ref<'a, Return, Function>(&'a self, f: Function) -> Returnwhere
Function: FnOnce(&'a Self) -> Return,
fn pipe_ref<'a, Return, Function>(&'a self, f: Function) -> Returnwhere
Function: FnOnce(&'a Self) -> Return,
Source§fn pipe_mut<'a, Return, Function>(&'a mut self, f: Function) -> Returnwhere
Function: FnOnce(&'a mut Self) -> Return,
fn pipe_mut<'a, Return, Function>(&'a mut self, f: Function) -> Returnwhere
Function: FnOnce(&'a mut Self) -> Return,
Source§fn pipe_as_ref<'a, Param, Return, Function>(&'a self, f: Function) -> Return
fn pipe_as_ref<'a, Param, Return, Function>(&'a self, f: Function) -> Return
f to &self where f takes a single parameter of type Param
and Self implements trait AsRef<Param>. Read moreSource§fn pipe_as_mut<'a, Param, Return, Function>(&'a mut self, f: Function) -> Return
fn pipe_as_mut<'a, Param, Return, Function>(&'a mut self, f: Function) -> Return
f to &mut self where f takes a single parameter of type Param
and Self implements trait AsMut<Param>. Read moreSource§fn pipe_deref<'a, Param, Return, Function>(&'a self, f: Function) -> Return
fn pipe_deref<'a, Param, Return, Function>(&'a self, f: Function) -> Return
f to &self where f takes a single parameter of type Param
and Self implements trait Deref<Target = Param>. Read moreSource§fn pipe_deref_mut<'a, Param, Return, Function>(
&'a mut self,
f: Function,
) -> Returnwhere
Self: DerefMut<Target = Param>,
Param: 'a + ?Sized,
Function: FnOnce(&'a mut Param) -> Return,
fn pipe_deref_mut<'a, Param, Return, Function>(
&'a mut self,
f: Function,
) -> Returnwhere
Self: DerefMut<Target = Param>,
Param: 'a + ?Sized,
Function: FnOnce(&'a mut Param) -> Return,
f to &mut self where f takes a single parameter of type Param
and Self implements trait DerefMut<Target = Param>. Read moreSource§fn pipe_borrow<'a, Param, Return, Function>(&'a self, f: Function) -> Return
fn pipe_borrow<'a, Param, Return, Function>(&'a self, f: Function) -> Return
f to &self where f takes a single parameter of type Param
and Self implements trait Borrow<Param>. Read moreSource§fn pipe_borrow_mut<'a, Param, Return, Function>(
&'a mut self,
f: Function,
) -> Return
fn pipe_borrow_mut<'a, Param, Return, Function>( &'a mut self, f: Function, ) -> Return
f to &mut self where f takes a single parameter of type Param
and Self implements trait BorrowMut<Param>. Read moreSource§impl<SS, SP> SupersetOf<SS> for SPwhere
SS: SubsetOf<SP>,
impl<SS, SP> SupersetOf<SS> for SPwhere
SS: SubsetOf<SP>,
Source§fn to_subset(&self) -> Option<SS>
fn to_subset(&self) -> Option<SS>
self from the equivalent element of its
superset. Read moreSource§fn is_in_subset(&self) -> bool
fn is_in_subset(&self) -> bool
self is actually part of its subset T (and can be converted to it).Source§fn to_subset_unchecked(&self) -> SS
fn to_subset_unchecked(&self) -> SS
self.to_subset but without any property checks. Always succeeds.Source§fn from_subset(element: &SS) -> SP
fn from_subset(element: &SS) -> SP
self to the equivalent element of its superset.