pub struct Configuration(/* private fields */);Expand description
Configuration of a multi-body system, represented as a vector of joint positions.
Implementations§
Source§impl Configuration
impl Configuration
Sourcepub fn zeros(size: usize) -> Configuration
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.
Sourcepub fn ones(size: usize) -> Configuration
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.
Sourcepub fn from_element(size: usize, value: f64) -> Configuration
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?
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
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}Sourcepub fn rows(&self, start: usize, nrows: usize) -> Configuration
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.
Sourcepub fn update_rows(
&mut self,
start: usize,
values: &Configuration,
) -> Result<(), ConfigurationError>
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.
Sourcepub fn from_row_slice(data: &[f64]) -> Configuration
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.
Sourcepub fn concat(configs: &[Configuration]) -> Configuration
pub fn concat(configs: &[Configuration]) -> Configuration
Concatenates multiple Configuration objects into a single configuration.
§Arguments
configs- A slice ofConfigurationobjects to concatenate.
§Returns
A new Configuration object containing all values from the input configurations.
Sourcepub fn random(
nq: usize,
rng: &mut ThreadRng,
min: &Configuration,
max: &Configuration,
) -> Configuration
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.
Sourcepub fn check_size(
&self,
name: &str,
expected_size: usize,
) -> Result<(), ConfigurationError>
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
impl AbsDiffEq for Configuration
Source§fn default_epsilon() -> <Configuration as AbsDiffEq>::Epsilon
fn default_epsilon() -> <Configuration as AbsDiffEq>::Epsilon
Source§fn abs_diff_eq(
&self,
other: &Configuration,
epsilon: <Configuration as AbsDiffEq>::Epsilon,
) -> bool
fn abs_diff_eq( &self, other: &Configuration, epsilon: <Configuration as AbsDiffEq>::Epsilon, ) -> bool
Source§fn abs_diff_ne(&self, other: &Rhs, epsilon: Self::Epsilon) -> bool
fn abs_diff_ne(&self, other: &Rhs, epsilon: Self::Epsilon) -> bool
AbsDiffEq::abs_diff_eq.Source§impl Add for &Configuration
impl Add for &Configuration
Source§type Output = Configuration
type Output = Configuration
+ operator.Source§fn add(self, rhs: &Configuration) -> <&Configuration as Add>::Output
fn add(self, rhs: &Configuration) -> <&Configuration as Add>::Output
+ operation. Read moreSource§impl Add for Configuration
impl Add for Configuration
Source§type Output = Configuration
type Output = Configuration
+ operator.Source§fn add(self, rhs: Configuration) -> <Configuration as Add>::Output
fn add(self, rhs: Configuration) -> <Configuration as Add>::Output
+ operation. Read moreSource§impl Clone for Configuration
impl Clone for Configuration
Source§fn clone(&self) -> Configuration
fn clone(&self) -> Configuration
1.0.0 · Source§fn clone_from(&mut self, source: &Self)
fn clone_from(&mut self, source: &Self)
source. Read moreSource§impl Debug for Configuration
impl Debug for Configuration
Source§impl Display for Configuration
impl Display for Configuration
Source§impl Index<usize> for Configuration
impl Index<usize> for Configuration
Source§impl IndexMut<usize> for Configuration
impl IndexMut<usize> for Configuration
Source§impl Mul<f64> for &Configuration
impl Mul<f64> for &Configuration
Source§impl PartialEq for Configuration
impl PartialEq for Configuration
Source§impl RelativeEq for Configuration
impl RelativeEq for Configuration
Source§fn default_max_relative() -> f64
fn default_max_relative() -> f64
Source§fn relative_eq(
&self,
other: &Configuration,
epsilon: f64,
max_relative: f64,
) -> bool
fn relative_eq( &self, other: &Configuration, epsilon: f64, max_relative: f64, ) -> bool
Source§fn relative_ne(
&self,
other: &Rhs,
epsilon: Self::Epsilon,
max_relative: Self::Epsilon,
) -> bool
fn relative_ne( &self, other: &Rhs, epsilon: Self::Epsilon, max_relative: Self::Epsilon, ) -> bool
RelativeEq::relative_eq.Source§impl Sub for &Configuration
impl Sub for &Configuration
Source§type Output = Configuration
type Output = Configuration
- operator.Source§fn sub(self, rhs: &Configuration) -> <&Configuration as Sub>::Output
fn sub(self, rhs: &Configuration) -> <&Configuration as Sub>::Output
- operation. Read moreSource§impl SubAssign<&Configuration> for Configuration
impl SubAssign<&Configuration> for Configuration
Source§fn sub_assign(&mut self, rhs: &Configuration)
fn sub_assign(&mut self, rhs: &Configuration)
-= operation. Read moreimpl StructuralPartialEq for Configuration
Auto Trait Implementations§
impl Freeze for Configuration
impl RefUnwindSafe for Configuration
impl Send for Configuration
impl Sync for Configuration
impl Unpin for Configuration
impl UnsafeUnpin for Configuration
impl UnwindSafe for Configuration
Blanket Implementations§
Source§impl<T> BorrowMut<T> for Twhere
T: ?Sized,
impl<T> BorrowMut<T> for Twhere
T: ?Sized,
Source§fn borrow_mut(&mut self) -> &mut T
fn borrow_mut(&mut self) -> &mut T
Source§impl<T> CloneToUninit for Twhere
T: Clone,
impl<T> CloneToUninit for Twhere
T: Clone,
Source§impl<SS, SP> SupersetOf<SS> for SPwhere
SS: SubsetOf<SP>,
impl<SS, SP> SupersetOf<SS> for SPwhere
SS: SubsetOf<SP>,
Source§fn to_subset(&self) -> Option<SS>
fn to_subset(&self) -> Option<SS>
self from the equivalent element of its
superset. Read moreSource§fn is_in_subset(&self) -> bool
fn is_in_subset(&self) -> bool
self is actually part of its subset T (and can be converted to it).Source§fn to_subset_unchecked(&self) -> SS
fn to_subset_unchecked(&self) -> SS
self.to_subset but without any property checks. Always succeeds.Source§fn from_subset(element: &SS) -> SP
fn from_subset(element: &SS) -> SP
self to the equivalent element of its superset.