Struct Model

Source
pub struct Model { /* private fields */ }
Expand description

Calculates poses of joints and dynamic properties of the robot.

Implementations§

Source§

impl Model

Source

pub fn new<S: AsRef<Path>>( model_filename: S, libm_filename: Option<&Path>, ) -> FrankaResult<Self>

Creates a new Model instance from the shared object of the Model for offline usage.

If you just want to use the model to control the Robot you should use Robot::load_model.

If you do not have the model you can use the download_model example to download the model

§Arguments
  • model_filename - Path to the model.
  • libm_filename - Path to libm.so.6 . You probably do not need to specify the path as it it should be detected automatically. However if you get panics for unresolved symbols or libm could not be found you have to specify the path. On most Ubuntu systems it is in
/lib/x86_64-linux-gnu/libm.so.6

It maybe has a different name on your machine but it is not the “libm.so”. You can verify that it is the correct libm by checking:

 nm -D /lib/x86_64-linux-gnu/libm.so.6 | grep sincos
§Errors
  • ModelException
§libm FAQ

What is libm? - Libm is the Math library of the C Standard Library. It is what you get when you include <math.h> in C

Why do we need it? - Because the model is not self contained and relies on some functions from libm

How does the libfranka embed libm? They are not including <math.h> - Apparently it gets somehow included when using <array> ¯_(ツ)_/¯

Source

pub fn pose( &self, frame: &Frame, q: &[f64; 7], F_T_EE: &[f64; 16], EE_T_K: &[f64; 16], ) -> [f64; 16]

Gets the 4x4 pose matrix for the given frame in base frame.

The pose is represented as a 4x4 matrix in column-major format.

§Arguments
  • frame - The desired frame.
  • q - Joint position.
  • F_T_EE - End effector in flange frame.
  • EE_T_K - Stiffness frame K in the end effector frame.
§Return

Vectorized 4x4 pose matrix, column-major.

Source

pub fn pose_from_state( &self, frame: &Frame, robot_state: &RobotState, ) -> [f64; 16]

Gets the 4x4 pose matrix for the given frame in base frame.

The pose is represented as a 4x4 matrix in column-major format.

§Arguments
  • frame - The desired frame.
  • robot_state - State from which the pose should be calculated.
§Return

Vectorized 4x4 pose matrix, column-major.

Source

pub fn body_jacobian( &self, frame: &Frame, q: &[f64; 7], F_T_EE: &[f64; 16], EE_T_K: &[f64; 16], ) -> [f64; 42]

Gets the 6x7 Jacobian for the given frame, relative to that frame.

The Jacobian is represented as a 6x7 matrix in column-major format.

§Arguments
  • frame - The desired frame.
  • q - Joint position.
  • F_T_EE - End effector in flange frame.
  • EE_T_K - Stiffness frame K in the end effector frame.
§Return

Vectorized 6x7 Jacobian, column-major.

Source

pub fn body_jacobian_from_state( &self, frame: &Frame, robot_state: &RobotState, ) -> [f64; 42]

Gets the 6x7 Jacobian for the given frame, relative to that frame.

The Jacobian is represented as a 6x7 matrix in column-major format.

§Arguments
  • frame - The desired frame.
  • robot_state - State from which the pose should be calculated.
§Return

Vectorized 6x7 Jacobian, column-major.

Source

pub fn zero_jacobian( &self, frame: &Frame, q: &[f64; 7], F_T_EE: &[f64; 16], EE_T_K: &[f64; 16], ) -> [f64; 42]

Gets the 6x7 Jacobian for the given joint relative to the base frame.

The Jacobian is represented as a 6x7 matrix in column-major format.

§Arguments
  • frame - The desired frame.
  • q - Joint position.
  • F_T_EE - End effector in flange frame.
  • EE_T_K - Stiffness frame K in the end effector frame.
§Return

Vectorized 6x7 Jacobian, column-major.

Source

pub fn zero_jacobian_from_state( &self, frame: &Frame, robot_state: &RobotState, ) -> [f64; 42]

Gets the 6x7 Jacobian for the given joint relative to the base frame.

The Jacobian is represented as a 6x7 matrix in column-major format.

§Arguments
  • frame - The desired frame.
  • robot_state - State from which the pose should be calculated.
§Return

Vectorized 6x7 Jacobian, column-major.

Source

pub fn mass( &self, q: &[f64; 7], I_total: &[f64; 9], m_total: f64, F_x_Ctotal: &[f64; 3], ) -> [f64; 49]

Calculates the 7x7 mass matrix. Unit: [kg \times m^2].

§Arguments
  • q - Joint position.
  • I_total - Inertia of the attached total load including end effector, relative to center of mass, given as vectorized 3x3 column-major matrix. Unit: [kg * m^2].
  • m_total - Weight of the attached total load including end effector. Unit: [kg].
  • F_x_Ctotal - Translation from flange to center of mass of the attached total load. Unit: [m].
§Return

Vectorized 7x7 mass matrix, column-major.

Source

pub fn mass_from_state(&self, robot_state: &RobotState) -> [f64; 49]

Calculates the 7x7 mass matrix. Unit: [kg \times m^2].

§Arguments
  • robot_state - State from which the mass matrix should be calculated.
§Return

Vectorized 7x7 mass matrix, column-major.

Source

pub fn coriolis( &self, q: &[f64; 7], dq: &[f64; 7], I_total: &[f64; 9], m_total: f64, F_x_Ctotal: &[f64; 3], ) -> [f64; 7]

Calculates the Coriolis force vector (state-space equation): c= C \times dq, in [Nm].

§Arguments
  • q - Joint position.
  • dq - Joint velocity.
  • I_total - Inertia of the attached total load including end effector, relative to center of mass, given as vectorized 3x3 column-major matrix. Unit: [kg * m^2].
  • m_total - Weight of the attached total load including end effector. Unit: [kg].
  • F_x_Ctotal - Translation from flange to center of mass of the attached total load. Unit: [m].
§Return

Coriolis force vector.

Source

pub fn coriolis_from_state(&self, robot_state: &RobotState) -> [f64; 7]

Calculates the Coriolis force vector (state-space equation): c= C \times dq, in [Nm].

§Arguments
  • robot_state - State from which the Coriolis force vector should be calculated.
§Return

Coriolis force vector.

Source

pub fn gravity<'a, Grav: Into<Option<&'a [f64; 3]>>>( &self, q: &[f64; 7], m_total: f64, F_x_Ctotal: &[f64; 3], gravity_earth: Grav, ) -> [f64; 7]

Calculates the gravity vector. Unit: [Nm].

§Arguments
  • q - Joint position.
  • m_total - Weight of the attached total load including end effector. Unit: [kg].
  • F_x_Ctotal - Translation from flange to center of mass of the attached total load. Unit: [m].
  • gravity_earth - Earth’s gravity vector. Unit: [m / s^2] Default to [0.0, 0.0, -9.81].
§Return

Gravity vector.

Source

pub fn gravity_from_state<'a, Grav: Into<Option<&'a [f64; 3]>>>( &self, robot_state: &RobotState, gravity_earth: Grav, ) -> [f64; 7]

Calculates the gravity vector. Unit: [Nm].

§Arguments
  • robot_state - State from which the gravity vector should be calculated.
  • gravity_earth - Earth’s gravity vector. Unit: [m / s^2]. By default gravity_earth will be calculated from RobotState::O_ddP_O.
§Return

Gravity vector.

Auto Trait Implementations§

§

impl Freeze for Model

§

impl RefUnwindSafe for Model

§

impl Send for Model

§

impl Sync for Model

§

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