Public Attributes | List of all members
franka::RobotState Struct Reference

Describes the robot state. More...

#include <robot_state.h>

Public Attributes

std::array< double, 6 > cartesian_collision {}
 Indicates which contact level is activated in which Cartesian dimension $(x,y,z,R,P,Y)$. More...
 
std::array< double, 6 > cartesian_contact {}
 Indicates which contact level is activated in which Cartesian dimension $(x,y,z,R,P,Y)$. More...
 
double control_command_success_rate {}
 Percentage of the last 100 control commands that were successfully received by the robot. More...
 
Errors current_errors {}
 Current error state. More...
 
std::array< double, 2 > ddelbow_c {}
 Commanded elbow acceleration. More...
 
std::array< double, 7 > ddq_d {}
 $\dot{q}_d$ Desired joint acceleration. More...
 
std::array< double, 2 > delbow_c {}
 Commanded elbow velocity. More...
 
std::array< double, 7 > dq {}
 $\dot{q}$ Measured joint velocity. More...
 
std::array< double, 7 > dq_d {}
 $\dot{q}_d$ Desired joint velocity. More...
 
std::array< double, 7 > dtau_J {}
 $\dot{\tau_{J}}$ Derivative of measured link-side joint torque sensor signals. More...
 
std::array< double, 7 > dtheta {}
 $\dot{\theta}$ Motor velocity. More...
 
std::array< double, 16 > EE_T_K {}
 $^{EE}T_{K}$ Stiffness frame pose in end effector frame. More...
 
std::array< double, 2 > elbow {}
 Elbow configuration. More...
 
std::array< double, 2 > elbow_c {}
 Commanded elbow configuration. More...
 
std::array< double, 2 > elbow_d {}
 Desired elbow configuration. More...
 
std::array< double, 16 > F_T_EE {}
 $^{F}T_{EE}$ End effector frame pose in flange frame. More...
 
std::array< double, 3 > F_x_Cee {}
 $^{F}x_{C_{EE}}$ Configured center of mass of the end effector load with respect to flange frame. More...
 
std::array< double, 3 > F_x_Cload {}
 $^{F}x_{C_{load}}$ Configured center of mass of the external load with respect to flange frame. More...
 
std::array< double, 3 > 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. More...
 
std::array< double, 9 > I_ee {}
 $I_{EE}$ Configured rotational inertia matrix of the end effector load with respect to center of mass. More...
 
std::array< double, 9 > I_load {}
 $I_{load}$ Configured rotational inertia matrix of the external load with respect to center of mass. More...
 
std::array< double, 9 > I_total {}
 $I_{total}$ Combined rotational inertia matrix of the end effector load and the external load with respect to the center of mass. More...
 
std::array< double, 7 > joint_collision {}
 Indicates which contact level is activated in which joint. More...
 
std::array< double, 7 > joint_contact {}
 Indicates which contact level is activated in which joint. More...
 
std::array< double, 6 > 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. More...
 
Errors last_motion_errors {}
 Contains the errors that aborted the previous motion. More...
 
double m_ee {}
 $m_{EE}$ Configured mass of the end effector. More...
 
double m_load {}
 $m_{load}$ Configured mass of the external load. More...
 
double m_total {}
 $m_{total}$ Sum of the mass of the end effector and the external load. More...
 
std::array< double, 6 > O_ddP_EE_c {}
 ${^OddP_{EE}}_{c}$ Last commanded end effector acceleration in base frame. More...
 
std::array< double, 6 > O_dP_EE_c {}
 ${^OdP_{EE}}_{c}$ Last commanded end effector twist in base frame. More...
 
std::array< double, 6 > O_dP_EE_d {}
 ${^OdP_{EE}}_{d}$ Desired end effector twist in base frame. More...
 
std::array< double, 6 > O_F_ext_hat_K {}
 $^OF_{K,\text{ext}}$ Estimated external wrench (force, torque) acting on stiffness frame, expressed relative to the base frame. More...
 
std::array< double, 16 > O_T_EE {}
 $^{O}T_{EE}$ Measured end effector pose in base frame. More...
 
std::array< double, 16 > O_T_EE_c {}
 ${^OT_{EE}}_{c}$ Last commanded end effector pose of motion generation in base frame. More...
 
std::array< double, 16 > O_T_EE_d {}
 ${^OT_{EE}}_{d}$ Last desired end effector pose of motion generation in base frame. More...
 
std::array< double, 7 > q {}
 $q$ Measured joint position. More...
 
std::array< double, 7 > q_d {}
 $q_d$ Desired joint position. More...
 
RobotMode robot_mode = RobotMode::kUserStopped
 Current robot mode. More...
 
std::array< double, 7 > tau_ext_hat_filtered {}
 $\hat{\tau}_{\text{ext}}$ External torque, filtered. More...
 
std::array< double, 7 > tau_J {}
 $\tau_{J}$ Measured link-side joint torque sensor signals. More...
 
std::array< double, 7 > tau_J_d {}
 ${\tau_J}_d$ Desired link-side joint torque sensor signals without gravity. More...
 
std::array< double, 7 > theta {}
 $\theta$ Motor position. More...
 
Duration time {}
 Strictly monotonically increasing timestamp since robot start. More...
 

Detailed Description

Describes the robot state.

Definition at line 35 of file robot_state.h.

Member Data Documentation

std::array<double, 6> franka::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.

Definition at line 247 of file robot_state.h.

std::array<double, 6> franka::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.

Definition at line 229 of file robot_state.h.

double franka::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]$.

Definition at line 329 of file robot_state.h.

Errors franka::RobotState::current_errors {}

Current error state.

Definition at line 315 of file robot_state.h.

std::array<double, 2> franka::RobotState::ddelbow_c {}

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.

Definition at line 165 of file robot_state.h.

std::array<double, 7> franka::RobotState::ddq_d {}

$\dot{q}_d$ Desired joint acceleration.

Unit: $[\frac{rad}{s^2}]$

Definition at line 213 of file robot_state.h.

std::array<double, 2> franka::RobotState::delbow_c {}

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.

Definition at line 156 of file robot_state.h.

std::array<double, 7> franka::RobotState::dq {}

$\dot{q}$ Measured joint velocity.

Unit: $[\frac{rad}{s}]$

Definition at line 201 of file robot_state.h.

std::array<double, 7> franka::RobotState::dq_d {}

$\dot{q}_d$ Desired joint velocity.

Unit: $[\frac{rad}{s}]$

Definition at line 207 of file robot_state.h.

std::array<double, 7> franka::RobotState::dtau_J {}

$\dot{\tau_{J}}$ Derivative of measured link-side joint torque sensor signals.

Unit: $[\frac{Nm}{s}]$

Definition at line 183 of file robot_state.h.

std::array<double, 7> franka::RobotState::dtheta {}

$\dot{\theta}$ Motor velocity.

Unit: $[rad]$

Definition at line 310 of file robot_state.h.

std::array<double, 16> franka::RobotState::EE_T_K {}

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

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

See also K frame.

Definition at line 64 of file robot_state.h.

std::array<double, 2> franka::RobotState::elbow {}

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.

Definition at line 129 of file robot_state.h.

std::array<double, 2> franka::RobotState::elbow_c {}

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.

Definition at line 147 of file robot_state.h.

std::array<double, 2> franka::RobotState::elbow_d {}

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.

Definition at line 138 of file robot_state.h.

std::array<double, 16> franka::RobotState::F_T_EE {}

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

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

Definition at line 55 of file robot_state.h.

std::array<double, 3> franka::RobotState::F_x_Cee {}

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

Definition at line 82 of file robot_state.h.

std::array<double, 3> franka::RobotState::F_x_Cload {}

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

Definition at line 100 of file robot_state.h.

std::array<double, 3> franka::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.

Definition at line 120 of file robot_state.h.

std::array<double, 9> franka::RobotState::I_ee {}

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

Definition at line 76 of file robot_state.h.

std::array<double, 9> franka::RobotState::I_load {}

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

Definition at line 94 of file robot_state.h.

std::array<double, 9> franka::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.

Definition at line 113 of file robot_state.h.

std::array<double, 7> franka::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.

Definition at line 238 of file robot_state.h.

std::array<double, 7> franka::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.

Definition at line 221 of file robot_state.h.

std::array<double, 6> franka::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.

See also K frame. Unit: $[N,N,N,Nm,Nm,Nm]$.

Definition at line 269 of file robot_state.h.

Errors franka::RobotState::last_motion_errors {}

Contains the errors that aborted the previous motion.

Definition at line 320 of file robot_state.h.

double franka::RobotState::m_ee {}

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

Definition at line 70 of file robot_state.h.

double franka::RobotState::m_load {}

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

Definition at line 88 of file robot_state.h.

double franka::RobotState::m_total {}

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

Definition at line 106 of file robot_state.h.

std::array<double, 6> franka::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}]$.

Definition at line 298 of file robot_state.h.

std::array<double, 6> franka::RobotState::O_dP_EE_c {}

${^OdP_{EE}}_{c}$ Last commanded 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}]$.

Definition at line 290 of file robot_state.h.

std::array<double, 6> franka::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}]$.

Definition at line 276 of file robot_state.h.

std::array<double, 6> franka::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.

See also K frame. Unit: $[N,N,N,Nm,Nm,Nm]$.

Definition at line 261 of file robot_state.h.

std::array<double, 16> franka::RobotState::O_T_EE {}

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

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

Definition at line 41 of file robot_state.h.

std::array<double, 16> franka::RobotState::O_T_EE_c {}

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

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

Definition at line 283 of file robot_state.h.

std::array<double, 16> franka::RobotState::O_T_EE_d {}

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

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

Definition at line 48 of file robot_state.h.

std::array<double, 7> franka::RobotState::q {}

$q$ Measured joint position.

Unit: $[rad]$

Definition at line 189 of file robot_state.h.

std::array<double, 7> franka::RobotState::q_d {}

$q_d$ Desired joint position.

Unit: $[rad]$

Definition at line 195 of file robot_state.h.

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

Current robot mode.

Definition at line 334 of file robot_state.h.

std::array<double, 7> franka::RobotState::tau_ext_hat_filtered {}

$\hat{\tau}_{\text{ext}}$ External torque, filtered.

Unit: $[Nm]$.

Definition at line 253 of file robot_state.h.

std::array<double, 7> franka::RobotState::tau_J {}

$\tau_{J}$ Measured link-side joint torque sensor signals.

Unit: $[Nm]$

Definition at line 171 of file robot_state.h.

std::array<double, 7> franka::RobotState::tau_J_d {}

${\tau_J}_d$ Desired link-side joint torque sensor signals without gravity.

Unit: $[Nm]$

Definition at line 177 of file robot_state.h.

std::array<double, 7> franka::RobotState::theta {}

$\theta$ Motor position.

Unit: $[rad]$

Definition at line 304 of file robot_state.h.

Duration franka::RobotState::time {}

Strictly monotonically increasing timestamp since robot start.

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

Definition at line 342 of file robot_state.h.


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


libfranka
Author(s): Franka Emika GmbH
autogenerated on Tue Jul 9 2019 03:32:01