Expand description
A Rust interface for Bullet physics inspired by PyBullet.
§Example
use std::{thread, time::Duration};
use anyhow::Result;
use nalgebra::{Isometry3, Vector3};
use rubullet::*;
fn main() -> Result<()> {
let mut physics_client = PhysicsClient::connect(Mode::Gui)?;
physics_client.set_additional_search_path("../rubullet-sys/bullet3/libbullet3/data")?;
physics_client.set_gravity(Vector3::new(0.0, 0.0, -10.0));
let _plane_id = physics_client.load_urdf("plane.urdf", None)?;
let cube_start_position = Isometry3::translation(0.0, 0.0, 1.0);
let box_id = physics_client.load_urdf(
"r2d2.urdf",
UrdfOptions {
base_transform: cube_start_position,
..Default::default()
},
)?;
for _ in 0..10000 {
physics_client.step_simulation()?;
thread::sleep(Duration::from_micros(4167));
}
let cube_transform = physics_client.get_base_transform(box_id)?;
println!("{}", cube_transform);
Ok(())
}
Re-exports§
Modules§
- logging_
utils - Contains methods and types which are useful for logging
Structs§
- Aabb
- axis-aligned minimum bounding box
- Activation
State - AddDebug
Line Options - Represents options for
add_user_debug_line
- AddDebug
Text Options - Represents options for
add_user_debug_text
- BodyId
- The unique ID for a body within a physics server.
- Body
Info - Contains the body name and base name of a Body. BodyInfo is returned by get_body_info
- Camera
Image Options - Options for
get_camera_image
- Change
Constraint Options - contains the parameters for
change_constraint
method. - Change
Dynamics Options - Dynamics options for the
change_dynamics
method. Some options do not depend on the given link and apply to the whole body. These options are: - Change
Visual Shape Options - This struct keeps the information to change a visual shape with the change_visual_shape method.
- Collision
Id - The unique ID for a Collision Shape.
- Constraint
Id - The unique ID for a constraint.
- Constraint
Info - contains the parameters for
change_constraint
method. - Contact
Point - Is the result of the get_closest_points and get_contact_points methods.
- Debug
Visualizer Camera Info - Contains the state of the Gui camera.
Is returned by
get_debug_visualizer_camera
. - Dynamics
Info - Contains information about the mass, center of mass, friction and other properties of the base and links.
Is returned by
get_dynamics_info
. - Error
- Images
- Stores the images from
get_camera_image()
- Inverse
Kinematics Null Space Parameters - Parameters for Inverse Kinematics using the Nullspace
- Inverse
Kinematics Parameters - Parameters for the
calculate_inverse_kinematics()
You can easily create them using theInverseKinematicsParametersBuilder
- Inverse
Kinematics Parameters Builder - creates
InverseKinematicsParameters
using the Builder Pattern which can then be used incalculate_inverse_kinematics()
. Use the build() method to get the parameters. - ItemId
- The unique ID for a User Debug Parameter Item
- Jacobian
- Specifies a jacobian with 6 rows. The jacobian is split into a linear part and an angular part.
- Joint
Info - Contains basic information about a joint like its type and name. It can be obtained via
get_joint_info()
- Joint
State - Represents the current state of a joint. It can be retrieved via
get_joint_state()
- Keyboard
Event - Represents a key press Event
- Link
State - Describes the State of a Link
- Load
Model Flags - Use flag for loading the model. Flags can be combined with the
|
-operator. Example: - LogFlags
- LogId
- The unique ID for a Logging Object.
- Mouse
Button State - Represents the different possible states of a mouse button
- Multi
Body Options - Specifies all options for create_multi_body.
Most of the the time you are probably fine using
MultiBodyOptions::default()
or just setting the base_pose and/or mass - Overlapping
Object - Is the result of
get_overlapping_objects
. Each object specifies a link of a body. - Physics
Client - Connection to a physics server.
- Physics
Engine Parameters - See
SetPhysicsEngineParameterOptions
for a description of the parameters. - Physics
Server - A PhysicsServer is actually a PhysicsClient which is run as a TCP Server and with
all methods apart from
is_connected
disabled, as they would fail otherwise. This is for advanced users and you are usually you should be better of with a normalPhysicsClient
. - RayHit
Info - RayTest
Batch Options - Options for
ray_test_batch
- RayTest
Options - Options for
ray_test
- Renderer
AuxFlags - flags for camera rendering
- Reset
Flags - Experimental flags, best to ignore.
- SdfOptions
- Options for loading models from an SDF file into the physics server.
- SetPhysics
Engine Parameter Options - Options for the
set_physics_engine_parameter
method. - Soft
Body Options - options for
load_soft_body
- StateId
- The unique ID for a State Object.
- State
Logging Options - Texture
Id - The unique ID for a Texture
- Urdf
Options - Options for loading a URDF into the physics server.
- Velocity
- Contains the cartesian velocity stored as Vector with 6 elements (x,y,z,wx,wy,wz).
- Visual
Id - The unique ID for a Visual Shape
- Visual
Shape Data - Contains information about the visual shape of a body. It is returned by get_visual_shape_data
- Visual
Shape Flags - Experimental flags, best to ignore.
- Visual
Shape Options - VisualShape options are for the create_visual_shape function to specify additional options like the color.
Enums§
- Body
Type - Constraint
Solver Type - Control
Command - The ControlCommand specifies how the robot should move (Position Control, Velocity Control, Torque Control)
Each type of ControlCommand has its own set of Parameters. The Position mode for example takes a desired joint
position as input. It can be used in
set_joint_motor_control()
- Control
Command Array - Can be used in
set_joint_motor_control_array()
. It is basically the same asControlCommand
but with arrays. SeeControlCommand
for details. - Debug
Visualizer Flag - Flags for
configure_debug_visualizer()
- External
Force Frame - Frame for
apply_external_torque()
andapply_external_force()
- Geometric
Collision Shape - Collision shape which can be put the create_collision_shape method
- Geometric
Visual Shape - Visual shapes to put into the create_visual_shape method together with VisualShapeOptions
- IkSolver
- Specifies which Inverse Kinematics Solver to use in
calculate_inverse_kinematics()
- Joint
Feedback Mode - Specifies joint feedback frame. Is used in
SetPhysicsEngineParameterOptions::joint_feedback_mode
- Joint
Type - An enum to represent different types of joints
- Logging
Type - Mode
- Ways to connect to physics clients.
- Mouse
Event - Mouse Events can either be a “Move” or a “Button” event. A “Move” event is when the mouse is moved in the OpenGL window and a “Button” even is when a mouse button is clicked.
- Renderer
- Server
Mode - Choose which type of server you want.