Skip to main content

Configuration

Struct Configuration 

Source
pub struct Configuration(/* private fields */);
Expand description

Configuration of a multi-body system, represented as a vector of joint positions.

Implementations§

Source§

impl Configuration

Source

pub fn zeros(size: usize) -> Configuration

Creates a new Configuration with the given size, initialized to zeros.

§Arguments
  • size - The size of the configuration vector.
§Returns

A new Configuration object with all values set to zero.

Source

pub fn ones(size: usize) -> Configuration

Creates a new Configuration with the given size, initialized to ones.

§Arguments
  • size - The size of the configuration vector.
§Returns

A new Configuration object with all values set to one.

Source

pub fn from_element(size: usize, value: f64) -> Configuration

Creates a new Configuration with the given size, initialized to the specified value.

§Arguments
  • size - The size of the configuration vector.
  • value - The value to initialize each element of the configuration vector.
§Returns

A new Configuration object with all values set to the specified value.

Examples found in repository?
examples/inverse_dynamics.rs (line 13)
3fn main() {
4    let urdf_path = "./examples/descriptions/ur5/ur5_robot.urdf"; // Path to the URDF file
5    let mesh_path = "./examples/descriptions/ur5/"; // Optional mesh path
6
7    // Build models from the URDF file
8    let (model, _coll_model, _viz_model) =
9        build_models_from_urdf(urdf_path, Some(mesh_path)).expect("Failed to parse URDF file");
10
11    // Generate a random configuration, velocity and acceleration
12    let q = random_configuration(&model);
13    let v = Configuration::from_element(model.nv, 1.0);
14    let a = Configuration::from_element(model.nv, 1.0);
15
16    // Create data structure for the model
17    let mut data = model.create_data();
18
19    // Compute inverse dynamics
20    inverse_dynamics(&model, &mut data, &q, &v, &a, None)
21        .expect("Failed to compute inverse dynamics");
22
23    // Print the computed torques
24    println!("Computed torques: {}", data.tau);
25}
More examples
Hide additional examples
examples/forward_dynamics.rs (line 13)
3fn main() {
4    let urdf_path = "./examples/descriptions/ur5/ur5_robot.urdf"; // Path to the URDF file
5    let mesh_path = "./examples/descriptions/ur5/"; // Optional mesh path
6
7    // Build models from the URDF file
8    let (model, _coll_model, _viz_model) =
9        build_models_from_urdf(urdf_path, Some(mesh_path)).expect("Failed to parse URDF file");
10
11    // Generate a random configuration, velocity and acceleration
12    let q = random_configuration(&model);
13    let v = Configuration::from_element(model.nv, 1.0);
14    let tau = Configuration::from_element(model.nv, 1.0);
15
16    // Create data structure for the model
17    let mut data = model.create_data();
18
19    // Compute forward dynamics
20    let ddq = forward_dynamics(&model, &mut data, &q, &v, &tau, None, ABAConvention::Local)
21        .expect("Failed to compute forward dynamics");
22
23    // Print the computed torques
24    println!("Joint accelerations: {}", ddq);
25}
Source

pub fn len(&self) -> usize

Returns the length of the configuration vector.

Source

pub fn is_empty(&self) -> bool

Checks if the configuration vector is empty.

Source

pub fn rows(&self, start: usize, nrows: usize) -> Configuration

Returns a slice of the configuration vector from start to start + nrows - 1 (inclusive).

The returned slice goes from index start to start + nrows - 1, included, and contains nrows elements.

§Arguments
  • start - The starting index of the slice.
  • nrows - The number of rows to include in the slice.
§Returns

A new Configuration object containing the specified slice.

Source

pub fn update_rows( &mut self, start: usize, values: &Configuration, ) -> Result<(), ConfigurationError>

Updates a slice of the configuration vector starting from start with the values from another configuration.

The slice to be updated starts at index start and has the same length as the provided values configuration.

§Arguments
  • start - The starting index of the slice to be updated.
  • values - The configuration containing the new values to be copied.
§Returns
  • Ok(()) if the update was successful.
  • Err(ConfigurationError) if the sizes of the slices do not match.
Source

pub fn from_row_slice(data: &[f64]) -> Configuration

Creates a new Configuration from a slice of scalar values.

§Arguments
  • data - A slice of scalar values.
§Returns

A new Configuration object containing the values from the slice.

Source

pub fn concat(configs: &[Configuration]) -> Configuration

Concatenates multiple Configuration objects into a single configuration.

§Arguments
§Returns

A new Configuration object containing all values from the input configurations.

Source

pub fn random( nq: usize, rng: &mut ThreadRng, min: &Configuration, max: &Configuration, ) -> Configuration

Generates a random Configuration within specified minimum and maximum bounds.

§Arguments
  • nq - The size of the configuration vector.
  • rng - A mutable reference to a random number generator.
  • min - The minimum bounds for each element of the configuration.
  • max - The maximum bounds for each element of the configuration.
§Returns

A new Configuration object with random values within the specified bounds.

Source

pub fn check_size( &self, name: &str, expected_size: usize, ) -> Result<(), ConfigurationError>

Checks if the size of the configuration matches the expected size.

Trait Implementations§

Source§

impl AbsDiffEq for Configuration

Source§

type Epsilon = f64

Used for specifying relative comparisons.
Source§

fn default_epsilon() -> <Configuration as AbsDiffEq>::Epsilon

The default tolerance to use when testing values that are close together. Read more
Source§

fn abs_diff_eq( &self, other: &Configuration, epsilon: <Configuration as AbsDiffEq>::Epsilon, ) -> bool

A test for equality that uses the absolute difference to compute the approximate equality of two numbers.
Source§

fn abs_diff_ne(&self, other: &Rhs, epsilon: Self::Epsilon) -> bool

The inverse of AbsDiffEq::abs_diff_eq.
Source§

impl Add for &Configuration

Source§

type Output = Configuration

The resulting type after applying the + operator.
Source§

fn add(self, rhs: &Configuration) -> <&Configuration as Add>::Output

Performs the + operation. Read more
Source§

impl Add for Configuration

Source§

type Output = Configuration

The resulting type after applying the + operator.
Source§

fn add(self, rhs: Configuration) -> <Configuration as Add>::Output

Performs the + operation. Read more
Source§

impl Clone for Configuration

Source§

fn clone(&self) -> Configuration

Returns a duplicate of the value. Read more
1.0.0 · Source§

fn clone_from(&mut self, source: &Self)

Performs copy-assignment from source. Read more
Source§

impl Debug for Configuration

Source§

fn fmt(&self, f: &mut Formatter<'_>) -> Result<(), Error>

Formats the value using the given formatter. Read more
Source§

impl Display for Configuration

Source§

fn fmt(&self, f: &mut Formatter<'_>) -> Result<(), Error>

Formats the value using the given formatter. Read more
Source§

impl Index<usize> for Configuration

Source§

type Output = f64

The returned type after indexing.
Source§

fn index(&self, index: usize) -> &<Configuration as Index<usize>>::Output

Performs the indexing (container[index]) operation. Read more
Source§

impl IndexMut<usize> for Configuration

Source§

fn index_mut( &mut self, index: usize, ) -> &mut <Configuration as Index<usize>>::Output

Performs the mutable indexing (container[index]) operation. Read more
Source§

impl Mul<f64> for &Configuration

Source§

type Output = Matrix<f64, Dyn, Const<1>, VecStorage<f64, Dyn, Const<1>>>

The resulting type after applying the * operator.
Source§

fn mul(self, rhs: f64) -> <&Configuration as Mul<f64>>::Output

Performs the * operation. Read more
Source§

impl PartialEq for Configuration

Source§

fn eq(&self, other: &Configuration) -> bool

Tests for self and other values to be equal, and is used by ==.
1.0.0 · Source§

fn ne(&self, other: &Rhs) -> bool

Tests for !=. The default implementation is almost always sufficient, and should not be overridden without very good reason.
Source§

impl RelativeEq for Configuration

Source§

fn default_max_relative() -> f64

The default relative tolerance for testing values that are far-apart. Read more
Source§

fn relative_eq( &self, other: &Configuration, epsilon: f64, max_relative: f64, ) -> bool

A test for equality that uses a relative comparison if the values are far apart.
Source§

fn relative_ne( &self, other: &Rhs, epsilon: Self::Epsilon, max_relative: Self::Epsilon, ) -> bool

The inverse of RelativeEq::relative_eq.
Source§

impl Sub for &Configuration

Source§

type Output = Configuration

The resulting type after applying the - operator.
Source§

fn sub(self, rhs: &Configuration) -> <&Configuration as Sub>::Output

Performs the - operation. Read more
Source§

impl SubAssign<&Configuration> for Configuration

Source§

fn sub_assign(&mut self, rhs: &Configuration)

Performs the -= operation. Read more
Source§

impl StructuralPartialEq for Configuration

Auto Trait Implementations§

Blanket Implementations§

Source§

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

Source§

fn type_id(&self) -> TypeId

Gets the TypeId of self. Read more
Source§

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

Source§

fn borrow(&self) -> &T

Immutably borrows from an owned value. Read more
Source§

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

Source§

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

Mutably borrows from an owned value. Read more
Source§

impl<T> CloneToUninit for T
where T: Clone,

Source§

unsafe fn clone_to_uninit(&self, dest: *mut u8)

🔬This is a nightly-only experimental API. (clone_to_uninit)
Performs copy-assignment from self to dest. Read more
Source§

impl<T> From<T> for T

Source§

fn from(t: T) -> T

Returns the argument unchanged.

Source§

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

Source§

fn into(self) -> U

Calls U::from(self).

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

Source§

impl<T> Same for T

Source§

type Output = T

Should always be Self
Source§

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

Source§

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

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

fn is_in_subset(&self) -> bool

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

fn to_subset_unchecked(&self) -> SS

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

fn from_subset(element: &SS) -> SP

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

impl<T> ToOwned for T
where T: Clone,

Source§

type Owned = T

The resulting type after obtaining ownership.
Source§

fn to_owned(&self) -> T

Creates owned data from borrowed data, usually by cloning. Read more
Source§

fn clone_into(&self, target: &mut T)

Uses borrowed data to replace owned data, usually by cloning. Read more
Source§

impl<T> ToString for T
where T: Display + ?Sized,

Source§

fn to_string(&self) -> String

Converts the given value to a String. Read more
Source§

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

Source§

type Error = Infallible

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

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

Performs the conversion.
Source§

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

Source§

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

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

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

Performs the conversion.
Source§

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

Source§

fn vzip(self) -> V

Source§

impl<T> Scalar for T
where T: 'static + Clone + PartialEq + Debug,