pub struct RobotState {Show 47 fields
pub O_T_EE: [f64; 16],
pub O_T_EE_d: [f64; 16],
pub F_T_EE: [f64; 16],
pub F_T_NE: [f64; 16],
pub NE_T_EE: [f64; 16],
pub EE_T_K: [f64; 16],
pub m_ee: f64,
pub I_ee: [f64; 9],
pub F_x_Cee: [f64; 3],
pub m_load: f64,
pub I_load: [f64; 9],
pub F_x_Cload: [f64; 3],
pub m_total: f64,
pub I_total: [f64; 9],
pub F_x_Ctotal: [f64; 3],
pub elbow: [f64; 2],
pub elbow_d: [f64; 2],
pub elbow_c: [f64; 2],
pub delbow_c: [f64; 2],
pub ddelbow_c: [f64; 2],
pub tau_J: [f64; 7],
pub tau_J_d: [f64; 7],
pub dtau_J: [f64; 7],
pub q: [f64; 7],
pub q_d: [f64; 7],
pub dq: [f64; 7],
pub dq_d: [f64; 7],
pub ddq_d: [f64; 7],
pub joint_contact: [f64; 7],
pub cartesian_contact: [f64; 6],
pub joint_collision: [f64; 7],
pub cartesian_collision: [f64; 6],
pub tau_ext_hat_filtered: [f64; 7],
pub O_F_ext_hat_K: [f64; 6],
pub K_F_ext_hat_K: [f64; 6],
pub O_dP_EE_d: [f64; 6],
pub O_ddP_O: [f64; 3],
pub O_T_EE_c: [f64; 16],
pub O_dP_EE_c: [f64; 6],
pub O_ddP_EE_c: [f64; 6],
pub theta: [f64; 7],
pub dtheta: [f64; 7],
pub current_errors: FrankaErrors,
pub last_motion_errors: FrankaErrors,
pub control_command_success_rate: f64,
pub robot_mode: RobotMode,
pub time: Duration,
}
Expand description
Describes the robot state.
Fields§
§O_T_EE: [f64; 16]
Measured end effector pose in base frame. Pose is represented as a 4x4 matrix in column-major format.
O_T_EE_d: [f64; 16]
Last desired end effector pose of motion generation in base frame. Pose is represented as a 4x4 matrix in column-major format.
F_T_EE: [f64; 16]
End effector frame pose in flange frame. Pose is represented as a 4x4 matrix in column-major format.
§See
F_T_NE: [f64; 16]
Nominal end effector frame pose in flange frame. Pose is represented as a 4x4 matrix in column-major format.
§See
NE_T_EE: [f64; 16]
End effector frame pose in nominal end effector frame. Pose is represented as a 4x4 matrix in column-major format.
§See
EE_T_K: [f64; 16]
Stiffness frame pose in end effector frame. Pose is represented as a 4x4 matrix in column-major format.
See also K-Frame
m_ee: f64
Configured mass of the end effector.
I_ee: [f64; 9]
Configured rotational inertia matrix of the end effector load with respect to center of mass.
F_x_Cee: [f64; 3]
Configured center of mass of the end effector load with respect to flange frame.
m_load: f64
Configured mass of the external load.
I_load: [f64; 9]
Configured rotational inertia matrix of the external load with respect to center of mass.
F_x_Cload: [f64; 3]
Configured center of mass of the external load with respect to flange frame.
m_total: f64
Sum of the mass of the end effector and the external load.
I_total: [f64; 9]
Combined rotational inertia matrix of the end effector load and the external load with respect to the center of mass.
F_x_Ctotal: [f64; 3]
Combined center of mass of the end effector load and the external load with respect to flange frame.
elbow: [f64; 2]
Elbow configuration.
The values of the array are:
- [0] Position of the 3rd joint in [rad].
- [1] Sign of the 4th joint. Can be +1 or -1.
elbow_d: [f64; 2]
Desired elbow configuration.
The values of the array are:
- [0] Position of the 3rd joint in [rad].
- [1] Sign of the 4th joint. Can be +1 or -1.
elbow_c: [f64; 2]
Commanded elbow configuration.
The values of the array are:
- [0] Position of the 3rd joint in [rad].
- [1] Sign of the 4th joint. Can be +1 or -1.
delbow_c: [f64; 2]
Commanded elbow velocity.
The values of the array are:
- [0] Velocity of the 3rd joint in [rad/s].
- [1] Sign of the 4th joint. Can be +1 or -1.
ddelbow_c: [f64; 2]
Commanded elbow acceleration.
The values of the array are:
- [0] Acceleration of the 3rd joint in [rad/s^2].
- [1] Sign of the 4th joint. Can be +1 or -1.
tau_J: [f64; 7]
Measured link-side joint torque sensor signals. Unit: [Nm]
tau_J_d: [f64; 7]
Desired link-side joint torque sensor signals without gravity. Unit: [Nm]
dtau_J: [f64; 7]
Derivative of measured link-side joint torque sensor signals. Unit: [Nm/s]
q: [f64; 7]
Measured joint position. Unit: [rad]
q_d: [f64; 7]
Desired joint position. Unit: [rad]
dq: [f64; 7]
Measured joint velocity. Unit: [rad/s]
dq_d: [f64; 7]
Desired joint velocity. Unit: [rad/s]
ddq_d: [f64; 7]
Desired joint acceleration. Unit: [rad/s^2]
joint_contact: [f64; 7]
Indicates which contact level is activated in which joint. After contact disappears, value turns to zero.
See Robot::set_collision_behavior
for setting sensitivity values.
cartesian_contact: [f64; 6]
Indicates which contact level is activated in which Cartesian dimension (x,y,z,R,P,Y). After contact disappears, the value turns to zero.
See Robot::set_collision_behavior
for setting sensitivity values.
joint_collision: [f64; 7]
Indicates which contact level is activated in which joint. After contact disappears, the value stays the same until a reset command is sent.
See Robot::set_collision_behavior
for setting sensitivity values.
See Robot::automatic_error_recovery
for performing a reset after a collision.
cartesian_collision: [f64; 6]
Indicates which contact level is activated in which Cartesian dimension (x,y,z,R,P,Y). After contact disappears, the value stays the same until a reset command is sent.
See Robot::set_collision_behavior
for setting sensitivity values.
See Robot::automatic_error_recovery
for performing a reset after a collision.
tau_ext_hat_filtered: [f64; 7]
External torque, filtered. Unit: [Nm]
O_F_ext_hat_K: [f64; 6]
Estimated external wrench (force, torque) acting on stiffness frame, expressed relative to the base frame. See also @ref k-frame “K frame”. Unit: [N,N,N,Nm,Nm,Nm].
K_F_ext_hat_K: [f64; 6]
Estimated external wrench (force, torque) acting on stiffness frame, expressed relative to the stiffness frame. See also @ref k-frame “K frame”. Unit: [N,N,N,Nm,Nm,Nm].
O_dP_EE_d: [f64; 6]
Desired end effector twist in base frame. Unit: [m/s,m/s,m/s,rad/s,rad/s,rad/s]
O_ddP_O: [f64; 3]
Linear component of the acceleration of the robot’s base, expressed in frame parallel to the
base frame, i.e. the base’s translational acceleration. If the base is resting
this shows the direction of the gravity vector. It is hardcoded for now to {0, 0, -9.81}
.
O_T_EE_c: [f64; 16]
Last commanded end effector pose of motion generation in base frame. Pose is represented as a 4x4 matrix in column-major format.
O_dP_EE_c: [f64; 6]
Last commanded end effector twist in base frame. Unit: [m/s,m/s,m/s,rad/s,rad/s,rad/s]
O_ddP_EE_c: [f64; 6]
Last commanded end effector acceleration in base frame. Unit: [m/s^2,m/s^2,m/s^2,rad/s^2,rad/s^2,rad/s^2]
theta: [f64; 7]
Motor position. Unit: [rad]
dtheta: [f64; 7]
Motor velocity. Unit: [rad/s]
current_errors: FrankaErrors
Current error state.
last_motion_errors: FrankaErrors
Contains the errors that aborted the previous motion
control_command_success_rate: f64
Percentage of the last 100 control commands that were successfully received by the robot.
Shows a value of zero if no control or motion generator loop is currently running.
Range [0,1]
robot_mode: RobotMode
Current robot mode.
time: Duration
Strictly monotonically increasing timestamp since robot start.
Inside of control loops “time_step” parameter of Robot::control can be used instead
Trait Implementations§
Source§impl Clone for RobotState
impl Clone for RobotState
Source§fn clone(&self) -> RobotState
fn clone(&self) -> RobotState
1.0.0 · Source§fn clone_from(&mut self, source: &Self)
fn clone_from(&mut self, source: &Self)
source
. Read moreSource§impl Debug for RobotState
impl Debug for RobotState
Source§impl Default for RobotState
impl Default for RobotState
Source§fn default() -> RobotState
fn default() -> RobotState
Auto Trait Implementations§
impl Freeze for RobotState
impl RefUnwindSafe for RobotState
impl Send for RobotState
impl Sync for RobotState
impl Unpin for RobotState
impl UnwindSafe for RobotState
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.