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: StringName 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: usizeNumber of position variables.
nv: usizeNumber of velocity variables.
inertias: Vec<Inertia>Inertias of the bodies at each joint.
frames: Vec<Frame>Operational frames at each joint
gravity: Vector3DThe spatial gravity of the model.
Implementations§
Source§impl Model
impl Model
Sourcepub fn new(name: String) -> Model
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.
Sourcepub fn add_joint(
&mut self,
parent_id: usize,
joint_model: JointWrapper,
placement: SE3,
name: String,
) -> Result<usize, ModelError>
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.
Sourcepub fn add_frame(
&mut self,
frame: Frame,
append_inertia: bool,
) -> Result<usize, ModelError>
pub fn add_frame( &mut self, frame: Frame, append_inertia: bool, ) -> Result<usize, ModelError>
Sourcepub fn create_data(&self) -> Data
pub fn create_data(&self) -> Data
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}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}Sourcepub fn append_body_to_joint(
&mut self,
joint_id: usize,
inertia: &Inertia,
placement: SE3,
) -> Result<(), ModelError>
pub fn append_body_to_joint( &mut self, joint_id: usize, inertia: &Inertia, placement: SE3, ) -> Result<(), ModelError>
Sourcepub fn get_joint_id(&self, name: &str) -> Option<usize>
pub fn get_joint_id(&self, name: &str) -> Option<usize>
Returns the index of the joint with the given name.
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
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}Sourcepub fn get_frame_id(
&self,
name: &str,
frame_type: Option<&FrameType>,
) -> Option<usize>
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?
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}Sourcepub fn njoints(&self) -> usize
pub fn njoints(&self) -> usize
Returns the number of joints in the model, including the world frame.
Sourcepub fn nframes(&self) -> usize
pub fn nframes(&self) -> usize
Returns the number of frames in the model, including the world frame.
Sourcepub fn print_joint_tree(&self) -> Result<(), Error>
pub fn print_joint_tree(&self) -> Result<(), Error>
Prints the joint tree of the model to the standard output.
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 // 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§
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> 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.