libfranka 0.15.0
FCI C++ API
Loading...
Searching...
No Matches
Public Attributes | List of all members
franka::RobotState Struct Reference

Describes the robot state. More...

#include <robot_state.h>

Collaboration diagram for franka::RobotState:
Collaboration graph
[legend]

Public Attributes

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

Detailed Description

Describes the robot state.

Examples
cartesian_impedance_control.cpp, communication_test.cpp, echo_robot_state.cpp, force_control.cpp, generate_cartesian_pose_motion.cpp, generate_cartesian_pose_motion_external_control_loop.cpp, generate_cartesian_velocity_motion.cpp, generate_cartesian_velocity_motion_external_control_loop.cpp, generate_consecutive_motions.cpp, generate_elbow_motion.cpp, generate_joint_position_motion.cpp, generate_joint_position_motion_external_control_loop.cpp, generate_joint_velocity_motion.cpp, generate_joint_velocity_motion_external_control_loop.cpp, joint_impedance_control.cpp, motion_with_control.cpp, motion_with_control_external_control_loop.cpp, and print_joint_poses.cpp.

Member Data Documentation

◆ cartesian_collision

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.

◆ cartesian_contact

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.

◆ control_command_success_rate

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]\).

Examples
communication_test.cpp.

◆ ddelbow_c

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

Commanded elbow acceleration.

The values of the array are:

  • ddelbow_c[0] Acceleration of the 3rd joint in \(\frac{rad}{s^2}\)
  • ddelbow_c[1] is always 0.

◆ ddq_d

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

\(\ddot{q}_d\) Desired joint acceleration.

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

◆ delbow_c

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

Commanded elbow velocity.

The values of the array are:

  • delbow_c[0] Velocity of the 3rd joint in \(\frac{rad}{s}\)
  • delbow_c[1] is always 0.

◆ dq

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

\(\dot{q}\) Measured joint velocity.

Unit: \([\frac{rad}{s}]\)

Examples
cartesian_impedance_control.cpp, motion_with_control.cpp, and motion_with_control_external_control_loop.cpp.

◆ dq_d

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

\(\dot{q}_d\) Desired joint velocity.

Unit: \([\frac{rad}{s}]\)

◆ dtau_J

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

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

Unit: \([\frac{Nm}{s}]\)

◆ dtheta

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

\(\dot{\theta}\) Motor velocity.

Unit: \([\frac{rad}{s}]\)

◆ EE_T_K

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.

◆ elbow

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

Elbow configuration.

The values of the array are:

  • elbow[0]: Position of the 3rd joint in \([rad]\).
  • elbow[1]: Flip direction of the elbow (4th joint):
    • +1 if \(q_4 > q_{elbow-flip}\)
    • 0 if \(q_4 == q_{elbow-flip} \)
    • -1 if \(q_4 < q_{elbow-flip} \)
    with \(q_{elbow-flip}\) as specified in the robot interface specification page in the FCI Documentation.
Examples
generate_elbow_motion.cpp.

◆ elbow_c

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

Commanded elbow configuration.

The values of the array are:

  • elbow_c[0]: Position of the 3rd joint in \([rad]\).
  • elbow_c[1]: Flip direction of the elbow (4th joint):
    • +1 if \(q_4 > q_{elbow-flip}\)
    • 0 if \(q_4 == q_{elbow-flip} \)
    • -1 if \(q_4 < q_{elbow-flip} \)
    with \(q_{elbow-flip}\) as specified in the robot interface specification page in the FCI Documentation.

◆ elbow_d

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

Desired elbow configuration.

The values of the array are:

  • elbow_d[0]: Position of the 3rd joint in \([rad]\).
  • elbow_d[1]: Flip direction of the elbow (4th joint):
    • +1 if \(q_4 > q_{elbow-flip}\)
    • 0 if \(q_4 == q_{elbow-flip} \)
    • -1 if \(q_4 < q_{elbow-flip} \)
    with \(q_{elbow-flip}\) as specified in the robot interface specification page in the FCI Documentation.

◆ F_T_EE

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.

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

◆ F_T_NE

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

\(^{F}T_{NE}\) Nominal end effector frame pose in flange frame.

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

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

◆ joint_collision

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.

◆ joint_contact

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.

◆ K_F_ext_hat_K

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.

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]\).

◆ NE_T_EE

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

\(^{NE}T_{EE}\) End effector frame pose in nominal end effector frame.

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

See also
Robot::setEE to change this frame.
F_T_EE
F_T_NE
Robot for an explanation of the F, NE and EE frames.

◆ O_ddP_EE_c

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}]\).

◆ O_ddP_O

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

\({^OddP}_O\) 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 harcoded for now to {0, 0, -9.81}.

◆ O_dP_EE_c

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}]\).

◆ O_dP_EE_d

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}]\).

◆ O_F_ext_hat_K

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.

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

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.

Examples
cartesian_impedance_control.cpp, generate_cartesian_pose_motion.cpp, and generate_elbow_motion.cpp.

◆ O_T_EE_c

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.

◆ O_T_EE_d

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.

◆ q

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

◆ q_d

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

\(q_d\) Desired joint position.

Unit: \([rad]\)

Examples
motion_with_control.cpp, and motion_with_control_external_control_loop.cpp.

◆ tau_ext_hat_filtered

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

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

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

Unit: \([Nm]\)

Examples
force_control.cpp.

◆ tau_J_d

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

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

Unit: \([Nm]\)

◆ theta

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

\(\theta\) Motor position.

Unit: \([rad]\)

◆ time

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.


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