Struct rubullet::PhysicsClient[][src]

pub struct PhysicsClient { /* fields omitted */ }

Connection to a physics server.

This serves as an abstraction over the possible physics servers, providing a unified interface.

Implementations

impl PhysicsClient[src]

pub fn connect(mode: Mode) -> Result<PhysicsClient, Error>[src]

Creates a PhysicsClient by connecting to a physics simulation.

There are different Modes for creating a PhysicsClient:

  • Gui mode creates an OpenGL window where the simulation will be visualized. There can only be one Gui instance at a time.
  • Direct mode will run without any visualization. In this mode you cannot access OpenGL features like debugging lines, text and Parameters. You also cannot get mouse or keyboard events. The can be many instances of PhysicsClients running in Direct mode

Other modes are currently not implemented.

pub fn reset_simulation(&mut self)[src]

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

pub fn set_time_step(&mut self, time_step: Duration)[src]

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.

pub fn set_real_time_simulation(&mut self, enable_real_time_simulation: bool)[src]

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

pub fn set_additional_search_path<P: AsRef<Path>>(
    &mut self,
    path: P
) -> Result<(), Error>
[src]

Sets an additional search path for loading assets.

pub fn set_gravity<GravityVector: Into<Vector3<f64>>>(
    &mut self,
    gravity: GravityVector
) -> Result<(), Error>
[src]

Sets the default gravity force for all objects.

By default, there is no gravitational force enabled.

Arguments

  • gravity - a gravity vector. Can be a Vector3, a [f64;3]-array or anything else that can be converted into a Vector3.

pub fn load_urdf<P: AsRef<Path>, Options: Into<Option<UrdfOptions>>>(
    &mut self,
    file: P,
    options: Options
) -> Result<BodyId, Error>
[src]

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 anyhow::Result;
use rubullet::*;
fn main() -> Result<()> {
    let mut physics_client = PhysicsClient::connect(Mode::Direct)?;
    physics_client.set_additional_search_path("../rubullet-sys/bullet3/libbullet3/data")?;
    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",
            UrdfOptions {
                flags: LoadModelFlags::URDF_ENABLE_CACHED_GRAPHICS_SHAPES,
                ..Default::default()
            },
        )?;
    }
    assert_eq!(11, physics_client.get_num_bodies());
    Ok(())
}

pub fn load_sdf<P: AsRef<Path>, Options: Into<Option<SdfOptions>>>(
    &mut self,
    file: P,
    options: Options
) -> Result<Vec<BodyId>, Error>
[src]

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 anyhow::Result;
use rubullet::*;
fn main() -> Result<()> {
    let mut physics_client = PhysicsClient::connect(Mode::Direct)?;
    physics_client.set_additional_search_path("../rubullet-sys/bullet3/libbullet3/data")?;
    let cubes = physics_client.load_sdf("two_cubes.sdf", None)?;
    assert_eq!(3, cubes.len()); // 2 cubes + 1 plane
    Ok(())
}

pub fn load_mjcf<P: AsRef<Path>, Flags: Into<Option<LoadModelFlags>>>(
    &mut self,
    file: P,
    flags: Flags
) -> Result<Vec<BodyId>, Error>
[src]

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 anyhow::Result;
use rubullet::*;
fn main() -> Result<()> {
    let mut physics_client = PhysicsClient::connect(Mode::Direct)?;
    physics_client.set_additional_search_path("../rubullet-sys/bullet3/libbullet3/data")?;
    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(())
}

pub fn step_simulation(&mut self) -> Result<(), Error>[src]

Performs all the actions in a single forward dynamics simulation step such as collision detection, constraint solving, and integration.

pub fn get_base_transform(
    &mut self,
    body: BodyId
) -> Result<Isometry3<f64>, Error>
[src]

Reports the current transform of the base.

Arguments

pub fn reset_base_transform(&mut self, body: BodyId, pose: &Isometry3<f64>)[src]

You can reset the position and orientation of the base (root) of each object. It is best only to do this at the start, and not during a running simulation, since the command will override the effect of all physics simulation. The linear and angular velocity is set to zero. You can use reset_base_velocity to reset to a non-zero linear and/or angular velocity.

Arguments

  • body - the BodyId, as returned by load_urdf etc.
  • pose - reset the base of the object at the specified position in world space coordinates

pub fn get_base_velocity(&mut self, body: BodyId) -> Result<Velocity, Error>[src]

You get access to the linear and angular velocity of the base of a body.

Arguments

Return

Returns a result which is either a Velocity (linear velocity, angular velocity) or an Error

See also

reset_base_velocity to reset a base velocity and for examples

pub fn reset_base_velocity<IntoVector3: Into<Vector3<f64>>, Linear: Into<Option<IntoVector3>>, Angular: Into<Option<IntoVector3>>>(
    &mut self,
    body: BodyId,
    linear_velocity: Linear,
    angular_velocity: Angular
)
[src]

Reset the linear and/or angular velocity of the base of a body

Arguments

  • body - the BodyId, as returned by load_urdf etc.
  • linear_velocity - either a [f64;3] or a Vector3 which contains the desired linear velocity (x,y,z) in Cartesian world coordinates or None to not change the linear velocity
  • angular_velocity - either a [f64;3] or a Vector3 which contains the desired angular velocity (wx,wy,wz) in Cartesian world coordinates or None to not change the angular velocity

Example

use anyhow::Result;
use nalgebra::{Isometry3, Vector3};
use rubullet::*;

fn main() -> Result<()> {
   let mut physics_client = PhysicsClient::connect(Mode::Direct)?;
   physics_client.set_additional_search_path("../rubullet-sys/bullet3/libbullet3/data")?;
   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()
       },
   )?;

   physics_client
       .reset_base_velocity(box_id, [1., 2., 3.], [4., 5., 6.]);
   let velocity = physics_client.get_base_velocity(box_id)?;
   assert_eq!(velocity.to_vector().as_slice(), &[1., 2., 3., 4., 5., 6.]);

   physics_client
       .reset_base_velocity(box_id, Vector3::zeros(), None);
   let velocity = physics_client.get_base_velocity(box_id)?;
   assert_eq!(velocity.to_vector().as_slice(), &[0., 0., 0., 4., 5., 6.]);

   physics_client
       .reset_base_velocity(box_id, None, [0., 0., 0.]);
   let velocity = physics_client.get_base_velocity(box_id)?;
   assert_eq!(velocity.to_vector().as_slice(), & [0.; 6]);

   Ok(())
}

Queries the Cartesian world pose for the center of mass for a link. It will also report the local inertial frame of the center of mass to the URDF link frame, to make it easier to compute the graphics/visualization frame.

Warning

  • the returned link velocity will only be available if compute_link_velocity is set to true. Otherwise, it will be None.

Arguments

  • body - the BodyId, as returned by load_urdf etc.
  • link_index - link index
  • compute_link_velocity - will compute the link velocity and put it into the LinkState if set to true. Otherwise the velocity within the LinkState will be invalid.
  • compute_forward_kinematics - if true the Cartesian world pose will be recomputed using forward kinematics.

See also

getLinkStates will return the information for multiple links. Instead of link_index it will accept link_indices as an array of i32. This can improve performance by reducing calling overhead of multiple calls to get_link_state() .

Warning

  • the returned link velocity will only be valid if compute_link_velocity is set to true

Arguments

  • body - the BodyId, as returned by load_urdf etc.
  • link_indices - link indices
  • compute_link_velocity - will compute the link velocity and put it into the LinkState if set to true. Otherwise the velocity within the LinkState will be invalid.
  • compute_forward_kinematics - if true the Cartesian world pose will be recomputed using forward kinematics.

See also

pub fn change_dynamics_linear_damping(
    &mut self,
    body: BodyId,
    linear_damping: f64
)
[src]

pub fn change_dynamics_angular_damping(
    &mut self,
    body: BodyId,
    angular_damping: f64
)
[src]

pub fn get_num_joints(&mut self, body: BodyId) -> usize[src]

returns the number of joints of a body

Arguments

pub fn get_joint_info(&mut self, body: BodyId, joint_index: usize) -> JointInfo[src]

Query info about a joint like its name and type

Arguments

See JointInfo for an example use

pub fn reset_joint_state<Velocity: Into<Option<f64>>>(
    &mut self,
    body: BodyId,
    joint_index: usize,
    value: f64,
    velocity: Velocity
) -> Result<(), Error>
[src]

You can reset the state of the joint. It is best only to do this at the start, while not running the simulation: resetJointState overrides all physics simulation. Note that we only support 1-DOF motorized joints at the moment, sliding joint or revolute joints.

Arguments

  • body - the BodyId, as returned by load_urdf etc.
  • joint_index - a joint index in the range [0..get_num_joints(body)]
  • value - the joint position (angle in radians or position)
  • velocity- optional joint velocity (angular or linear velocity)

pub fn get_joint_state(
    &mut self,
    body: BodyId,
    joint_index: usize
) -> Result<JointState, Error>
[src]

get information about the joint state such as the joint position, velocity, joint reaction forces and joint motor torque.

Arguments

pub fn get_joint_states(
    &mut self,
    body: BodyId,
    joint_indices: &[usize]
) -> Result<Vec<JointState>, Error>
[src]

get_joint_states is the array version of get_joint_state. Instead of passing in a single joint_index, you pass in a list of joint_indices.

Arguments

pub fn calculate_mass_matrix(
    &mut self,
    body: BodyId,
    object_positions: &[f64]
) -> Result<DMatrix<f64>, Error>
[src]

calculate_mass_matrix will compute the system inertia for an articulated body given its joint positions. The composite rigid body algorithm (CBRA) is used to compute the mass matrix.

Arguments

  • body - the BodyId, as returned by load_urdf etc.
  • object_positions - joint positions for each link

Return

The result is the square mass matrix with dimensions dofCount * dofCount, stored as a list of dofCount rows, each row is a list of dofCount mass matrix elements. Note that when multidof (spherical) joints are involved, calculate_mass_matrix will use a different code path, that is a bit slower.

pub fn calculate_inverse_kinematics(
    &mut self,
    body: BodyId,
    params: InverseKinematicsParameters<'_>
) -> Result<Vec<f64>, Error>
[src]

You can compute the joint angles that makes the end-effector reach a given target position in Cartesian world space. Internally, Bullet uses an improved version of Samuel Buss Inverse Kinematics library. At the moment only the Damped Least Squares method with or without Null Space control is exposed, with a single end-effector target. Optionally you can also specify the target orientation of the end effector. In addition, there is an option to use the null-space to specify joint limits and rest poses.

See InverseKinematicsParametersBuilder and InverseKinematicsParameters for more details.

Arguments

Note

If you set the NullSpaceParameters wrong this function will return an error, while the PyBullet just uses the normal Ik instead.

pub fn calculate_inverse_dynamics(
    &mut self,
    body: BodyId,
    object_positions: &[f64],
    object_velocities: &[f64],
    object_accelerations: &[f64]
) -> Result<Vec<f64>, Error>
[src]

calculate_inverse_dynamics will compute the forces needed to reach the given joint accelerations, starting from specified joint positions and velocities. The inverse dynamics is computed using the recursive Newton Euler algorithm (RNEA).

Arguments

  • body - the BodyId, as returned by load_urdf etc.
  • object_positions - joint positions for each degree of freedom (DoF). Note that fixed joints have 0 degrees of freedom. The base is skipped/ignored in all cases (floating base and fixed base).
  • object_velocities - joint velocities for each degree of freedom (DoF)
  • object_acceleration - desired joint accelerations for each degree of freedom (DoF)

Note

When multidof (spherical) joints are involved, the calculate_inverse_dynamics uses a different code path and is a bit slower. Also note that calculate_inverse_dynamics ignores the joint/link damping, while forward dynamics (in stepSimulation) includes those damping terms. So if you want to compare the inverse dynamics and forward dynamics, make sure to set those damping terms to zero using change_dynamics_linear_damping and change_dynamics_angular_damping.

pub fn calculate_jacobian<LocalPosition: Into<Translation3<f64>>>(
    &mut self,
    body: BodyId,
    link_index: usize,
    local_position: LocalPosition,
    object_positions: &[f64],
    object_velocities: &[f64],
    object_accelerations: &[f64]
) -> Result<Jacobian, Error>
[src]

calculate_jacobian will compute the translational and rotational jacobians for a point on a link, e.g. x_dot = J * q_dot. The returned jacobians are slightly different depending on whether the root link is fixed or floating. If floating, the jacobians will include columns corresponding to the root link degrees of freedom; if fixed, the jacobians will only have columns associated with the joints. The function call takes the full description of the kinematic state, this is because calculateInverseDynamics is actually called first and the desired jacobians are extracted from this; therefore, it is reasonable to pass zero vectors for joint velocities and accelerations if desired.

Arguments

  • body - the BodyId, as returned by load_urdf etc.
  • link_index - link index for the jacobian.
  • local_position - the point on the specified link to compute the jacobian for, in link local coordinates around its center of mass. It needs to be something that can be converted to a Translation3 (Vector3, Point3, [f64;3], ..)
  • object_positions - joint positions (angles)
  • object_velocities - joint velocities
  • object_accelerations - desired joint accelerations

See jacobian.rs for an example

pub fn set_joint_motor_control(
    &mut self,
    body: BodyId,
    joint_index: usize,
    control_mode: ControlMode,
    maximum_force: Option<f64>
)
[src]

sets joint motor commands. This function is the rust version of setJointMotorControl2 from PyBullet. This function differs a bit from the corresponding PyBullet function. Instead of providing optional arguments that depend on the Control Mode, the necessary parameters are directly encoded in the ControlMode Enum.

We can control a robot by setting a desired control mode for one or more joint motors. During the stepSimulation the physics engine will simulate the motors to reach the given target value that can be reached within the maximum motor forces and other constraints.

Important Note:

by default, each revolute joint and prismatic joint is motorized using a velocity motor. You can disable those default motor by using a maximum force of 0. This will let you perform torque control. For Example:

    client.set_joint_motor_control(panda_id, joint_index, ControlMode::Velocity(0.), Some(0.));

Arguments

  • body - the BodyId, as returned by load_urdf etc.
  • joint_index - link index in range [0..get_num_joints(bodyUniqueId)] (note that link index == joint index)
  • control_mode - Specifies how to control the robot (Position, Torque, etc.)
  • maximum_force - this is the maximum motor force used to reach the target value. It has no effect in Torque mode.

Example

use rubullet::{ControlMode, PhysicsClient, Mode};
use anyhow::Result;
pub fn main() -> Result<()> {
    let mut client = PhysicsClient::connect(Mode::Direct)?;
    client.set_additional_search_path("../rubullet-sys/bullet3/libbullet3/examples/pybullet/gym/pybullet_data")?;
    let panda_id = client.load_urdf("franka_panda/panda.urdf", None)?;
    let joint_index = 1;
    client.set_joint_motor_control(panda_id, joint_index, ControlMode::Torque(100.), None);
    client.set_joint_motor_control(panda_id, joint_index, ControlMode::Position(0.4), Some(1000.));
Ok(())
}

pub fn set_joint_motor_control_array(
    &mut self,
    body: BodyId,
    joint_indices: &[usize],
    control_mode: ControlModeArray<'_>,
    maximum_force: Option<&[f64]>
) -> Result<(), Error>
[src]

The array version of set_joint_motor_control(). This reduces the calling overhead and should therefore be faster. See set_joint_motor_control() for more details.

Arguments

  • body - the BodyId, as returned by load_urdf etc.
  • joint_indices - list of link indices in range [0..get_num_joints(bodyUniqueId)] (note that link index == joint index)
  • control_mode - Specifies how to control the robot (Position, Torque, etc.)
  • maximum_force - this is the maximum motor force used to reach the target value for each joint. It has no effect in Torque mode.

pub fn compute_view_matrix<Point: Into<Point3<f32>>, Vector: Into<Vector3<f32>>>(
    camera_eye_position: Point,
    camera_target_position: Point,
    camera_up_vector: Vector
) -> Matrix4<f32>
[src]

computes the view matrix which can be used together with the projection matrix to generate camera images within the simulation

Arguments

  • camera_eye_position - eye position in Cartesian world coordinates
  • camera_target_position - position of the target (focus) point, in Cartesian world coordinates
  • camera_up_vector - up vector of the camera, in Cartesian world coordinates

Example

use rubullet::PhysicsClient;
use nalgebra::{Point3, Vector3};

// variant 1: using arrays
let eye_position = [1.; 3];
let target_position = [1., 0., 0.];
let up_vector = [0., 1., 0.];
let view_matrix_from_arrays = PhysicsClient::compute_view_matrix(eye_position, target_position, up_vector);

// variant 2: using vectors and points
let eye_position = Point3::new(1.,1.,1.);
let target_position = Point3::new(1., 0., 0.);
let up_vector = Vector3::new(0., 1., 0.);
let view_matrix_from_points = PhysicsClient::compute_view_matrix(eye_position, target_position, up_vector);
assert_eq!(view_matrix_from_arrays.as_slice(),view_matrix_from_points.as_slice());

See also

pub fn compute_view_matrix_from_yaw_pitch_roll<Point: Into<Point3<f32>>>(
    camera_target_position: Point,
    distance: f32,
    yaw: f32,
    pitch: f32,
    roll: f32,
    z_axis_is_up: bool
) -> Matrix4<f32>
[src]

computes the view matrix which can be used together with the projection matrix to generate camera images within the simulation

Arguments

  • camera_target_position - position of the target (focus) point, in Cartesian world coordinates
  • distance - distance from eye to focus point
  • yaw - yaw angle in degrees left/right around up-axis.
  • pitch - pitch in degrees up/down.
  • roll - roll in degrees around forward vector
  • z_axis_is_up - if true the Z axis is the up axis of the camera. Otherwise the Y axis will be the up axis.

Example

use rubullet::PhysicsClient;
use nalgebra::Point3;
// variant 1: using array
let target_position = [1., 0., 0.];
let view_matrix_from_array = PhysicsClient::compute_view_matrix_from_yaw_pitch_roll(
    target_position,
    0.6,
    0.2,
    0.3,
    0.5,
    false,
);
// variant 1: using Point3
let target_position = Point3::new(1., 0., 0.);
let view_matrix_from_point = PhysicsClient::compute_view_matrix_from_yaw_pitch_roll(
    target_position,
    0.6,
    0.2,
    0.3,
    0.5,
    false,
);
assert_eq!(view_matrix_from_array.as_slice(),view_matrix_from_point.as_slice());

See also

pub fn compute_projection_matrix(
    left: f32,
    right: f32,
    bottom: f32,
    top: f32,
    near_val: f32,
    far_val: f32
) -> Matrix4<f32>
[src]

computes the projection matrix which can be used together with the view matrix to generate camera images within the simulation

Arguments

  • left - left screen (canvas) coordinate
  • right - right screen (canvas) coordinate
  • bottom - bottom screen (canvas) coordinate
  • top - top screen (canvas) coordinate
  • near - near plane distance
  • far - far plane distance

See also

pub fn compute_projection_matrix_fov(
    fov: f32,
    aspect: f32,
    near_val: f32,
    far_val: f32
) -> Matrix4<f32>
[src]

computes the projection matrix which can be used together with the view matrix to generate camera images within the simulation

Arguments

  • fov - left screen (canvas) coordinate
  • aspect - right screen (canvas) coordinate
  • near_val - near plane distance
  • far_val - far plane distance

See also

pub fn get_camera_image(
    &mut self,
    width: i32,
    height: i32,
    view_matrix: Matrix4<f32>,
    projection_matrix: Matrix4<f32>
) -> Result<Images, Error>
[src]

returns an RGBA, depth and segmentation images.

Note

Depth and segmentation images are currently not really images as the image crate does not properly support these types yet.

Arguments

  • width - eye position in Cartesian world coordinates
  • height - position of the target (focus) point, in Cartesian world coordinates
  • view_matrix - view matrix, see compute_view_matrix
  • projection_matrix - projection matrix, see compute_projection_matrix

See also

pub fn configure_debug_visualizer(
    &mut self,
    flag: DebugVisualizerFlag,
    enable: bool
)
[src]

This method can configure some settings of the built-in OpenGL visualizer, such as enabling or disabling wireframe, shadows and GUI rendering. This is useful since some laptops or Desktop GUIs have performance issues with our OpenGL 3 visualizer.

Arguments

  • flag - Feature to enable or disable
  • enable - enables or disables the feature

pub fn add_user_debug_line<Options: Into<Option<AddDebugLineOptions>>, Start: Into<Point3<f64>>, End: Into<Point3<f64>>>(
    &mut self,
    line_from_xyz: Start,
    line_to_xyz: End,
    options: Options
) -> Result<ItemId, Error>
[src]

You can add a 3d line specified by a 3d starting point (from) and end point (to), a color [red,green,blue], a line width and a duration in seconds.

Arguments

  • line_from_xyz - starting point of the line in Cartesian world coordinates. Can be a Point3, a Vector3, an array or anything else than can be converted into a Point3.
  • line_to_xyz - end point of the line in Cartesian world coordinates. Can be a Point3, a Vector3, an array or anything else than can be converted into a Point3.
  • options - advanced options for the line. Use None for default settings.

Return

A unique item id of the line. You can use remove_user_debug_item() to delete it.

Example

let mut client = PhysicsClient::connect(Gui)?;
    let red_line = client.add_user_debug_line(
        [0.; 3],
        Point3::new(1.,1.,1.),
        AddDebugLineOptions {
            line_color_rgb: [1., 0., 0.],
            ..Default::default()
        },
    )?;

pub fn add_user_debug_parameter<'a, Text: Into<&'a str>>(
    &mut self,
    param_name: Text,
    range_min: f64,
    range_max: f64,
    start_value: f64
) -> Result<ItemId, Error>
[src]

Lets you add custom sliders and buttons to tune parameters.

Arguments

  • param_name - name of the parameter. Needs to be something that can be converted to a &str.
  • range_min - minimum value of the slider. If minimum value > maximum value a button instead of a slider will appear.
  • range_max - maximum value of the slider
  • start_value - starting value of the slider

Return

A unique item id of the button/slider, which can be used by read_user_debug_parameter()

Example

use rubullet::PhysicsClient;
use rubullet::Mode::Gui;
use anyhow::Result;
pub fn main() -> Result<()> {
    let mut client = PhysicsClient::connect(Gui)?;
    let slider = client.add_user_debug_parameter("my_slider",0.,1.,0.5)?;
    let button = client.add_user_debug_parameter("my_button",1.,0.,1.)?;
    let value_slider = client.read_user_debug_parameter(slider)?;
    let value_button = client.read_user_debug_parameter(button)?; // value increases by one for every press
    Ok(())
}

pub fn read_user_debug_parameter(&mut self, item: ItemId) -> Result<f64, Error>[src]

Reads the current value of a debug parameter. For a button the value will increase by 1 every time the button is clicked.

Arguments

item - the unique item generated by [add_user_debug_parameter())Self::add_user_debug_parameter() See [add_user_debug_parameter())Self::add_user_debug_parameter() for an example.

pub fn add_user_debug_text<'a, Text: Into<&'a str>, Position: Into<Point3<f64>>, Options: Into<Option<AddDebugTextOptions>>>(
    &mut self,
    text: Text,
    text_position: Position,
    options: Options
) -> Result<ItemId, Error>
[src]

You can add some 3d text at a specific location using a color and size.

Arguments

  • text - text represented by something which can be converted to a &str
  • text_position - 3d position of the text in Cartesian world coordinates [x,y,z]. Can be a Point3, a Vector3, an array or anything else than can be converted into a Point3.
  • options - advanced options for the text. Use None for default settings.

Return

A unique item id of the text. You can use remove_user_debug_item() to delete it.

Example

let mut client = PhysicsClient::connect(Gui)?;
    let text = client.add_user_debug_text("My text", Point3::new(0., 0., 1.), None)?;
    let text_red_on_floor = client.add_user_debug_text(
        "My red text on the floor",
        [0.;3],
        AddDebugTextOptions {
            text_color_rgb: [1., 0., 0.],
            text_orientation: Some(UnitQuaternion::from_euler_angles(0.,0.,0.)),
            ..Default::default()
        },
    )?;

pub fn remove_user_debug_item(&mut self, item: ItemId)[src]

Removes debug items which were created with add_user_debug_line, add_user_debug_parameter or add_user_debug_text.

Arguments

  • item - unique id of the debug item to be removed (line, text etc)

Example

    let text = client.add_user_debug_text("My text", [0., 0., 1.], None)?;
    client.remove_user_debug_item(text);

pub fn remove_all_user_debug_items(&mut self)[src]

will remove all debug items (text, lines etc).

Example

let mut client = PhysicsClient::connect(Gui)?;
    let text = client.add_user_debug_text("My text", Point3::new(0., 0., 1.), None)?;
    let text_2 = client.add_user_debug_text("My text2", [0., 0., 2.], None)?;
    client.remove_all_user_debug_items();

pub fn set_debug_object_color<Link: Into<Option<usize>>, Color: Into<Option<[f64; 3]>>>(
    &mut self,
    body: BodyId,
    link_index: Link,
    object_debug_color: Color
)
[src]

The built-in OpenGL visualizers have a wireframe debug rendering feature: press ‘w’ to toggle. The wireframe has some default colors. You can override the color of a specific object and link using this method.

Arguments

  • body - the BodyId, as returned by load_urdf etc.
  • link_index - link index. Use None for the base.
  • object_debug_color - debug color in [Red,Green,Blue]. If not provided, the custom color will be removed.

pub fn get_keyboard_events(&mut self) -> Vec<KeyboardEvent>[src]

You can receive all keyboard events that happened since the last time you called get_keyboard_events() This method will return a List of all KeyboardEvents that happened since then.

Example

use std::time::Duration;
use anyhow::Result;
use rubullet::*;

fn main() -> Result<()> {
    let mut physics_client = PhysicsClient::connect(Mode::Gui)?;
    loop {
        let events = physics_client.get_keyboard_events();
        for event in events.iter() {
            if event.key == 'i' && event.was_triggered() {
                println!("i-key was pressed");
            }
        }
        std::thread::sleep(Duration::from_secs_f64(0.01));
    }
    Ok(())
}

pub fn get_mouse_events(&mut self) -> Vec<MouseEvent>[src]

Similar to get_keyboard_events() you can get the mouse events that happened since the last call to get_mouse_events(). All the mouse move events are merged into a single mouse move event with the most up-to-date position. The mouse move event is only returned when the mouse has been moved. The mouse button event always includes the current mouse position.

Example

use anyhow::Result;
use rubullet::*;
use std::time::Duration;

fn main() -> Result<()> {
    let mut physics_client = PhysicsClient::connect(Mode::Gui)?;
    loop {
        let events = physics_client.get_mouse_events();
        for event in events.iter() {
            match event {
                MouseEvent::Move {
                    mouse_pos_x,
                    mouse_pos_y,
                } => {
                    println!(
                        "The mouse has moved to x: {}, y: {}",
                        mouse_pos_x, mouse_pos_y
                    );
                }
                MouseEvent::Button {
                    mouse_pos_x,
                    mouse_pos_y,
                    button_index,
                    button_state,
                } => {
                    println!(
                        "The mouse position is x: {}, y: {}",
                        mouse_pos_x, mouse_pos_y
                    );
                    if button_state.was_triggered() {
                        println!("Mouse Button {} has been triggered", button_index);
                    }
                }
            }
        }
        std::thread::sleep(Duration::from_secs_f64(0.01));
    }
    Ok(())
}

pub fn apply_external_force<Force: Into<Vector3<f64>>, Position: Into<Point3<f64>>, Link: Into<Option<usize>>>(
    &mut self,
    body: BodyId,
    link_index: Link,
    force_object: Force,
    position_object: Position,
    flags: ExternalForceFrame
)
[src]

Applies a force to a body.

Note that this method will only work when explicitly stepping the simulation using step_simulation(), in other words: set_real_time_simulation(false) After each simulation step, the external forces are cleared to zero. If you are using set_real_time_simulation(true), This method will have undefined behavior (either 0, 1 or multiple force applications).

Arguments

  • body - the BodyId, as returned by load_urdf etc.
  • link_index - link index or None for the base.
  • force_object - force vector to be applied [x,y,z] either as an array, Point3 or Vector3. See flags for coordinate system
  • position_object - position on the link where the force is applied.
  • flags - Specify the coordinate system of force/position: either WORLD_FRAME for Cartesian world coordinates or LINK_FRAME for local link coordinates.

pub fn apply_external_torque<Torque: Into<Vector3<f64>>, Link: Into<Option<usize>>>(
    &mut self,
    body: BodyId,
    link_index: Link,
    torque_object: Torque,
    flags: ExternalForceFrame
)
[src]

Applies a torque to a body.

Note that this method will only work when explicitly stepping the simulation using step_simulation(), in other words: set_real_time_simulation(false) After each simulation step, the external torques are cleared to zero. If you are using set_real_time_simulation(true), This method will have undefined behavior (either 0, 1 or multiple torque applications).

Arguments

  • body - the BodyId, as returned by load_urdf etc.
  • link_index - link index or None for the base.
  • torque_object - torque vector to be applied [x,y,z] either as an array or a Vector3. See flags for coordinate system
  • flags - Specify the coordinate system of torque: either WORLD_FRAME for Cartesian world coordinates or LINK_FRAME for local link coordinates.

pub fn enable_joint_torque_sensor(
    &mut self,
    body: BodyId,
    joint_index: usize,
    enable_sensor: bool
) -> Result<(), Error>
[src]

You can enable or disable a joint force/torque sensor in each joint. Once enabled, if you perform a step_simulation(), the get_joint_state() will report the joint reaction forces in the fixed degrees of freedom: a fixed joint will measure all 6DOF joint forces/torques. A revolute/hinge joint force/torque sensor will measure 5DOF reaction forces along all axis except the hinge axis. The applied force by a joint motor is available in the applied_joint_motor_torque field in JointState if you call get_joint_state().

pub fn create_collision_shape(
    &mut self,
    shape: GeometricCollisionShape,
    frame_offset: Isometry3<f64>
) -> Result<CollisionId, Error>
[src]

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.

Return

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

See also

pub fn create_visual_shape(
    &mut self,
    shape: GeometricVisualShape,
    options: VisualShapeOptions
) -> Result<VisualId, Error>
[src]

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 option to specify, like colors.

Return

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

See also

pub fn create_multi_body(
    &mut self,
    base_collision_shape: CollisionId,
    base_visual_shape: VisualId,
    options: MultiBodyOptions
) -> Result<BodyId, Error>
[src]

You can create a multi body with only a single base without joints/child links or you can create a multi body with joints/child links. If you provide links, make sure the length of every vector is the same .

Arguments

  • base_collision_shape - unique id from create_collision_shape or use CollisionId::NONE if you do not want to have a collision shape. You can re-use the collision shape for multiple multibodies (instancing)
  • base_visual_shape - unique id from create_visual_shape or use VisualId::NONE if you do not want to set a visual shape. You can re-use the visual shape (instancing)
  • options - additional options for creating a multi_body. See MultiBodyOptions for details

Return

returns the BodyId of the newly created body.

Note: Currently, if you use batch_positions you will not get back a list of Id’s, like in PyBullet. Instead you will get the Id of the last body in the batch.

Example

   let sphere_shape = GeometricCollisionShape::Sphere { radius: 0.4 };
   let box_collision = physics_client.create_collision_shape(sphere_shape, Isometry3::identity())?;
   let box_shape = GeometricVisualShape::Box {
       half_extents: Vector3::from_element(0.5),
   };
   let box_visual = physics_client.create_visual_shape(
       box_shape,
       VisualShapeOptions {
           rgba_colors: [0., 1., 0., 1.],
           ..Default::default()
       },
   )?;
   let box_id =
       physics_client.create_multi_body(box_collision, box_visual, MultiBodyOptions::default())?;

pub fn change_visual_shape<Link: Into<Option<usize>>>(
    &mut self,
    body: BodyId,
    link_index: Link,
    options: ChangeVisualShapeOptions
) -> Result<(), Error>
[src]

Use this function to change the texture of a shape, the RGBA color and other properties.

Arguments

Example

In this example we change the color of a shape

   let sphere_shape = GeometricCollisionShape::Sphere { radius: 0.4 };
   let box_collision = physics_client.create_collision_shape(sphere_shape, Isometry3::identity())?;
   let box_shape = GeometricVisualShape::Box {
       half_extents: Vector3::from_element(0.5),
   };
   let box_visual = physics_client.create_visual_shape(
       box_shape,
       VisualShapeOptions {
           rgba_colors: [0., 1., 0., 1.],
           ..Default::default()
       },
   )?;
   let box_id =
       physics_client.create_multi_body(box_collision, box_visual, MultiBodyOptions::default())?;

   let color = physics_client.get_visual_shape_data(box_id,false)?[0].rgba_color;
   assert_eq!(color, [0.,1.,0.,1.]);

   physics_client.change_visual_shape(
       box_id,
       None,
       ChangeVisualShapeOptions {
           rgba_color: Some([1., 0., 0., 1.]),
           ..Default::default()
       },
   )?;

   let color = physics_client.get_visual_shape_data(box_id,false)?[0].rgba_color;
   assert_eq!(color, [1.,0.,0.,1.]);

pub fn get_visual_shape_data(
    &mut self,
    body: BodyId,
    request_texture_id: bool
) -> Result<Vec<VisualShapeData>, Error>
[src]

Returns a list of visual shape data of a body. See change_visual_shape() for an example.

pub fn load_texture<File: AsRef<Path>>(
    &mut self,
    file: File
) -> Result<TextureId, Error>
[src]

Load a texture from file and return a non-negative texture unique id if the loading succeeds. This unique id can be used with change_visual_shape.

See create_multi_body_batch.rs for an example

pub fn remove_body(&mut self, body: BodyId)[src]

will remove a body by its body unique id

pub fn get_body_info(&mut self, body: BodyId) -> Result<BodyInfo, Error>[src]

gets the BodyInfo (base name and body name) of a body

pub fn get_num_bodies(&mut self) -> usize[src]

returns the total number of bodies in the physics server

Trait Implementations

impl Drop for PhysicsClient[src]

Auto Trait Implementations

Blanket Implementations

impl<T> Any for T where
    T: 'static + ?Sized
[src]

impl<T> Borrow<T> for T where
    T: ?Sized
[src]

impl<T> BorrowMut<T> for T where
    T: ?Sized
[src]

impl<T> From<T> for T[src]

impl<T, U> Into<U> for T where
    U: From<T>, 
[src]

impl<T> Pointable for T

type Init = T

The type for initializers.

impl<T> Same<T> for T

type Output = T

Should always be Self

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

impl<T, U> TryFrom<U> for T where
    U: Into<T>, 
[src]

type Error = Infallible

The type returned in the event of a conversion error.

impl<T, U> TryInto<U> for T where
    U: TryFrom<T>, 
[src]

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

The type returned in the event of a conversion error.

impl<V, T> VZip<V> for T where
    V: MultiLane<T>,