Franky 0.12.0
A High-Level Motion API for Franka
Loading...
Searching...
No Matches
Static Public Member Functions | Public Attributes | List of all members
franky::RobotState Struct Reference

Full state of the robot. More...

#include <robot_state.hpp>

Static Public Member Functions

static RobotState from_franka (const franka::RobotState &robot_state, std::optional< Vector7d > ddq_est=std::nullopt, std::optional< Twist > O_dP_EE_est=std::nullopt, std::optional< TwistAcceleration > O_ddP_EE_est=std::nullopt, std::optional< double > delbow_est=std::nullopt, std::optional< double > ddelbow_est=std::nullopt)
 
static RobotState from_franka (const franka::RobotState &robot_state, const Jacobian &ee_jacobian, const Vector7d &ddq_est)
 

Public Attributes

Affine O_T_EE {}
 
Affine O_T_EE_d {}
 
Affine F_T_EE {}
 
Affine EE_T_K {}
 
double m_ee {}
 
IntertiaMatrix I_ee {}
 
Eigen::Vector3d F_x_Cee {}
 
double m_load {}
 
IntertiaMatrix I_load {}
 
Eigen::Vector3d F_x_Cload {}
 
double m_total {}
 
IntertiaMatrix I_total {}
 
Eigen::Vector3d F_x_Ctotal {}
 
ElbowState elbow {}
 
ElbowState elbow_d {}
 
ElbowState elbow_c {}
 
double delbow_c {}
 
double ddelbow_c {}
 
Vector7d tau_J {}
 
Vector7d tau_J_d {}
 
Vector7d dtau_J {}
 
Vector7d q {}
 
Vector7d q_d {}
 
Vector7d dq {}
 
Vector7d dq_d {}
 
Vector7d ddq_d {}
 
Vector7d joint_contact {}
 
Vector6d cartesian_contact {}
 
Vector7d joint_collision {}
 
Vector6d cartesian_collision {}
 
Vector7d tau_ext_hat_filtered {}
 
Vector6d O_F_ext_hat_K {}
 
Vector6d K_F_ext_hat_K {}
 
Twist O_dP_EE_d {}
 
Affine O_T_EE_c {}
 
Twist O_dP_EE_c {}
 
TwistAcceleration O_ddP_EE_c {}
 
Vector7d theta {}
 
Vector7d dtheta {}
 
franka::Errors current_errors {}
 
franka::Errors last_motion_errors {}
 
double control_command_success_rate {}
 
franka::RobotMode robot_mode = franka::RobotMode::kUserStopped
 
franka::Duration time {}
 
std::optional< Vector7dddq_est {}
 
std::optional< TwistO_dP_EE_est {}
 
std::optional< TwistAccelerationO_ddP_EE_est {}
 
std::optional< doubledelbow_est {}
 
std::optional< doubleddelbow_est {}
 

Detailed Description

Full state of the robot.

This class contains all fields of franka::RobotState and some additional fields. Each additional field ends in "_est". Unlike franka::RobotState, all fields are converted to appropriate Eigen/franky types.

Member Function Documentation

◆ from_franka() [1/2]

RobotState franky::RobotState::from_franka ( const franka::RobotState &  robot_state,
const Jacobian ee_jacobian,
const Vector7d ddq_est 
)
static

◆ from_franka() [2/2]

RobotState franky::RobotState::from_franka ( const franka::RobotState &  robot_state,
std::optional< Vector7d ddq_est = std::nullopt,
std::optional< Twist O_dP_EE_est = std::nullopt,
std::optional< TwistAcceleration O_ddP_EE_est = std::nullopt,
std::optional< double delbow_est = std::nullopt,
std::optional< double ddelbow_est = std::nullopt 
)
static

Member Data Documentation

◆ cartesian_collision

Vector6d franky::RobotState::cartesian_collision {}

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 also
Robot::setCollisionBehavior for setting sensitivity values.
Robot::automaticErrorRecovery for performing a reset after a collision.

◆ cartesian_contact

Vector6d franky::RobotState::cartesian_contact {}

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 also
Robot::setCollisionBehavior for setting sensitivity values.

◆ control_command_success_rate

double franky::RobotState::control_command_success_rate {}

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]$.

◆ current_errors

franka::Errors franky::RobotState::current_errors {}

Current error state.

◆ ddelbow_c

double franky::RobotState::ddelbow_c {}

Commanded elbow acceleration of the 3rd joint in $\frac{rad}{s^2}$

◆ ddelbow_est

std::optional<double> franky::RobotState::ddelbow_est {}

Estimated elbow acceleration (acceleration of the third joint), computed by franky. Not provided by franka firmware. Unit: $[\frac{rad}{s^2}]$.

◆ ddq_d

Vector7d franky::RobotState::ddq_d {}

$\ddot{q}_d$ Desired joint acceleration. Unit: $[\frac{rad}{s^2}]$

◆ ddq_est

std::optional<Vector7d> franky::RobotState::ddq_est {}

Estimated joint acceleration computed by franky. This value does not come from the franka firmware. Unit: $[\frac{rad}{s^2}]$.

◆ delbow_c

double franky::RobotState::delbow_c {}

Commanded velocity of the 3rd joint in $\frac{rad}{s}$

◆ delbow_est

std::optional<double> franky::RobotState::delbow_est {}

Estimated elbow velocity (velocity of the third joint), computed by franky. Not provided by franka firmware. Unit: $[\frac{rad}{s}]$.

◆ dq

Vector7d franky::RobotState::dq {}

$\dot{q}$ Measured joint velocity. Unit: $[\frac{rad}{s}]$

◆ dq_d

Vector7d franky::RobotState::dq_d {}

$\dot{q}_d$ Desired joint velocity. Unit: $[\frac{rad}{s}]$

◆ dtau_J

Vector7d franky::RobotState::dtau_J {}

$\dot{\tau_{J}}$ Derivative of measured link-side joint torque sensor signals. Unit: $[\frac{Nm}{s}]$

◆ dtheta

Vector7d franky::RobotState::dtheta {}

$\dot{\theta}$ Motor velocity. Unit: $[\frac{rad}{s}]$

◆ EE_T_K

Affine franky::RobotState::EE_T_K {}

$^{EE}T_{K}$ Stiffness frame pose in end effector frame.

See also K frame.

◆ elbow

ElbowState franky::RobotState::elbow {}

Elbow configuration.

◆ elbow_c

ElbowState franky::RobotState::elbow_c {}

Commanded elbow configuration.

◆ elbow_d

ElbowState franky::RobotState::elbow_d {}

Desired elbow configuration.

◆ F_T_EE

Affine franky::RobotState::F_T_EE {}

$^{F}T_{EE}$ End effector frame pose in flange frame.

See also
F_T_NE
NE_T_EE
Robot for an explanation of the F, NE and EE frames.

◆ F_x_Cee

Eigen::Vector3d franky::RobotState::F_x_Cee {}

$^{F}x_{C_{EE}}$ Configured center of mass of the end effector load with respect to flange frame.

◆ F_x_Cload

Eigen::Vector3d franky::RobotState::F_x_Cload {}

$^{F}x_{C_{load}}$ Configured center of mass of the external load with respect to flange frame.

◆ F_x_Ctotal

Eigen::Vector3d franky::RobotState::F_x_Ctotal {}

$^{F}x_{C_{total}}$ Combined center of mass of the end effector load and the external load with respect to flange frame.

◆ I_ee

IntertiaMatrix franky::RobotState::I_ee {}

$I_{EE}$ Configured rotational inertia matrix of the end effector load with respect to center of mass.

◆ I_load

IntertiaMatrix franky::RobotState::I_load {}

$I_{load}$ Configured rotational inertia matrix of the external load with respect to center of mass.

◆ I_total

IntertiaMatrix franky::RobotState::I_total {}

$I_{total}$ Combined rotational inertia matrix of the end effector load and the external load with respect to the center of mass.

◆ joint_collision

Vector7d franky::RobotState::joint_collision {}

Indicates which contact level is activated in which joint. After contact disappears, the value stays the same until a reset command is sent.

See also
Robot::setCollisionBehavior for setting sensitivity values.
Robot::automaticErrorRecovery for performing a reset after a collision.

◆ joint_contact

Vector7d franky::RobotState::joint_contact {}

Indicates which contact level is activated in which joint. After contact disappears, value turns to zero.

See also
Robot::setCollisionBehavior for setting sensitivity values.

◆ K_F_ext_hat_K

Vector6d franky::RobotState::K_F_ext_hat_K {}

$^{K}F_{K,\text{ext}}$ Estimated external wrench (force, torque) acting on stiffness frame, expressed relative to the stiffness frame. Forces applied by the robot to the environment are positive, while forces applied by the environment on the robot are negative. Becomes $[0,0,0,0,0,0]$ when near or in a singularity. See also Stiffness frame K. Unit: $[N,N,N,Nm,Nm,Nm]$.

◆ last_motion_errors

franka::Errors franky::RobotState::last_motion_errors {}

Contains the errors that aborted the previous motion.

◆ m_ee

double franky::RobotState::m_ee {}

$m_{EE}$ Configured mass of the end effector.

◆ m_load

double franky::RobotState::m_load {}

$m_{load}$ Configured mass of the external load.

◆ m_total

double franky::RobotState::m_total {}

$m_{total}$ Sum of the mass of the end effector and the external load.

◆ O_ddP_EE_c

TwistAcceleration franky::RobotState::O_ddP_EE_c {}

${^OddP_{EE}}_{c}$ Last commanded end effector acceleration in base frame. Unit: $[\frac{m}{s^2},\frac{m}{s^2},\frac{m}{s^2},\frac{rad}{s^2},\frac{rad}{s^2},\frac{rad}{s^2}]$.

◆ O_ddP_EE_est

std::optional<TwistAcceleration> franky::RobotState::O_ddP_EE_est {}

Estimated end-effector spatial acceleration (linear and angular acceleration) expressed in base frame. Computed by franky; not provided by franka firmware. Unit: $[\frac{m}{s^2},\frac{m}{s^2},\frac{m}{s^2},\frac{rad}{s^2},\frac{rad}{s^2},\frac{rad}{s^2}]$.

◆ O_dP_EE_c

Twist franky::RobotState::O_dP_EE_c {}

${^OdP_{EE}}_{c}$ Last commanded end effector twist in base frame.

◆ O_dP_EE_d

Twist franky::RobotState::O_dP_EE_d {}

${^OdP_{EE}}_{d}$ Desired end effector twist in base frame. Unit: $[\frac{m}{s},\frac{m}{s},\frac{m}{s},\frac{rad}{s},\frac{rad}{s},\frac{rad}{s}]$.

◆ O_dP_EE_est

std::optional<Twist> franky::RobotState::O_dP_EE_est {}

Estimated end-effector twist (linear and angular velocity) expressed in base frame. Computed by franky; not provided by franka firmware. Unit: $[\frac{m}{s},\frac{m}{s},\frac{m}{s},\frac{rad}{s},\frac{rad}{s},\frac{rad}{s}]$.

◆ O_F_ext_hat_K

Vector6d franky::RobotState::O_F_ext_hat_K {}

$^OF_{K,\text{ext}}$ Estimated external wrench (force, torque) acting on stiffness frame, expressed relative to the base frame. Forces applied by the robot to the environment are positive, while forces applied by the environment on the robot are negative. Becomes $[0,0,0,0,0,0]$ when near or in a singularity. See also Stiffness frame K. Unit: $[N,N,N,Nm,Nm,Nm]$.

◆ O_T_EE

Affine franky::RobotState::O_T_EE {}

$^{O}T_{EE}$ Measured end effector pose in base frame.

◆ O_T_EE_c

Affine franky::RobotState::O_T_EE_c {}

${^OT_{EE}}_{c}$ Last commanded end effector pose of motion generation in base frame.

◆ O_T_EE_d

Affine franky::RobotState::O_T_EE_d {}

${^OT_{EE}}_{d}$ Last desired end effector pose of motion generation in base frame.

◆ q

Vector7d franky::RobotState::q {}

$q$ Measured joint position. Unit: $[rad]$

◆ q_d

Vector7d franky::RobotState::q_d {}

$q_d$ Desired joint position. Unit: $[rad]$

◆ robot_mode

franka::RobotMode franky::RobotState::robot_mode = franka::RobotMode::kUserStopped

Current robot mode.

◆ tau_ext_hat_filtered

Vector7d franky::RobotState::tau_ext_hat_filtered {}

$\hat{\tau}_{\text{ext}}$ Low-pass filtered torques generated by external forces on the joints. It does not include configured end-effector and load nor the mass and dynamics of the robot. tau_ext_hat_filtered is the error between tau_J and the expected torques given by the robot model. Unit: $[Nm]$.

◆ tau_J

Vector7d franky::RobotState::tau_J {}

$\tau_{J}$ Measured link-side joint torque sensor signals. Unit: $[Nm]$

◆ tau_J_d

Vector7d franky::RobotState::tau_J_d {}

${\tau_J}_d$ Desired link-side joint torque sensor signals without gravity. Unit: $[Nm]$

◆ theta

Vector7d franky::RobotState::theta {}

$\theta$ Motor position. Unit: $[rad]$

◆ time

franka::Duration franky::RobotState::time {}

Strictly monotonically increasing timestamp since robot start.

Inside of control loops time_step parameter of Robot::control can be used instead.


The documentation for this struct was generated from the following files: