Struct rubullet::PhysicsClient [−][src]
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
There are also other modes for more advanced use cases. However, these were not heavily tested, so be careful when you use them.
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]
&mut self,
path: P
) -> Result<(), Error>
Sets an additional search path for loading assets.
pub fn set_gravity<GravityVector: Into<Vector3<f64>>>(
&mut self,
gravity: GravityVector
)
[src]
&mut self,
gravity: GravityVector
)
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]
&mut self,
file: P,
options: Options
) -> Result<BodyId, Error>
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_scaling
anduse_maximal_coordinates
for loading the URDF-file. SeeUrdfOptions
.
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]
&mut self,
file: P,
options: Options
) -> Result<Vec<BodyId>, Error>
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_scaling
anduse_maximal_coordinates
for loading the SDF-file. SeeSdfOptions
.
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]
&mut self,
file: P,
flags: Flags
) -> Result<Vec<BodyId>, Error>
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]
&mut self,
body: BodyId
) -> Result<Isometry3<f64>, Error>
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
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]
&mut self,
body: BodyId,
linear_velocity: Linear,
angular_velocity: Angular
)
Reset the linear and/or angular velocity of the base of a body
Arguments
body
- theBodyId
, as returned byload_urdf
etc.linear_velocity
- either a [f64;3] or a Vector3 which contains the desired linear velocity (x,y,z) in Cartesian world coordinates orNone
to not change the linear velocityangular_velocity
- either a [f64;3] or a Vector3 which contains the desired angular velocity (wx,wy,wz) in Cartesian world coordinates orNone
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(()) }
pub fn get_link_state(
&mut self,
body: BodyId,
link_index: usize,
compute_link_velocity: bool,
compute_forward_kinematics: bool
) -> Result<LinkState, Error>
[src]
&mut self,
body: BodyId,
link_index: usize,
compute_link_velocity: bool,
compute_forward_kinematics: bool
) -> Result<LinkState, Error>
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
- theBodyId
, as returned byload_urdf
etc.link_index
- link indexcompute_link_velocity
- will compute the link velocity and put it into theLinkState
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
LinkState
for more information about different types of link framesget_link_states()
to get multiple link states
pub fn get_link_states(
&mut self,
body: BodyId,
link_indices: &[usize],
compute_link_velocity: bool,
compute_forward_kinematics: bool
) -> Result<Vec<LinkState>, Error>
[src]
&mut self,
body: BodyId,
link_indices: &[usize],
compute_link_velocity: bool,
compute_forward_kinematics: bool
) -> Result<Vec<LinkState>, Error>
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
- theBodyId
, as returned byload_urdf
etc.link_indices
- link indicescompute_link_velocity
- will compute the link velocity and put it into theLinkState
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
LinkState
for more information about different types of link framesget_link_state()
to get only a single link state
pub fn change_dynamics<Link: Into<Option<usize>>>(
&mut self,
body: BodyId,
link_index: Link,
options: ChangeDynamicsOptions
)
[src]
&mut self,
body: BodyId,
link_index: Link,
options: ChangeDynamicsOptions
)
You can change the properties such as mass, friction and restitution coefficients using this method.
Arguments
body
- theBodyId
, as returned byload_urdf
etc.link_index
- link index orNone
for the base. Note that not all options require a link index. In those cases where you only want to set these kind of parameters you can just set the link_index toNone
.- options - Various options to the change the dynamics.
Example
let cube_id = physics_client.load_urdf( "cube_small.urdf", UrdfOptions { base_transform: Isometry3::translation(0., 0., 1.), ..Default::default() }, )?; physics_client.change_dynamics( cube_id, None, ChangeDynamicsOptions { mass: Some(38.), lateral_friction: Some(0.1), ..Default::default() }, ); let dynamics_info = physics_client.get_dynamics_info(cube_id, None)?; println!("{:?}", dynamics_info); assert!((dynamics_info.mass - 38.).abs() < 1e-7); assert!((dynamics_info.lateral_friction - 0.1).abs() < 1e-7);
pub fn get_dynamics_info<Link: Into<Option<usize>>>(
&mut self,
body: BodyId,
link_index: Link
) -> Result<DynamicsInfo, Error>
[src]
&mut self,
body: BodyId,
link_index: Link
) -> Result<DynamicsInfo, Error>
With this method you can get information about the mass, center of mass, friction and other properties of the base and links.
Arguments
See change_dynamics
for an example
pub fn get_num_joints(&mut self, body: BodyId) -> usize
[src]
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
body
- theBodyId
, as returned byload_urdf
etc.joint_index
- an index in the range [0..get_num_joints(body)
]
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]
&mut self,
body: BodyId,
joint_index: usize,
value: f64,
velocity: Velocity
) -> Result<(), Error>
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
- theBodyId
, as returned byload_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]
&mut self,
body: BodyId,
joint_index: usize
) -> Result<JointState, Error>
get information about the joint state such as the joint position, velocity, joint reaction forces and joint motor torque.
Arguments
body
- theBodyId
, as returned byload_urdf
etc.joint_index
- a joint index in the range [0..get_num_joints(body)
]
pub fn get_joint_states(
&mut self,
body: BodyId,
joint_indices: &[usize]
) -> Result<Vec<JointState>, Error>
[src]
&mut self,
body: BodyId,
joint_indices: &[usize]
) -> Result<Vec<JointState>, Error>
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
body
- theBodyId
, as returned byload_urdf
etc.joint_indices
- a list of joint indices which each index in the range [0..get_num_joints(body)
]
pub fn calculate_mass_matrix(
&mut self,
body: BodyId,
object_positions: &[f64]
) -> Result<DMatrix<f64>, Error>
[src]
&mut self,
body: BodyId,
object_positions: &[f64]
) -> Result<DMatrix<f64>, Error>
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
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]
&mut self,
body: BodyId,
params: InverseKinematicsParameters<'_>
) -> Result<Vec<f64>, Error>
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]
&mut self,
body: BodyId,
object_positions: &[f64],
object_velocities: &[f64],
object_accelerations: &[f64]
) -> Result<Vec<f64>, Error>
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
- theBodyId
, as returned byload_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 with
use rubullet::ChangeDynamicsOptions; ChangeDynamicsOptions { joint_damping: Some(0.), linear_damping: Some(0.), angular_damping: Some(0.), ..Default::default() };
See also the inverse_dynamics
example in the example folder.
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]
&mut self,
body: BodyId,
link_index: usize,
local_position: LocalPosition,
object_positions: &[f64],
object_velocities: &[f64],
object_accelerations: &[f64]
) -> Result<Jacobian, Error>
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
- theBodyId
, as returned byload_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 velocitiesobject_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]
&mut self,
body: BodyId,
joint_index: usize,
control_mode: ControlMode,
maximum_force: Option<f64>
)
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
- theBodyId
, as returned byload_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]
&mut self,
body: BodyId,
joint_indices: &[usize],
control_mode: ControlModeArray<'_>,
maximum_force: Option<&[f64]>
) -> Result<(), Error>
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
- theBodyId
, as returned byload_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<Vector: Into<Vector3<f32>>>(
camera_eye_position: Vector,
camera_target_position: Vector,
camera_up_vector: Vector
) -> Matrix4<f32>
[src]
camera_eye_position: Vector,
camera_target_position: Vector,
camera_up_vector: Vector
) -> Matrix4<f32>
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 coordinatescamera_target_position
- position of the target (focus) point, in Cartesian world coordinatescamera_up_vector
- up vector of the camera, in Cartesian world coordinates
Example
use rubullet::PhysicsClient; use nalgebra::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 let eye_position = Vector3::new(1.,1.,1.); let target_position = Vector3::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<Vector: Into<Vector3<f32>>>(
camera_target_position: Vector,
distance: f32,
yaw: f32,
pitch: f32,
roll: f32,
z_axis_is_up: bool
) -> Matrix4<f32>
[src]
camera_target_position: Vector,
distance: f32,
yaw: f32,
pitch: f32,
roll: f32,
z_axis_is_up: bool
) -> Matrix4<f32>
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 coordinatesdistance
- distance from eye to focus pointyaw
- yaw angle in degrees left/right around up-axis.pitch
- pitch in degrees up/down.roll
- roll in degrees around forward vectorz_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::Vector3; // 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 Vector3 let target_position = Vector3::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]
left: f32,
right: f32,
bottom: f32,
top: f32,
near_val: f32,
far_val: f32
) -> Matrix4<f32>
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) coordinateright
- right screen (canvas) coordinatebottom
- bottom screen (canvas) coordinatetop
- top screen (canvas) coordinatenear
- near plane distancefar
- far plane distance
See also
pub fn compute_projection_matrix_fov(
fov: f32,
aspect: f32,
near_val: f32,
far_val: f32
) -> Matrix4<f32>
[src]
fov: f32,
aspect: f32,
near_val: f32,
far_val: f32
) -> Matrix4<f32>
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) coordinateaspect
- right screen (canvas) coordinatenear_val
- near plane distancefar_val
- far plane distance
See also
pub fn get_camera_image<Options: Into<Option<CameraImageOptions>>>(
&mut self,
width: usize,
height: usize,
options: Options
) -> Result<Images, Error>
[src]
&mut self,
width: usize,
height: usize,
options: Options
) -> Result<Images, Error>
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 coordinatesheight
- position of the target (focus) point, in Cartesian world coordinatesoptions
- additional options to set view and projection matrix etc.
See also
- compute_view_matrix
- compute_view_matrix_from_yaw_pitch_roll
- compute_projection_matrix
- compute_projection_matrix_fov
- panda_camera_demo.rs for an example
pub fn configure_debug_visualizer(
&mut self,
flag: DebugVisualizerFlag,
enable: bool
)
[src]
&mut self,
flag: DebugVisualizerFlag,
enable: bool
)
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 disableenable
- enables or disables the feature
pub fn add_user_debug_line<Options: Into<Option<AddDebugLineOptions>>, Start: Into<Vector3<f64>>, End: Into<Vector3<f64>>>(
&mut self,
line_from_xyz: Start,
line_to_xyz: End,
options: Options
) -> Result<ItemId, Error>
[src]
&mut self,
line_from_xyz: Start,
line_to_xyz: End,
options: Options
) -> Result<ItemId, Error>
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 Vector3.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 Vector3.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], Vector3::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]
&mut self,
param_name: Text,
range_min: f64,
range_max: f64,
start_value: f64
) -> Result<ItemId, Error>
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 sliderstart_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<Vector3<f64>>, Options: Into<Option<AddDebugTextOptions>>>(
&mut self,
text: Text,
text_position: Position,
options: Options
) -> Result<ItemId, Error>
[src]
&mut self,
text: Text,
text_position: Position,
options: Options
) -> Result<ItemId, Error>
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 &strtext_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 Vector3.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", Vector3::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", Vector3::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]
&mut self,
body: BodyId,
link_index: Link,
object_debug_color: Color
)
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
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<Vector3<f64>>, Link: Into<Option<usize>>>(
&mut self,
body: BodyId,
link_index: Link,
force_object: Force,
position_object: Position,
flags: ExternalForceFrame
)
[src]
&mut self,
body: BodyId,
link_index: Link,
force_object: Force,
position_object: Position,
flags: ExternalForceFrame
)
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
- theBodyId
, as returned byload_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 systemposition_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]
&mut self,
body: BodyId,
link_index: Link,
torque_object: Torque,
flags: ExternalForceFrame
)
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
- theBodyId
, as returned byload_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 systemflags
- 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]
&mut self,
body: BodyId,
joint_index: usize,
enable_sensor: bool
) -> Result<(), Error>
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]
&mut self,
shape: GeometricCollisionShape,
frame_offset: Isometry3<f64>
) -> Result<CollisionId, Error>
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.
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]
&mut self,
shape: GeometricVisualShape,
options: VisualShapeOptions
) -> Result<VisualId, Error>
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 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]
&mut self,
base_collision_shape: CollisionId,
base_visual_shape: VisualId,
options: MultiBodyOptions
) -> Result<BodyId, Error>
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 useCollisionId::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 useVisualId::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 create_multi_body_batch(
&mut self,
base_collision_shape: CollisionId,
base_visual_shape: VisualId,
batch_positions: &[Vector3<f64>],
options: MultiBodyOptions
) -> Result<Vec<BodyId>, Error>
[src]
&mut self,
base_collision_shape: CollisionId,
base_visual_shape: VisualId,
batch_positions: &[Vector3<f64>],
options: MultiBodyOptions
) -> Result<Vec<BodyId>, Error>
like create_multi_body
but creates multiple instances of this
object.
Arguments
base_collision_shape
- unique id from create_collision_shape or useCollisionId::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 useVisualId::NONE
if you do not want to set a visual shape. You can re-use the visual shape (instancing)batch_positions
- list of base positions for the new multibodies.options
- additional options for creating a multi_body. See MultiBodyOptions for details
Return
returns a list of BodyId’s of the newly created bodies.
See create_multi_body_batch.rs
for an example.
pub fn change_visual_shape<Link: Into<Option<usize>>>(
&mut self,
body: BodyId,
link_index: Link,
options: ChangeVisualShapeOptions
) -> Result<(), Error>
[src]
&mut self,
body: BodyId,
link_index: Link,
options: ChangeVisualShapeOptions
) -> Result<(), Error>
Use this function to change the texture of a shape, the RGBA color and other properties.
Arguments
body
- theBodyId
, as returned byload_urdf
etc.link_index
- link index or None for the base.options
- optional parameters to change the visual shape. See ChangeVisualShapeOptions
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]
&mut self,
body: BodyId,
request_texture_id: bool
) -> Result<Vec<VisualShapeData>, Error>
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]
&mut self,
file: File
) -> Result<TextureId, Error>
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
pub fn create_constraint<ChildBody: Into<Option<BodyId>>, ParentLink: Into<Option<usize>>, ChildLink: Into<Option<usize>>, JointAxisVector: Into<Vector3<f64>>>(
&mut self,
parent_body: BodyId,
parent_link_index: ParentLink,
child_body: ChildBody,
child_link_index: ChildLink,
joint_type: JointType,
joint_axis: JointAxisVector,
parent_frame_pose: Isometry3<f64>,
child_frame_pose: Isometry3<f64>
) -> Result<ConstraintId, Error>
[src]
&mut self,
parent_body: BodyId,
parent_link_index: ParentLink,
child_body: ChildBody,
child_link_index: ChildLink,
joint_type: JointType,
joint_axis: JointAxisVector,
parent_frame_pose: Isometry3<f64>,
child_frame_pose: Isometry3<f64>
) -> Result<ConstraintId, Error>
URDF, SDF and MJCF specify articulated bodies as a tree-structures without loops. Thhis method allows you to connect specific links of bodies to close those loops. In addition, you can create arbitrary constraints between objects, and between an object and a specific world frame.
It can also be used to control the motion of physics objects, driven by animated frames, such as a VR controller. It is better to use constraints, instead of setting the position or velocity directly for such purpose, since those constraints are solved together with other dynamics constraints.
Arguments
parent_body
- parent body unique idparent_link_index
- parent link index (orNone
for the base)child_body
- child body unique id, orNone
for no body (specify a non-dynamic child frame in world coordinates)child_link_index
- child link index (orNone
for the base)joint_type
- aJointType
for the constraintjoint_axis
- joint axis in child link frame. Must be something that can be converted into a Vector3parent_frame_pose
- pose of the joint frame relative to parent center of mass frame.child_frame_pose
- pose of the joint frame relative to a given child center of mass frame (or world origin if no child specified)
Example
let cube_id = physics_client.load_urdf( "cube_small.urdf", UrdfOptions { base_transform: Isometry3::translation(0., 0., 1.), ..Default::default() }, )?; physics_client.set_gravity([0., 0., -10.]); physics_client.set_real_time_simulation(true); let cid = physics_client.create_constraint( cube_id, None, None, None, JointType::Fixed, [0.; 3], Isometry3::identity(), Isometry3::translation(0., 0., 1.), )?; println!("{:?}", cid); println!("{:?}", physics_client.get_constraint(0)?); assert_eq!(1, physics_client.get_num_constraints()); let constraint_info = physics_client.get_constraint_info(cid)?; println!("{:?}", constraint_info); let mut a = -PI; loop { a += 0.05; if a > PI { break; } std::thread::sleep(Duration::from_secs_f64(0.01)); let change_constraint_options = ChangeConstraintOptions { joint_child_pivot: Some(Vector3::new(a, 0., 1.)), joint_child_frame_orientation: Some(UnitQuaternion::from_euler_angles(a, 0., 0.)), max_force: Some(50.), ..Default::default() }; physics_client.change_constraint(cid, change_constraint_options); let constraint_info = physics_client.get_constraint_info(cid)?; assert!((constraint_info.joint_child_frame_pose.translation.x - a).abs() < 1e-7); assert!( (constraint_info .joint_child_frame_pose .rotation .euler_angles() .0 - a) .abs() < 1e-7 ); } let constraint_state = physics_client.get_constraint_state(cid)?; println!("{}", constraint_state); physics_client.remove_constraint(cid); assert_eq!(0, physics_client.get_num_constraints());
pub fn change_constraint(
&mut self,
constraint: ConstraintId,
options: ChangeConstraintOptions
)
[src]
&mut self,
constraint: ConstraintId,
options: ChangeConstraintOptions
)
Allows you to change parameters of an existing constraint.
See create_constraint
for an example.
pub fn remove_constraint(&mut self, constraint: ConstraintId)
[src]
removes a constraint
See create_constraint
for an example.
pub fn get_num_constraints(&mut self) -> usize
[src]
You can query for the total number of constraints, created using
create_constraint
See create_constraint
for an example.
pub fn get_constraint(
&mut self,
serial_index: usize
) -> Result<ConstraintId, Error>
[src]
&mut self,
serial_index: usize
) -> Result<ConstraintId, Error>
will take a serial index in range 0..get_num_constraints
,
and reports the constraint unique id.
Note that the constraint unique ids may not be contiguous, since you may remove constraints.
See create_constraint
for an example.
pub fn get_constraint_info(
&mut self,
constraint: ConstraintId
) -> Result<ConstraintInfo, Error>
[src]
&mut self,
constraint: ConstraintId
) -> Result<ConstraintInfo, Error>
Get the user-created constraint info, given a ConstraintId.
See create_constraint
for an example.
pub fn get_constraint_state(
&mut self,
constraint: ConstraintId
) -> Result<DVector<f64>, Error>
[src]
&mut self,
constraint: ConstraintId
) -> Result<DVector<f64>, Error>
Give a constraint unique id, you can query for the applied constraint forces in the most
recent simulation step. The input is a constraint unique id and the output is a vector of
constraint forces, its dimension is the degrees of freedom that are affected by the
constraint (a fixed constraint affects 6 DoF for example).
See create_constraint
for an example.
pub fn get_aabb<Link: Into<Option<usize>>>(
&mut self,
body: BodyId,
link_index: Link
) -> Result<Aabb, Error>
[src]
&mut self,
body: BodyId,
link_index: Link
) -> Result<Aabb, Error>
queriers the axis aligned bounding box (in world space) given an object unique id,
and optionally a link index. (when you pass None
, you get the AABB of the base).
Arguments
Example
let r2d2 = physics_client.load_urdf("r2d2.urdf", None)?; let aabb = physics_client.get_aabb(r2d2, None)?; println!("{:?}", aabb);
See also the get_aabb.rs example in the example folder
pub fn get_overlapping_objects(&mut self, aabb: Aabb) -> Vec<OverlappingObject>
[src]
This query will return all the unique ids of objects that have axis aligned bounding box overlap with a given axis aligned bounding box. Note that the query is conservative and may return additional objects that don’t have actual AABB overlap. This happens because the acceleration structures have some heuristic that enlarges the AABBs a bit (extra margin and extruded along the velocity vector).
Example
physics_client.load_urdf("plane.urdf", None)?; let cube_id = physics_client.load_urdf( "cube_small.urdf", UrdfOptions { base_transform: Isometry3::translation(0., 0., 0.5), ..Default::default() }, )?; let overlapping_object = physics_client.get_overlapping_objects(Aabb{ min: [-1.;3].into(), max:[1.;3].into(), }); assert_eq!(2,overlapping_object.len());
pub fn get_contact_points<BodyA: Into<Option<BodyId>>, BodyB: Into<Option<BodyId>>>(
&mut self,
body_a: BodyA,
body_b: BodyB,
link_a: Option<Option<usize>>,
link_b: Option<Option<usize>>
) -> Result<Vec<ContactPoint>, Error>
[src]
&mut self,
body_a: BodyA,
body_b: BodyB,
link_a: Option<Option<usize>>,
link_b: Option<Option<usize>>
) -> Result<Vec<ContactPoint>, Error>
The getContactPoints API returns the contact points computed during the most recent call to
step_simulation
. Note that if you change the state of the
simulation after step_simulation
,
the ‘get_contact_points()’ is not updated and potentially invalid
Arguments
body_a
- only report contact points that involve body Abody_b
- only report contact points that involve body B. Important: you need to have a body A if you provide body B.link_a
- Only report contact points that involve link_index_a of body_a. See note on usage of this option.link_b
- Only report contact points that involve link_index_b of body_b. See note on usage of this option.
Note on usage of the link_indices:
You can either provide:
None
- if you want to have all the links.Some(None)
- if you want to specify the Base linkSome(Some(2))
- if you want to specify link2
.
Example
let mut physics_client = PhysicsClient::connect(Mode::Direct)?; physics_client.set_additional_search_path("../rubullet-sys/bullet3/libbullet3/data")?; physics_client.load_urdf("plane.urdf", None)?; let _cube_a = physics_client.load_urdf( "cube_small.urdf", UrdfOptions { base_transform: Isometry3::translation(0., 0., 1.), ..Default::default() }, )?; let _cube_b = physics_client.load_urdf( "cube_small.urdf", UrdfOptions { base_transform: Isometry3::translation(0., 0., 0.), ..Default::default() }, )?; physics_client.step_simulation()?; let points = physics_client.get_contact_points(None, None, None, None)?; assert_eq!(4, points.len());
See also the contact_friction.rs
example in the example folder.
pub fn get_closest_points_body_body<LinkA: Into<Option<usize>>, LinkB: Into<Option<usize>>>(
&mut self,
body_a: BodyId,
link_index_a: LinkA,
body_b: BodyId,
link_index_b: LinkB,
distance: f64
) -> Result<Vec<ContactPoint>, Error>
[src]
&mut self,
body_a: BodyId,
link_index_a: LinkA,
body_b: BodyId,
link_index_b: LinkB,
distance: f64
) -> Result<Vec<ContactPoint>, Error>
Computes contact points independent from step_simulation
.
It also lets you compute closest points of objects with an arbitrary separating distance.
In this query there will be no normal forces reported.
There are 3 variants of this method:
get_closest_points_body_body
- calculates the closest points between two bodies.get_closest_points_body_shape
- calculates the closest points between a body and a collision shapeget_closest_points_shape_shape
- calculates the closest points between two collision shapes
Arguments
body_a
- BodyId for the first objectlink_index_a
- link index for object A orNone
for the base.body_b
- BodyId for the second objectlink_index_b
- link index for object B orNone
for the base.distance
- If the distance between objects exceeds this maximum distance, no points may be returned.
Example
let cube_a = physics_client.load_urdf("cube_small.urdf", None)?; let cube_b = physics_client.load_urdf( "cube_small.urdf", UrdfOptions { base_transform: Isometry3::translation(0., 0., 0.5), ..Default::default() }, )?; let points = physics_client.get_closest_points_body_body(cube_a, None, cube_b, None, 1.)?; assert!((points[0].contact_distance - 0.45).abs() < 1e-5); assert_eq!(points[0].body_a, Some(cube_a)); assert_eq!(points[0].body_b, Some(cube_b)); assert_eq!(points[0].link_index_a, None); assert_eq!(points[0].link_index_b, None); assert!((points[0].position_on_a.z - 0.025).abs() < 1e-5); assert!((points[0].position_on_b.z - 0.475).abs() < 1e-5);
See also
get_closest_points.rs
in the example for folder for an other exampleget_closest_points_body_shape
get_closest_points_shape_shape
pub fn get_closest_points_body_shape<Link: Into<Option<usize>>>(
&mut self,
body: BodyId,
link_index: Link,
collision_shape: CollisionId,
shape_pose: Isometry3<f64>,
distance: f64
) -> Result<Vec<ContactPoint>, Error>
[src]
&mut self,
body: BodyId,
link_index: Link,
collision_shape: CollisionId,
shape_pose: Isometry3<f64>,
distance: f64
) -> Result<Vec<ContactPoint>, Error>
Computes contact points independent from step_simulation
.
It also lets you compute closest points of objects with an arbitrary separating distance.
In this query there will be no normal forces reported.
There are 3 variants of this method:
get_closest_points_body_body
- calculates the closest points between two bodies.get_closest_points_body_shape
- calculates the closest points between a body and a collision shapeget_closest_points_shape_shape
- calculates the closest points between two collision shapes
Arguments
body
- BodyId for the body objectlink_index
- link index for object A orNone
for the base.collision_shape
- Collision shape of the other objectshape_pose
- pose of the collision shape in world coordinates.distance
- If the distance between objects exceeds this maximum distance, no points may be returned.
See also
get_closest_points.rs
in the example for folder for an exampleget_closest_points_body_body
get_closest_points_shape_shape
pub fn get_closest_points_shape_shape(
&mut self,
collision_shape_a: CollisionId,
shape_pose_a: Isometry3<f64>,
collision_shape_b: CollisionId,
shape_pose_b: Isometry3<f64>,
distance: f64
) -> Result<Vec<ContactPoint>, Error>
[src]
&mut self,
collision_shape_a: CollisionId,
shape_pose_a: Isometry3<f64>,
collision_shape_b: CollisionId,
shape_pose_b: Isometry3<f64>,
distance: f64
) -> Result<Vec<ContactPoint>, Error>
Computes contact points independent from step_simulation
.
It also lets you compute closest points of objects with an arbitrary separating distance.
In this query there will be no normal forces reported.
There are 3 variants of this method:
get_closest_points_body_body
- calculates the closest points between two bodies.get_closest_points_body_shape
- calculates the closest points between a body and a collision shapeget_closest_points_shape_shape
- calculates the closest points between two collision shapes
Arguments
collision_shape_a
- CollisionId of the first shapeshape_pose_a
- pose of the first collision shape in world coordinates.collision_shape_b
- CollisionId of the second shapeshape_pose_b
- pose of the second collision shape in world coordinates.distance
- If the distance between objects exceeds this maximum distance, no points may be returned.
See also
get_closest_points.rs
in the example for folder for an exampleget_closest_points_body_shape
get_closest_points_body_body
pub fn start_state_logging<P: AsRef<Path>, Options: Into<Option<StateLoggingOptions>>>(
&mut self,
logging_type: LoggingType,
file: P,
options: Options
) -> Result<LogId, Error>
[src]
&mut self,
logging_type: LoggingType,
file: P,
options: Options
) -> Result<LogId, Error>
State logging lets you log the state of the simulation, such as the state of one or more
objects after each simulation step (after each call to stepSimulation or automatically after
each simulation step when set_real_time_simulation
is enabled).
This allows you to record
trajectories of objects. There is also the option to log the common state of bodies such as
base position and orientation, joint positions (angles) and joint motor forces.
All log files generated using this method can be read using Rust, C++ or Python scripts.
Arguments
logging_type
- select one of different modes for loggingfile
- a file in which the logging data will be saved.options
- define various logging options.
Examples
dump_log.rs
- a tool which prints the content of a log file.kuka_with_cube.rs
- records the state of a generic robot.kuka_with_cube_playback.rs
- reads the log file generated bykuka_with_cube.rs
and replays the joint states.log_minitaur.rs
- logs the state of a minatur robot.profile_timing.rs
- an example which shows how to profile your function with thesubmit_profile_timing
method.
let log_id = physics_client.start_state_logging( LoggingType::GenericRobot, "LOG0001.txt", None, )?;
pub fn stop_state_logging(&mut self, log: LogId)
[src]
Stops a logger. If you use a ProfileTimings
logger, you need to call this method at the end. Otherwise, your data will not be saved to the
file.
Arguments
log
-LogId
as returned bystart_state_logging
pub fn submit_profile_timing<'a, EventName: Into<Option<&'a str>>>(
&mut self,
event_name: EventName
)
[src]
&mut self,
event_name: EventName
)
submit_profile_timing allows to insert start and stop timings to profile Rust code.
RuBullet and Bullet have instrumented many functions so you can see where the time is spend.
You can dump those profile timings in a file, that can be viewed with Google Chrome
in the about://tracing
window using the LOAD feature. In the GUI,
you can press ‘p’ to start/stop the profile dump. In some cases you may want to
instrument the timings of your client code.
Arguments
event_name
- Give the timing a name or useNone
to specify the end of the timing.
Usage
To use this function you need to create a logger with start_state_logging
with ProfileTimings
as LoggingType
You can start a timing by calling
client.submit_profile_timing("my_timing");
This will start a timing called my_timing0
. The “0” is a running index which get s increased for every new timing.
calling client.submit_profile_timing("my_timing");
again will start a timing called my_timing1
.
The timing are put onto stacked and are being stopped by calling client.submit_profile_timing(None);
.
Calling it the first time will stop my_timing1
. And the second calling it a second time will
stop my_timing0
.
At the end call the stop_state_logging
method to write
the profiling data into the log file. Open about://tracing
or chrome://tracing
in Chrome or
Chromium to view your data.
Example
from the profile_timing.rs
example:
use anyhow::Result; use rubullet::*; use std::time::{Duration, Instant}; fn main() -> Result<()> { let mut physics_client = PhysicsClient::connect(Mode::Gui)?; let t = Instant::now() + Duration::from_secs_f64(3.1); let log_id = physics_client.start_state_logging( LoggingType::ProfileTimings, "chrome_about_tracing.json", None, )?; while Instant::now() < t { physics_client.step_simulation()?; physics_client.submit_profile_timing("rusttest"); std::thread::sleep(Duration::from_secs_f64(1. / 240.)); physics_client.submit_profile_timing("nested"); for _ in 0..100 { physics_client.submit_profile_timing("deep_nested"); physics_client.submit_profile_timing(None); } std::thread::sleep(Duration::from_millis(1)); physics_client.submit_profile_timing(None); physics_client.submit_profile_timing(None); } physics_client.stop_state_logging(log_id); Ok(()) }
pub fn save_world<P: AsRef<Path>>(&mut self, filename: P) -> Result<(), Error>
[src]
You can create an approximate snapshot of the current world as a PyBullet Python file (Yes, a Python file and not a Rust file), stored on the server. save_world can be useful as a basic editing feature, setting up the robot, joint angles, object positions and environment for example in VR. Later you can just load the PyBullet Python file to re-create the world. You could also use it to create a Python version of your awesome world to show it to your friends who are not using RuBullet yet! The python snapshot contains loadURDF commands together with initialization of joint angles and object transforms. Note that not all settings are stored in the world file.
Arguments
filename
- location where to save the python file.
Example
physics_client.load_urdf("plane.urdf", None)?; let cube_a = physics_client.load_urdf("cube_small.urdf", None)?; let cube_b = physics_client.load_urdf( "cube_small.urdf", UrdfOptions { base_transform: Isometry3::translation(0., 0., 0.5), ..Default::default() }, )?; let points = physics_client.save_world("my_world.py")?;
pub fn load_bullet<P: AsRef<Path>>(
&mut self,
bullet_filename: P
) -> Result<Vec<BodyId>, Error>
[src]
&mut self,
bullet_filename: P
) -> Result<Vec<BodyId>, Error>
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.
pub fn save_bullet<P: AsRef<Path>>(
&mut self,
bullet_filename: P
) -> Result<(), Error>
[src]
&mut self,
bullet_filename: P
) -> Result<(), Error>
Saves all bodies and the current state into a .bullet
file which can then be read by
load_bullet
or restore_state_from_file
.
Example
physics_client.load_urdf("plane.urdf", None)?; let cube_a = physics_client.load_urdf("cube_small.urdf", None)?; let cube_b = physics_client.load_urdf( "cube_small.urdf", UrdfOptions { base_transform: Isometry3::translation(0., 0., 0.5), ..Default::default() }, )?; physics_client.step_simulation()?; physics_client.save_bullet("cubes.bullet")?;
See also save_and_restore.rs
example.
pub fn restore_state(&mut self, state: StateId) -> Result<(), Error>
[src]
restores a state from memory using a state id which was created with save_state
.
See save_and_restore.rs
example.
pub fn restore_state_from_file<P: AsRef<Path>>(
&mut self,
filename: P
) -> Result<(), Error>
[src]
&mut self,
filename: P
) -> Result<(), Error>
restores a state from a .bullet
file. It is necessary that the correct bodies are already
loaded. If this is not the case use load_bullet
instead.
See save_and_restore.rs
example.
pub fn save_state(&mut self) -> Result<StateId, Error>
[src]
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.
pub fn remove_state(&mut self, state: StateId)
[src]
Removes a state from memory.
pub fn set_physics_engine_parameter(
&mut self,
options: SetPhysicsEngineParameterOptions
)
[src]
&mut self,
options: SetPhysicsEngineParameterOptions
)
Set some internal physics engine parameter, such as cfm or erp etc.
pub fn get_physics_engine_parameters(
&mut self
) -> Result<PhysicsEngineParameters, Error>
[src]
&mut self
) -> Result<PhysicsEngineParameters, Error>
Get the current values of internal physics engine parameter.
Warning
Some of the parameters are always returning the same value even when you change them using
set_physics_engine_parameter
. These parameters are:
- constraint_solver_type
- minimum_solver_island_size
- report_solver_analytics
- warm_starting_factor
- sparse_sdf_voxel_size
pub fn get_debug_visualizer_camera(&mut self) -> DebugVisualizerCameraInfo
[src]
You can get the width and height (in pixels) of the camera, its view and projection matrix
and more information using this command.
Can be useful to calculate rays. See add_planar_reflection.rs
example.
pub fn reset_debug_visualizer_camera<Vector: Into<Vector3<f32>>>(
&mut self,
camera_distance: f32,
camera_yaw: f32,
camera_pitch: f32,
camera_target_position: Vector
)
[src]
&mut self,
camera_distance: f32,
camera_yaw: f32,
camera_pitch: f32,
camera_target_position: Vector
)
You can reset the 3D OpenGL debug visualizer camera distance (between eye and camera target position), camera yaw and pitch and camera target position
Arguments
camera_distance
- distance from eye to camera target positioncamera_yaw
- camera yaw angle (in degrees) left/rightcamera_pitch
- camera pitch angle (in degrees) up/downcamera_target_position
- this is the camera focus point
pub fn ray_test<RayFrom: Into<Vector3<f64>>, RayTo: Into<Vector3<f64>>, Options: Into<Option<RayTestOptions>>>(
&mut self,
ray_from_position: RayFrom,
ray_to_position: RayTo,
options: Options
) -> Result<Option<RayHitInfo>, Error>
[src]
&mut self,
ray_from_position: RayFrom,
ray_to_position: RayTo,
options: Options
) -> Result<Option<RayHitInfo>, Error>
You can perform a single raycast to find the intersection information of the first object hit.
Arguments
ray_from_position
- start of the ray in world coordinatesray_to_position
- end of the ray in world coordinatesoptions
- additional options. SeeRayTestOptions
Return
Either None
, which means that there was no object hit or a RayHitInfo
which contains all necessary information about the hit target.
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_small.urdf", None)?; let hit_info = physics_client.ray_test([-1.; 3], [1.; 3], None)?.unwrap(); assert_eq!(hit_info.body_id, cube); assert!(physics_client.ray_test([2.; 3], [1.; 3], None)?.is_none()); Ok(()) }
See add_planar_reflection.rs
for a more complex example.
pub fn ray_test_batch<Options: Into<Option<RayTestBatchOptions>>>(
&mut self,
ray_from_positions: &[Vector3<f64>],
ray_to_positions: &[Vector3<f64>],
options: Options
) -> Result<Vec<Option<RayHitInfo>>, Error>
[src]
&mut self,
ray_from_positions: &[Vector3<f64>],
ray_to_positions: &[Vector3<f64>],
options: Options
) -> Result<Vec<Option<RayHitInfo>>, Error>
This is similar to the ray_test
, but allows you to provide an array
of rays, for faster execution. The size of ‘ray_from_positions’
needs to be equal to the size of ‘ray_to_positions’.
Arguments
ray_from_positions
- list of start points for each ray, in world coordinatesray_to_positions
- list of end points for each ray in world coordinates
options
- additional options to set the number of threads etc.
Return
A list of OptionNone
when nothing was hit. Otherwise the
you get the RayHitInfo
Example
use anyhow::Result; use nalgebra::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 cube = physics_client.load_urdf("cube_small.urdf", None)?; let from = vec![Vector3::from_element(-1.), Vector3::from_element(2.)]; let to = vec![Vector3::from_element(1.), Vector3::from_element(1.)]; let hit_list = physics_client.ray_test_batch(&from, &to, None)?; assert_eq!(hit_list[0].unwrap().body_id, cube); assert!(hit_list[1].is_none()); Ok(()) }
See batch_ray_cast.rs
for a more complex example.
pub fn set_collision_filter_group_mask<Link: Into<Option<usize>>>(
&mut self,
body: BodyId,
link_index: Link,
collision_filter_group: i32,
collision_filter_mask: i32
)
[src]
&mut self,
body: BodyId,
link_index: Link,
collision_filter_group: i32,
collision_filter_mask: i32
)
Each body is part of a group. It collides with other bodies if their group matches the mask, and vise versa. The following check is performed using the group and mask of the two bodies involved. It depends on the collision filter mode.
Arguments
body
- Id of the body to be configuredlink_index
- link index of the body to be configuredcollision_filter_group
- bitwise group of the filtercollision_filter_mask
- bitwise mask of the filter
See collision_filter.rs
for an example.
pub fn set_collision_filter_pair<LinkA: Into<Option<usize>>, LinkB: Into<Option<usize>>>(
&mut self,
body_a: BodyId,
body_b: BodyId,
link_index_a: LinkA,
link_index_b: LinkB,
enable_collision: bool
)
[src]
&mut self,
body_a: BodyId,
body_b: BodyId,
link_index_a: LinkA,
link_index_b: LinkB,
enable_collision: bool
)
You can have more fine-grain control over collision detection between specific pairs of links. With this method you can enable or disable collision detection. This method will override the filter group/mask and other logic.
Arguments
body_a
- Id of body Bbody_b
- Id of body Blink_index_a
- link index of body Alink_index_b
- link index of body Benable_collision
- enables and disables collision
See collision_filter.rs
for an example.
pub fn load_soft_body<P: AsRef<Path>, Options: Into<Option<SoftBodyOptions>>>(
&mut self,
filename: P,
options: Options
) -> Result<BodyId, Error>
[src]
&mut self,
filename: P,
options: Options
) -> Result<BodyId, Error>
lets you load a deformable object from a VTK or OBJ file.
Arguments
filename
- a relative or absolute path on the file system of the physics serveroptions
- use additional options. SeeSoftBodyOptions
.
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 _bunny = physics_client.load_soft_body("bunny.obj", None)?; Ok(()) }
pub fn create_soft_body_anchor<Body: Into<Option<BodyId>>, Link: Into<Option<usize>>, Vector: Into<Option<Vector3<f64>>>>(
&mut self,
soft_body_id: BodyId,
node_index: usize,
body: Body,
link_index: Link,
body_frame_position: Vector
) -> Result<ConstraintId, Error>
[src]
&mut self,
soft_body_id: BodyId,
node_index: usize,
body: Body,
link_index: Link,
body_frame_position: Vector
) -> Result<ConstraintId, Error>
You can pin vertices of a deformable object to the world, or attach a vertex of a deformable
to a multi body using this method.
It will return a ConstraintId.
You can remove this constraint using the remove_constraint
method.
See deformable_anchor.rs
for an example.
pub fn reset_simulation_with_flags(&mut self, flags: ResetFlags)
[src]
reset_simulation_with_flags does the same as reset_simulation
,
but also lets you add some experimental flags. It can be useful if you want to create a world
with soft body objects.
pub fn is_connected(&mut self) -> bool
[src]
check whether the client is still connected. Most of the time the call blocks instead of returning false, though
pub fn sync_body_info(&mut self) -> Result<(), Error>
[src]
sync_body_info will synchronize the body information (get_body_info) in case of multiple
clients connected to one physics server changing the world
( load_urdf
, remove_body etc).
pub fn disconnect(self)
[src]
closes the PhysicsClient.
pub fn get_body_id(&mut self, index: usize) -> Result<BodyId, Error>
[src]
get a specific body id. The index must be in range [0,get_num_bodies()].
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 plane_id = physics_client.load_urdf("plane.urdf", None)?; assert_eq!(physics_client.get_body_id(0)?, plane_id); Ok(()) }
Trait Implementations
impl Drop for PhysicsClient
[src]
Auto Trait Implementations
impl RefUnwindSafe for PhysicsClient
impl !Send for PhysicsClient
impl !Sync for PhysicsClient
impl Unpin for PhysicsClient
impl UnwindSafe for PhysicsClient
Blanket Implementations
impl<T> Any for T where
T: 'static + ?Sized,
[src]
T: 'static + ?Sized,
impl<T> Borrow<T> for T where
T: ?Sized,
[src]
T: ?Sized,
impl<T> BorrowMut<T> for T where
T: ?Sized,
[src]
T: ?Sized,
pub fn borrow_mut(&mut self) -> &mut T
[src]
impl<T> From<T> for T
[src]
impl<T, U> Into<U> for T where
U: From<T>,
[src]
U: From<T>,
impl<T> Pointable for T
pub const ALIGN: usize
type Init = T
The type for initializers.
pub unsafe fn init(init: <T as Pointable>::Init) -> usize
pub unsafe fn deref<'a>(ptr: usize) -> &'a T
pub unsafe fn deref_mut<'a>(ptr: usize) -> &'a mut T
pub unsafe fn drop(ptr: usize)
impl<T> Same<T> for T
type Output = T
Should always be Self
impl<SS, SP> SupersetOf<SS> for SP where
SS: SubsetOf<SP>,
SS: SubsetOf<SP>,
pub fn to_subset(&self) -> Option<SS>
pub fn is_in_subset(&self) -> bool
pub fn to_subset_unchecked(&self) -> SS
pub fn from_subset(element: &SS) -> SP
impl<T, U> TryFrom<U> for T where
U: Into<T>,
[src]
U: Into<T>,
type Error = Infallible
The type returned in the event of a conversion error.
pub fn try_from(value: U) -> Result<T, <T as TryFrom<U>>::Error>
[src]
impl<T, U> TryInto<U> for T where
U: TryFrom<T>,
[src]
U: TryFrom<T>,
type Error = <U as TryFrom<T>>::Error
The type returned in the event of a conversion error.
pub fn try_into(self) -> Result<U, <U as TryFrom<T>>::Error>
[src]
impl<V, T> VZip<V> for T where
V: MultiLane<T>,
V: MultiLane<T>,