PhysicsClient

Struct PhysicsClient 

Source
pub struct PhysicsClient { /* private fields */ }

Implementations§

Source§

impl PhysicsClient

! =====================================================================================================================================

§Connection & Session
APIStatusNotes
connectImplementedPhysicsClient::connect covers all modes in scope
disconnectImplementedPhysicsClient::disconnectPhysicsServer + Drop
getConnectionInfoImplementedRequires client/server introspection
isConnectedImplementedUses b3CanSubmitCommand
Source

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=‘’)
Source

pub fn get_connection_info(&mut self) -> BulletResult<String>

Source

pub fn disconnect(self)

“Disconnect from the physics server.”

Source

pub fn is_connected(&mut self) -> bool

Source§

impl PhysicsClient

! =====================================================================================================================================

§Simulation Parameters
APIStatusNotes
resetSimulationImplementedCore reset command
stepSimulationImplementedCore stepping command
performCollisionDetectionImplementedExtra collision command
setGravityImplementedPhysics param command
setTimeStepImplementedPhysics param command
setDefaultContactERPImplementedPhysics param command
setRealTimeSimulationImplementedPhysics param command
setPhysicsEngineParameterImplementedBulk physics-param configuration
getPhysicsEngineParametersImplementedQuery mirror of above
setInternalSimFlagsImplementedExpert-only flagging
Source

pub fn reset_simulation(&mut self) -> BulletResult<()>

reset_simulation will remove all objects from the world and reset the world to initial conditions.

Source

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?

Source

pub fn perform_collision_detection(&mut self) -> BulletResult<()>

Source

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].
Source

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.

Source

pub fn set_default_contact_erp( &mut self, default_contact_erp: f64, ) -> BulletResult<&mut Self>

Update the global default contact ERP (error reduction parameter).

Source

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
Source

pub fn set_physics_engine_parameter( &mut self, update: &PhysicsEngineParametersUpdate, ) -> BulletResult<&mut Self>

Apply a batch of physics engine parameters, mirroring PyBullet’s setPhysicsEngineParameter.

Source

pub fn get_physics_engine_parameters( &mut self, ) -> BulletResult<PhysicsEngineParameters>

Query the current physics simulation parameters from the server.

Source

pub fn set_internal_sim_flags(&mut self, flags: i32) -> BulletResult<&mut Self>

Set internal simulation flags (expert-level API).

Source§

impl PhysicsClient

Source

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 server
  • options - use additional options like global_scaling and use_maximal_coordinates for loading the URDF-file. See UrdfOptions.
§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(())
}
Source

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 like global_scaling and use_maximal_coordinates for loading the SDF-file. See SdfOptions.
§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(())
}
Source

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 the MuJoCo file 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(())
}
Source

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.

Source

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.

Source

pub fn save_world(&mut self, file: impl AsRef<Path>) -> BulletResult<()>

Source

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.

Source

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.

Source

pub fn remove_state(&mut self, state_id: i32) -> BulletResult<()>

Removes a state from memory.

Source

pub fn set_default_search_path(&mut self) -> BulletResult<&mut Self>

Source

pub fn set_additional_search_path( &mut self, path: impl AsRef<Path>, ) -> BulletResult<&mut Self>

Source

pub fn bullet_data_path() -> PathBuf

Source§

impl PhysicsClient

! =====================================================================================================================================

§Asset Creation & Mutation
APIStatusNotes
createCollisionShapeImplementedSupports primitive/mesh geometry
createCollisionShapeArrayImplementedCompound shape builder
removeCollisionShapeImplementedClean-up helper
getMeshDataPendingMesh inspection
getTetraMeshDataPendingSoft-body mesh
resetMeshDataOptionalDeformable specific
createVisualShapeImplementedVisual geometry authoring
createVisualShapeArrayImplementedBulk visual authoring
createMultiBodyImplementedProcedural multibody build
createConstraintImplementedConstraint authoring
changeConstraintImplementedConstraint mutation
removeConstraintImplementedConstraint teardown
enableJointForceTorqueSensorImplementedSensor toggle
removeBodyImplementedBody teardown
getNumConstraintsImplementedConstraint enumeration
getConstraintInfoImplementedConstraint query
getConstraintStateImplementedConstraint forces
getConstraintUniqueIdImplementedConstraint enumeration
changeVisualShapeImplementedVisual mutation
resetVisualShapeDataPendingLegacy alias
loadTextureImplementedVisual assets
changeTextureImplementedVisual assets
Source

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 shape
  • frame_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
Source

pub fn create_collision_shape_array( &mut self, options: &[(CollisionGeometry<'_>, impl Clone + Into<CollisionShapeOptions>)], ) -> BulletResult<i32>

Source

pub fn remove_collision_shape( &mut self, collision_shape_id: i32, ) -> BulletResult<()>

Source

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 shape
  • options - additional options to specify, like colors. See VisualShapeOptions for details.
§Return

Returns a unique VisualId which can then be used to create a body.

§See also
Source

pub fn create_visual_shape_array( &mut self, options: &[(VisualGeometry<'_>, Option<VisualShapeOptions>)], ) -> BulletResult<i32>

Source

pub fn change_visual_shape( &mut self, body_unique_id: i32, link_index: i32, options: &ChangeVisualShapeOptions, ) -> BulletResult<&mut Self>

Source

pub fn create_multi_body( &mut self, options: &MultiBodyCreateOptions<'_>, ) -> BulletResult<i32>

Source

pub fn create_constraint( &mut self, options: &ConstraintCreateOptions, ) -> BulletResult<i32>

Source

pub fn change_constraint( &mut self, constraint_id: i32, update: &ConstraintUpdate, ) -> BulletResult<&mut Self>

Source

pub fn remove_constraint(&mut self, constraint_id: i32) -> BulletResult<()>

Source

pub fn enable_joint_force_torque_sensor( &mut self, body_unique_id: i32, joint_index: i32, enable: bool, ) -> BulletResult<()>

Source

pub fn remove_body(&mut self, body_unique_id: i32) -> BulletResult<()>

Source

pub fn get_num_constraints(&self) -> i32

Source

pub fn get_constraint_info( &self, constraint_id: i32, ) -> BulletResult<ConstraintInfo>

Source

pub fn get_constraint_state( &mut self, constraint_id: i32, ) -> BulletResult<ConstraintState>

Source

pub fn get_constraint_unique_id(&self, index: i32) -> Option<i32>

Source

pub fn load_texture(&mut self, filename: &str) -> BulletResult<i32>

Source

pub fn change_texture( &mut self, texture_id: i32, data: &TextureData<'_>, ) -> BulletResult<()>

Source§

impl PhysicsClient

! =====================================================================================================================================

§Bodies, Joints & Base State
APIStatusNotes
getNumBodiesImplementedEnumeration helper
getBodyUniqueIdImplementedEnumeration helper
getBodyInfoImplementedNames cached
computeDofCountImplementedUseful with dynamics
syncBodyInfoImplementedMulti-client support
syncUserDataImplementedMulti-client support
addUserDataImplementedUser data authoring
getUserDataImplementedUser data query
removeUserDataImplementedUser data cleanup
getUserDataIdImplementedUser data query
getNumUserDataImplementedUser data query
getUserDataInfoImplementedUser data query
getBasePositionAndOrientationImplementedUses actual state request
getAABBImplementedContact bounds
resetBasePositionAndOrientationImplementedWorld authoring priority
unsupportedChangeScalingOptionalRudimentary scaling
getBaseVelocityImplementedUses actual state request
resetBaseVelocityImplementedDynamics priority
getNumJointsImplementedJoint enumeration
getJointInfoImplementedJoint metadata
getJointStateImplementedSingle joint sensor
getJointStatesImplementedBatch sensor support
getJointStateMultiDofImplementedMulti-DoF sensor
getJointStatesMultiDofImplementedMulti-DoF batch
getLinkStateImplementedForward kinematics
getLinkStatesImplementedBatch link state
resetJointStateImplementedWorld authoring priority
resetJointStateMultiDofImplementedMulti-DoF reset
resetJointStatesMultiDofImplementedMulti-DoF batch reset
Source

pub fn compute_dof_count(&self, body_unique_id: i32) -> i32

Source

pub fn sync_body_info(&mut self) -> BulletResult<()>

Source

pub fn sync_user_data( &mut self, body_unique_ids: Option<&[i32]>, ) -> BulletResult<()>

Source

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>

Source

pub fn remove_user_data(&mut self, user_data_id: i32) -> BulletResult<()>

Source

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>>

Source

pub fn get_user_data(&self, user_data_id: i32) -> BulletResult<Option<String>>

Source

pub fn get_num_user_data(&self, body_unique_id: i32) -> BulletResult<i32>

Source

pub fn get_user_data_info( &self, body_unique_id: i32, user_data_index: i32, ) -> BulletResult<UserDataInfo>

Source

pub fn get_aabb( &mut self, body_unique_id: i32, link_index: i32, ) -> BulletResult<Aabb>

Source

pub fn reset_base_position_and_orientation( &mut self, body_unique_id: i32, position: [f64; 3], orientation: [f64; 4], ) -> BulletResult<()>

Source

pub fn reset_base_velocity( &mut self, body_unique_id: i32, linear_velocity: Option<[f64; 3]>, angular_velocity: Option<[f64; 3]>, ) -> BulletResult<()>

Source

pub fn get_num_bodies(&self) -> i32

Source

pub fn get_body_unique_id(&self, serial_index: i32) -> i32

Source

pub fn get_body_info(&self, body_unique_id: i32) -> BulletResult<BodyInfo>

Source

pub fn get_num_joints(&self, body_unique_id: i32) -> i32

Source

pub fn get_joint_info( &self, body_unique_id: i32, joint_index: i32, ) -> BulletResult<JointInfo>

Source

pub fn get_joint_state( &mut self, body_unique_id: i32, joint_index: i32, ) -> BulletResult<JointState>

Source

pub fn get_joint_states( &mut self, body_unique_id: i32, joint_indices: &[i32], ) -> BulletResult<Vec<JointState>>

Source

pub fn get_joint_state_multi_dof( &mut self, body_unique_id: i32, joint_index: i32, ) -> BulletResult<JointStateMultiDof>

Source

pub fn get_joint_states_multi_dof( &mut self, body_unique_id: i32, joint_indices: &[i32], ) -> BulletResult<Vec<JointStateMultiDof>>

Source

pub fn get_base_position_and_orientation( &mut self, body_unique_id: i32, ) -> BulletResult<Isometry3<f64>>

Source

pub fn get_base_velocity( &mut self, body_unique_id: i32, ) -> BulletResult<[f64; 6]>

Source

pub fn reset_joint_state( &mut self, body_unique_id: i32, joint_index: i32, target_position: f64, target_velocity: Option<f64>, ) -> BulletResult<()>

Source

pub fn reset_joint_state_multi_dof( &mut self, body_unique_id: i32, joint_index: i32, positions: Option<&[f64]>, velocities: Option<&[f64]>, ) -> BulletResult<()>

Source

pub fn reset_joint_states_multi_dof( &mut self, body_unique_id: i32, targets: &[MultiDofTarget<'_>], ) -> BulletResult<()>

Source§

impl PhysicsClient

! =====================================================================================================================================

§Dynamics & Control
APIStatusNotes
changeDynamicsImplementedMutation wrapper
getDynamicsInfoImplementedMirrors Bullet query
setJointMotorControlOptionalLegacy single-call (deprecated)
setJointMotorControl2ImplementedPrimary motor control path
setJointMotorControlMultiDofImplementedMulti-DoF control
setJointMotorControlMultiDofArrayImplementedMulti-DoF batch control
setJointMotorControlArrayImplementedBatch joint control
applyExternalForceImplementedCore dynamics action
applyExternalTorqueImplementedCore dynamics action
calculateInverseDynamicsImplementedAdvanced dynamics
calculateJacobianImplementedAdvanced dynamics
calculateMassMatrixImplementedAdvanced dynamics
calculateInverseKinematicsImplementedDepends on jacobians
calculateInverseKinematics2ImplementedMulti-end-effector variant
Source

pub fn change_dynamics( &mut self, body_unique_id: i32, link_index: i32, update: &DynamicsUpdate, ) -> BulletResult<()>

Source

pub fn get_dynamics_info( &mut self, body_unique_id: i32, link_index: i32, ) -> BulletResult<DynamicsInfo>

Source

pub fn set_joint_motor_control( &mut self, body_unique_id: i32, joint_index: i32, control_mode: ControlMode, maximum_force: Option<f64>, ) -> BulletResult<()>

Source

pub fn set_joint_motor_control_array( &mut self, body_unique_id: i32, joint_index: &[i32], control_mode: ControlModeArray<'_>, maximum_force: Option<&[f64]>, ) -> BulletResult<()>

Source

pub fn set_joint_motor_control_multi_dof( &mut self, body_unique_id: i32, joint_index: i32, control: &MultiDofControl<'_>, ) -> BulletResult<()>

Source

pub fn set_joint_motor_control_multi_dof_array( &mut self, body_unique_id: i32, entries: &[MultiDofControlEntry<'_>], ) -> BulletResult<()>

Source

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<()>

Source

pub fn apply_external_torque( &mut self, body_unique_id: i32, link_index: i32, torque: impl Into<[f64; 3]>, frame: ForceFrame, ) -> BulletResult<()>

Source

pub fn calculate_inverse_dynamics( &mut self, body_unique_id: i32, joint_positions: &[f64], joint_velocities: &[f64], joint_accelerations: &[f64], ) -> BulletResult<Vec<f64>>

Source

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>

Source

pub fn calculate_mass_matrix( &mut self, body_unique_id: i32, joint_positions: &[f64], ) -> BulletResult<MassMatrix>

Source

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>>

Source

pub fn calculate_inverse_kinematics2( &mut self, body_unique_id: i32, options: &InverseKinematicsMultiTargetOptions<'_>, ) -> BulletResult<Vec<f64>>

Source§

impl PhysicsClient

! =====================================================================================================================================

§Collision Queries & Contact Data
APIStatusNotes
getContactPointsImplementedReturns per-contact data
getClosestPointsImplementedDistance queries
getOverlappingObjectsImplementedAABB queries
setCollisionFilterPairImplementedCollision filtering
setCollisionFilterGroupMaskImplementedCollision filtering
rayTestImplementedSingle raycast
rayTestBatchImplementedBatch raycasts
Source

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>>

Source

pub fn get_closest_points( &mut self, body_a: i32, body_b: i32, distance: f64, options: &ClosestPointsOptions, ) -> BulletResult<Vec<ClosestPoint>>

Source

pub fn get_overlapping_objects( &mut self, aabb_min: [f64; 3], aabb_max: [f64; 3], ) -> BulletResult<Vec<OverlappingObject>>

Source

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>

Source

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>

Source

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>>

Source

pub fn ray_test_batch( &mut self, options: &RayTestBatchOptions<'_>, ) -> BulletResult<Vec<RayHit>>

Source§

impl PhysicsClient

! =====================================================================================================================================

§Rendering, Debug & Visualization
APIStatusNotes
renderImagePendingObsolete; low priority
getCameraImageImplementedHigh effort (buffers)
isNumpyEnabledPendingSimple flag query
computeViewMatrixImplementedMath helper
computeViewMatrixFromYawPitchRollImplementedMath helper
computeProjectionMatrixImplementedMath helper
computeProjectionMatrixFOVImplementedMath helper
addUserDebugLineImplementedDebug draw
addUserDebugPointsImplementedDebug draw
addUserDebugTextImplementedDebug draw
addUserDebugParameterImplementedGUI slider/button
readUserDebugParameterImplementedGUI feedback
removeUserDebugItemImplementedDebug cleanup
removeAllUserDebugItemsImplementedDebug cleanup
removeAllUserParametersImplementedDebug cleanup
setDebugObjectColorImplementedDebug override
getDebugVisualizerCameraImplementedVisualizer query
configureDebugVisualizerImplementedVisualizer toggle
resetDebugVisualizerCameraImplementedVisualizer camera
getVisualShapeDataImplementedVisual query
getCollisionShapeDataImplementedCollision query
Source

pub fn get_camera_image( &mut self, request: &CameraImageOptions, ) -> BulletResult<CameraImage>

Source

pub fn compute_view_matrix( camera_eye_position: [f32; 3], camera_target_position: [f32; 3], camera_up_vector: [f32; 3], ) -> [f32; 16]

Source

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]

Source

pub fn compute_projection_matrix( left: f32, right: f32, bottom: f32, top: f32, near_val: f32, far_val: f32, ) -> [f32; 16]

Source

pub fn compute_projection_matrix_fov( fov: f32, aspect: f32, near_val: f32, far_val: f32, ) -> [f32; 16]

Source

pub fn add_user_debug_line( &mut self, options: &DebugLineOptions, ) -> BulletResult<i32>

Source

pub fn add_user_debug_points( &mut self, options: &DebugPointsOptions<'_>, ) -> BulletResult<i32>

Source

pub fn add_user_debug_text( &mut self, options: &DebugTextOptions<'_>, ) -> BulletResult<i32>

Source

pub fn add_user_debug_parameter( &mut self, options: &DebugParameterOptions<'_>, ) -> BulletResult<i32>

Source

pub fn read_user_debug_parameter( &mut self, parameter_id: i32, ) -> BulletResult<f64>

Source

pub fn remove_user_debug_item( &mut self, item_unique_id: i32, ) -> BulletResult<()>

Source

pub fn remove_all_user_debug_items(&mut self) -> BulletResult<()>

Source

pub fn remove_all_user_parameters(&mut self) -> BulletResult<()>

Source

pub fn set_debug_object_color( &mut self, object_unique_id: i32, link_index: i32, color: Option<[f64; 3]>, ) -> BulletResult<&mut Self>

Source

pub fn get_debug_visualizer_camera( &mut self, ) -> BulletResult<DebugVisualizerCamera>

Source

pub fn configure_debug_visualizer( &mut self, options: &DebugVisualizerOptions, ) -> BulletResult<&mut Self>

Source

pub fn reset_debug_visualizer_camera( &mut self, options: &ResetDebugVisualizerCameraOptions, ) -> BulletResult<&mut Self>

Source

pub fn get_visual_shape_data( &mut self, object_unique_id: i32, ) -> BulletResult<Vec<VisualShapeData>>

Source

pub fn get_collision_shape_data( &mut self, object_unique_id: i32, link_index: Option<i32>, ) -> BulletResult<Vec<CollisionShapeData>>

Source§

impl PhysicsClient

! =====================================================================================================================================

§VR, Input, Logging, Plugins & Misc
APIStatusNotes
getVREventsImplementedVR input
setVRCameraStateImplementedVR camera
getKeyboardEventsImplementedInput polling
getMouseEventsImplementedInput polling
startStateLoggingImplementedLogging
stopStateLoggingImplementedLogging
loadPluginImplementedPlugin system
unloadPluginImplementedPlugin system
executePluginCommandImplementedPlugin system
submitProfileTimingImplementedProfiling
setTimeOutImplementedClient timeout
getAPIVersionImplementedStatic constant
Source

pub fn get_vr_events( &mut self, options: &VrEventsOptions, ) -> BulletResult<Vec<VrControllerEvent>>

Source

pub fn set_vr_camera_state( &mut self, options: &VrCameraStateOptions, ) -> BulletResult<&mut Self>

Source

pub fn get_keyboard_events(&mut self) -> BulletResult<Vec<KeyboardEvent>>

Source

pub fn get_mouse_events(&mut self) -> BulletResult<Vec<MouseEvent>>

Source

pub fn start_state_logging( &mut self, logging_type: LoggingType, file_name: impl AsRef<Path>, options: Option<impl Into<StateLoggingOptions>>, ) -> BulletResult<i32>

Source

pub fn stop_state_logging(&mut self, logging_id: i32) -> BulletResult<&mut Self>

Source

pub fn load_plugin( &mut self, plugin_path: &str, postfix: Option<&str>, ) -> BulletResult<i32>

Source

pub fn unload_plugin(&mut self, plugin_unique_id: i32) -> BulletResult<()>

Source

pub fn execute_plugin_command( &mut self, options: &PluginCommandOptions<'_>, ) -> BulletResult<PluginCommandResult>

Source

pub fn submit_profile_timing( &mut self, event_name: Option<&str>, ) -> BulletResult<()>

Source

pub fn set_time_out(&mut self, time_out_seconds: f64) -> BulletResult<&mut Self>

Source

pub fn get_api_version(&self) -> i32

Trait Implementations§

Source§

impl Drop for PhysicsClient

Source§

fn drop(&mut self)

Executes the destructor for this type. Read more

Auto Trait Implementations§

Blanket Implementations§

Source§

impl<T> Any for T
where T: 'static + ?Sized,

Source§

fn type_id(&self) -> TypeId

Gets the TypeId of self. Read more
Source§

impl<T> Borrow<T> for T
where T: ?Sized,

Source§

fn borrow(&self) -> &T

Immutably borrows from an owned value. Read more
Source§

impl<T> BorrowMut<T> for T
where T: ?Sized,

Source§

fn borrow_mut(&mut self) -> &mut T

Mutably borrows from an owned value. Read more
Source§

impl<T> From<T> for T

Source§

fn from(t: T) -> T

Returns the argument unchanged.

Source§

impl<T, U> Into<U> for T
where U: From<T>,

Source§

fn into(self) -> U

Calls U::from(self).

That is, this conversion is whatever the implementation of From<T> for U chooses to do.

Source§

impl<X> Pipe for X

Source§

fn pipe<Return, Function>(self, f: Function) -> Return
where Self: Sized, Function: FnOnce(Self) -> Return,

Apply f to self. Read more
Source§

fn pipe_ref<'a, Return, Function>(&'a self, f: Function) -> Return
where Function: FnOnce(&'a Self) -> Return,

Apply f to &self. Read more
Source§

fn pipe_mut<'a, Return, Function>(&'a mut self, f: Function) -> Return
where Function: FnOnce(&'a mut Self) -> Return,

Apply f to &mut self. Read more
Source§

fn pipe_as_ref<'a, Param, Return, Function>(&'a self, f: Function) -> Return
where Self: AsRef<Param>, Param: 'a + ?Sized, Function: FnOnce(&'a Param) -> Return,

Apply f to &self where f takes a single parameter of type Param and Self implements trait AsRef<Param>. Read more
Source§

fn pipe_as_mut<'a, Param, Return, Function>(&'a mut self, f: Function) -> Return
where Self: AsMut<Param>, Param: 'a + ?Sized, Function: FnOnce(&'a mut Param) -> Return,

Apply f to &mut self where f takes a single parameter of type Param and Self implements trait AsMut<Param>. Read more
Source§

fn pipe_deref<'a, Param, Return, Function>(&'a self, f: Function) -> Return
where Self: Deref<Target = Param>, Param: 'a + ?Sized, Function: FnOnce(&'a Param) -> Return,

Apply f to &self where f takes a single parameter of type Param and Self implements trait Deref<Target = Param>. Read more
Source§

fn pipe_deref_mut<'a, Param, Return, Function>( &'a mut self, f: Function, ) -> Return
where Self: DerefMut<Target = Param>, Param: 'a + ?Sized, Function: FnOnce(&'a mut Param) -> Return,

Apply f to &mut self where f takes a single parameter of type Param and Self implements trait DerefMut<Target = Param>. Read more
Source§

fn pipe_borrow<'a, Param, Return, Function>(&'a self, f: Function) -> Return
where Self: Borrow<Param>, Param: 'a + ?Sized, Function: FnOnce(&'a Param) -> Return,

Apply f to &self where f takes a single parameter of type Param and Self implements trait Borrow<Param>. Read more
Source§

fn pipe_borrow_mut<'a, Param, Return, Function>( &'a mut self, f: Function, ) -> Return
where Self: BorrowMut<Param>, Param: 'a + ?Sized, Function: FnOnce(&'a mut Param) -> Return,

Apply f to &mut self where f takes a single parameter of type Param and Self implements trait BorrowMut<Param>. Read more
Source§

impl<T> Same for T

Source§

type Output = T

Should always be Self
Source§

impl<SS, SP> SupersetOf<SS> for SP
where SS: SubsetOf<SP>,

Source§

fn to_subset(&self) -> Option<SS>

The inverse inclusion map: attempts to construct self from the equivalent element of its superset. Read more
Source§

fn is_in_subset(&self) -> bool

Checks if self is actually part of its subset T (and can be converted to it).
Source§

fn to_subset_unchecked(&self) -> SS

Use with care! Same as self.to_subset but without any property checks. Always succeeds.
Source§

fn from_subset(element: &SS) -> SP

The inclusion map: converts self to the equivalent element of its superset.
Source§

impl<T, U> TryFrom<U> for T
where U: Into<T>,

Source§

type Error = Infallible

The type returned in the event of a conversion error.
Source§

fn try_from(value: U) -> Result<T, <T as TryFrom<U>>::Error>

Performs the conversion.
Source§

impl<T, U> TryInto<U> for T
where U: TryFrom<T>,

Source§

type Error = <U as TryFrom<T>>::Error

The type returned in the event of a conversion error.
Source§

fn try_into(self) -> Result<U, <U as TryFrom<T>>::Error>

Performs the conversion.