pub struct Model { /* private fields */ }
Expand description
Calculates poses of joints and dynamic properties of the robot.
Implementations
sourceimpl Model
impl Model
sourcepub fn new<S: AsRef<Path>>(
model_filename: S,
libm_filename: Option<&Path>
) -> FrankaResult<Self>
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> ¯_(ツ)_/¯
sourcepub fn pose(
&self,
frame: &Frame,
q: &[f64; 7],
F_T_EE: &[f64; 16],
EE_T_K: &[f64; 16]
) -> [f64; 16]
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.
sourcepub fn pose_from_state(
&self,
frame: &Frame,
robot_state: &RobotState
) -> [f64; 16]
pub fn pose_from_state(
&self,
frame: &Frame,
robot_state: &RobotState
) -> [f64; 16]
sourcepub fn body_jacobian(
&self,
frame: &Frame,
q: &[f64; 7],
F_T_EE: &[f64; 16],
EE_T_K: &[f64; 16]
) -> [f64; 42]
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.
sourcepub fn body_jacobian_from_state(
&self,
frame: &Frame,
robot_state: &RobotState
) -> [f64; 42]
pub fn body_jacobian_from_state(
&self,
frame: &Frame,
robot_state: &RobotState
) -> [f64; 42]
sourcepub fn zero_jacobian(
&self,
frame: &Frame,
q: &[f64; 7],
F_T_EE: &[f64; 16],
EE_T_K: &[f64; 16]
) -> [f64; 42]
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.
sourcepub fn zero_jacobian_from_state(
&self,
frame: &Frame,
robot_state: &RobotState
) -> [f64; 42]
pub fn zero_jacobian_from_state(
&self,
frame: &Frame,
robot_state: &RobotState
) -> [f64; 42]
sourcepub fn mass(
&self,
q: &[f64; 7],
I_total: &[f64; 9],
m_total: f64,
F_x_Ctotal: &[f64; 3]
) -> [f64; 49]
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.
sourcepub fn mass_from_state(&self, robot_state: &RobotState) -> [f64; 49]
pub fn mass_from_state(&self, robot_state: &RobotState) -> [f64; 49]
sourcepub fn coriolis(
&self,
q: &[f64; 7],
dq: &[f64; 7],
I_total: &[f64; 9],
m_total: f64,
F_x_Ctotal: &[f64; 3]
) -> [f64; 7]
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): , 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.
sourcepub fn coriolis_from_state(&self, robot_state: &RobotState) -> [f64; 7]
pub fn coriolis_from_state(&self, robot_state: &RobotState) -> [f64; 7]
sourcepub 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]
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.
sourcepub fn gravity_from_state<'a, Grav: Into<Option<&'a [f64; 3]>>>(
&self,
robot_state: &RobotState,
gravity_earth: Grav
) -> [f64; 7]
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 defaultgravity_earth
will be calculated fromRobotState::O_ddP_O
.
Return
Gravity vector.
Auto Trait Implementations
impl RefUnwindSafe for Model
impl Send for Model
impl Sync for Model
impl Unpin for Model
impl UnwindSafe for Model
Blanket Implementations
sourceimpl<T> BorrowMut<T> for T where
T: ?Sized,
impl<T> BorrowMut<T> for T where
T: ?Sized,
const: unstable · sourcefn borrow_mut(&mut self) -> &mut T
fn borrow_mut(&mut self) -> &mut T
Mutably borrows from an owned value. Read more
impl<SS, SP> SupersetOf<SS> for SP where
SS: SubsetOf<SP>,
impl<SS, SP> SupersetOf<SS> for SP where
SS: SubsetOf<SP>,
fn to_subset(&self) -> Option<SS>
fn to_subset(&self) -> Option<SS>
The inverse inclusion map: attempts to construct self
from the equivalent element of its
superset. Read more
fn is_in_subset(&self) -> bool
fn is_in_subset(&self) -> bool
Checks if self
is actually part of its subset T
(and can be converted to it).
fn to_subset_unchecked(&self) -> SS
fn to_subset_unchecked(&self) -> SS
Use with care! Same as self.to_subset
but without any property checks. Always succeeds.
fn from_subset(element: &SS) -> SP
fn from_subset(element: &SS) -> SP
The inclusion map: converts self
to the equivalent element of its superset.