Skip to main content

Model

Struct Model 

Source
pub struct Model {
    pub name: String,
    pub joint_names: Vec<String>,
    pub joint_parents: Vec<usize>,
    pub joint_placements: Vec<SE3>,
    pub joint_models: Vec<JointWrapper>,
    pub nq: usize,
    pub nv: usize,
    pub inertias: Vec<Inertia>,
    pub frames: Vec<Frame>,
    pub gravity: Vector3D,
}
Expand description

Data structure that contains the immutable properties of the robot model. It contains information about the joints, frames, and their local placements.

Fields§

§name: String

Name of the model.

§joint_names: Vec<String>

Names of the joints.

§joint_parents: Vec<usize>

Parent joint of each joint.

§joint_placements: Vec<SE3>

Placements of the joints relative to their parent joints.

§joint_models: Vec<JointWrapper>

Joint models.

§nq: usize

Number of position variables.

§nv: usize

Number of velocity variables.

§inertias: Vec<Inertia>

Inertias of the bodies at each joint.

§frames: Vec<Frame>

Operational frames at each joint

§gravity: Vector3D

The spatial gravity of the model.

Implementations§

Source§

impl Model

Source

pub fn new(name: String) -> Model

Creates a new Model with given name.

Same as Model::new_empty().

§Arguments
  • name - The name of the model.
Source

pub fn new_empty() -> Model

Creates a new empty Model.

§Returns

A new empty Model.

Source

pub fn add_joint( &mut self, parent_id: usize, joint_model: JointWrapper, placement: SE3, name: String, ) -> Result<usize, ModelError>

Adds a joint to the model.

§Arguments
  • parent_id - The identifier of the parent joint. Use 0 for the root joint.
  • joint_model - The joint model to add.
  • placement - The placement of the joint in the parent frame.
  • name - The name of the joint.
Source

pub fn add_frame( &mut self, frame: Frame, append_inertia: bool, ) -> Result<usize, ModelError>

Adds a frame (fixed joint) to the model.

§Arguments
  • placement - The placement of the frame in the parent frame.
  • name - The name of the frame.
§Returns

The identifier of the frame.

Source

pub fn create_data(&self) -> Data

Creates the data associated with the model.

§Returns

The data associated with the model.

Examples found in repository?
examples/inverse_dynamics.rs (line 17)
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 17)
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}
examples/forward_kinematics.rs (line 16)
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
12    let q = random_configuration(&model);
13    println!("Random configuration q: {}", q);
14
15    // Create data structure for the model
16    let mut data = model.create_data();
17
18    // Compute forward kinematics
19    forward_kinematics(&model, &mut data, &q, None, None)
20        .expect("Failed to compute forward kinematics");
21
22    // Print the placement of the joint 'wrist_3_joint'
23    let id = model.get_joint_id("wrist_3_joint").unwrap();
24    let placement = &data.joint_placements[id];
25    println!("Placement of 'wrist_3_joint':\n{}", placement);
26
27    // Compute the frame placements
28    update_frame_placements(&model, &mut data);
29
30    // Print the placement of the frame 'tool0'
31    let frame_id = model.get_frame_id("tool0", None).unwrap();
32    // we don't specify a frame type (None) as there is only one frame with this name
33    let frame_placement = &data.frame_placements[frame_id];
34    println!("Placement of frame 'tool0':\n{}", frame_placement);
35}
Source

pub fn append_body_to_joint( &mut self, joint_id: usize, inertia: &Inertia, placement: SE3, ) -> Result<(), ModelError>

Appends a body of given inertia to the joint with given id.

§Arguments
  • joint_id - The identifier of the joint to append the body to.
  • inertia - The inertia of the body to append.
  • placement - The placement of the body in the joint frame.
§Returns

A result indicating success or failure.

Source

pub fn get_joint_id(&self, name: &str) -> Option<usize>

Returns the index of the joint with the given name.

Examples found in repository?
examples/forward_kinematics.rs (line 23)
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
12    let q = random_configuration(&model);
13    println!("Random configuration q: {}", q);
14
15    // Create data structure for the model
16    let mut data = model.create_data();
17
18    // Compute forward kinematics
19    forward_kinematics(&model, &mut data, &q, None, None)
20        .expect("Failed to compute forward kinematics");
21
22    // Print the placement of the joint 'wrist_3_joint'
23    let id = model.get_joint_id("wrist_3_joint").unwrap();
24    let placement = &data.joint_placements[id];
25    println!("Placement of 'wrist_3_joint':\n{}", placement);
26
27    // Compute the frame placements
28    update_frame_placements(&model, &mut data);
29
30    // Print the placement of the frame 'tool0'
31    let frame_id = model.get_frame_id("tool0", None).unwrap();
32    // we don't specify a frame type (None) as there is only one frame with this name
33    let frame_placement = &data.frame_placements[frame_id];
34    println!("Placement of frame 'tool0':\n{}", frame_placement);
35}
Source

pub fn get_frame_id( &self, name: &str, frame_type: Option<&FrameType>, ) -> Option<usize>

Returns the index of the frame with the given name.

§Arguments
  • name - The name of the frame.
  • frame_type - The type of the frame.
§Returns

The index of the frame with the given name and type, or None if not found.

Examples found in repository?
examples/forward_kinematics.rs (line 31)
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
12    let q = random_configuration(&model);
13    println!("Random configuration q: {}", q);
14
15    // Create data structure for the model
16    let mut data = model.create_data();
17
18    // Compute forward kinematics
19    forward_kinematics(&model, &mut data, &q, None, None)
20        .expect("Failed to compute forward kinematics");
21
22    // Print the placement of the joint 'wrist_3_joint'
23    let id = model.get_joint_id("wrist_3_joint").unwrap();
24    let placement = &data.joint_placements[id];
25    println!("Placement of 'wrist_3_joint':\n{}", placement);
26
27    // Compute the frame placements
28    update_frame_placements(&model, &mut data);
29
30    // Print the placement of the frame 'tool0'
31    let frame_id = model.get_frame_id("tool0", None).unwrap();
32    // we don't specify a frame type (None) as there is only one frame with this name
33    let frame_placement = &data.frame_placements[frame_id];
34    println!("Placement of frame 'tool0':\n{}", frame_placement);
35}
Source

pub fn njoints(&self) -> usize

Returns the number of joints in the model, including the world frame.

Source

pub fn nframes(&self) -> usize

Returns the number of frames in the model, including the world frame.

Source

pub fn print_joint_tree(&self) -> Result<(), Error>

Prints the joint tree of the model to the standard output.

Examples found in repository?
examples/parse_urdf.rs (line 25)
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    // Print the names of the joints
12    println!("Joints in the model:");
13    for joint_name in &model.joint_names {
14        println!("- {}", joint_name);
15    }
16
17    // Print the names of the frames
18    println!("\nFrames in the model:");
19    for frame in &model.frames {
20        println!("- {}", frame.name);
21    }
22    println!();
23
24    // Print the joint tree
25    model.print_joint_tree().unwrap();
26}

Trait Implementations§

Source§

impl Clone for Model

Source§

fn clone(&self) -> Model

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 Model

Source§

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

Formats the value using the given formatter. Read more

Auto Trait Implementations§

§

impl Freeze for Model

§

impl RefUnwindSafe for Model

§

impl Send for Model

§

impl Sync for Model

§

impl Unpin for Model

§

impl UnsafeUnpin for Model

§

impl UnwindSafe for Model

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, 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