Struct RobotState
Defined in File robot_state.h
Struct Documentation
-
struct RobotState
Describes the robot state.
Public Members
-
std::array<double, 16> O_T_EE = {}
Measured end effector pose in base frame. Pose is represented as a 4x4 matrix in column-major format.
-
std::array<double, 16> O_T_EE_d = {}
Last desired end effector pose of motion generation in base frame. Pose is represented as a 4x4 matrix in column-major format.
-
std::array<double, 16> F_T_EE = {}
End effector frame pose in flange frame. Pose is represented as a 4x4 matrix in column-major format.See also
See also
See also
Robot for an explanation of the F, NE and EE frames.
-
std::array<double, 16> F_T_NE = {}
Nominal end effector frame pose in flange frame. Pose is represented as a 4x4 matrix in column-major format.See also
See also
See also
Robot for an explanation of the F, NE and EE frames.
-
std::array<double, 16> 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.
See also
See also
See also
Robot for an explanation of the F, NE and EE frames.
-
std::array<double, 16> 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.
-
double m_ee = {}
Configured mass of the end effector.
-
std::array<double, 9> I_ee = {}
Configured rotational inertia matrix of the end effector load with respect to center of mass.
-
std::array<double, 3> F_x_Cee = {}
Configured center of mass of the end effector load with respect to flange frame.
-
double m_load = {}
Configured mass of the external load.
-
std::array<double, 9> I_load = {}
Configured rotational inertia matrix of the external load with respect to center of mass.
-
std::array<double, 3> F_x_Cload = {}
Configured center of mass of the external load with respect to flange frame.
-
double m_total = {}
Sum of the mass of the end effector and the external load.
-
std::array<double, 9> 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 = {}
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.
The values of the array are:
elbow[0]: Position of the 3rd joint in
.elbow[1]: Flip direction of the elbow (4th joint):
+1 if
0 if
-1 if
with
as specified in the robot interface specification page in the FCI Documentation.
-
std::array<double, 2> elbow_d = {}
Desired elbow configuration.
The values of the array are:
elbow_d[0]: Position of the 3rd joint in
.elbow_d[1]: Flip direction of the elbow (4th joint):
+1 if
0 if
-1 if
with
as specified in the robot interface specification page in the FCI Documentation.
-
std::array<double, 2> elbow_c = {}
Commanded elbow configuration.
The values of the array are:
elbow_c[0]: Position of the 3rd joint in
.elbow_c[1]: Flip direction of the elbow (4th joint):
+1 if
0 if
-1 if
with
as specified in the robot interface specification page in the FCI Documentation.
-
std::array<double, 2> delbow_c = {}
Commanded elbow velocity.
The values of the array are:
delbow_c[0] Velocity of the 3rd joint in
delbow_c[1] is always 0.
-
std::array<double, 2> ddelbow_c = {}
Commanded elbow acceleration.
The values of the array are:
ddelbow_c[0] Acceleration of the 3rd joint in
ddelbow_c[1] is always 0.
-
std::array<double, 7> tau_J = {}
Measured link-side joint torque sensor signals. Unit:
-
std::array<double, 7> tau_J_d = {}
Desired link-side joint torque sensor signals without gravity. Unit:
-
std::array<double, 7> dtau_J = {}
Derivative of measured link-side joint torque sensor signals. Unit:
-
std::array<double, 7> q = {}
Measured joint position. Unit:
-
std::array<double, 7> q_d = {}
Desired joint position. Unit:
-
std::array<double, 7> dq = {}
Measured joint velocity. Unit:
-
std::array<double, 7> dq_d = {}
Desired joint velocity. Unit:
-
std::array<double, 7> ddq_d = {}
Desired joint acceleration. Unit:
-
std::array<double, 7> 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.
-
std::array<double, 6> cartesian_contact = {}
Indicates which contact level is activated in which Cartesian dimension
. After contact disappears, the value turns to zero.See also
Robot::setCollisionBehavior for setting sensitivity values.
-
std::array<double, 7> 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.
See also
Robot::automaticErrorRecovery for performing a reset after a collision.
-
std::array<double, 6> cartesian_collision = {}
Indicates which contact level is activated in which Cartesian dimension
. After contact disappears, the value stays the same until a reset command is sent.See also
Robot::setCollisionBehavior for setting sensitivity values.
See also
Robot::automaticErrorRecovery for performing a reset after a collision.
-
std::array<double, 7> tau_ext_hat_filtered = {}
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: .
-
std::array<double, 6> O_F_ext_hat_K = {}
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 when near or in a singularity. See also Stiffness frame K. Unit: .
-
std::array<double, 6> K_F_ext_hat_K = {}
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 when near or in a singularity. See also Stiffness frame K. Unit: .
-
std::array<double, 6> O_dP_EE_d = {}
Desired end effector twist in base frame. Unit: .
-
std::array<double, 3> O_ddP_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}
.
-
std::array<double, 16> O_T_EE_c = {}
Last commanded end effector pose of motion generation in base frame. Pose is represented as a 4x4 matrix in column-major format.
-
std::array<double, 6> O_dP_EE_c = {}
Last commanded end effector twist in base frame. Unit: .
-
std::array<double, 6> O_ddP_EE_c = {}
Last commanded end effector acceleration in base frame. Unit: .
-
std::array<double, 7> theta = {}
Motor position. Unit:
-
std::array<double, 7> dtheta = {}
Motor velocity. Unit:
-
double 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:
.
-
RobotMode robot_mode = RobotMode::kUserStopped
Current robot mode.
-
Duration time = {}
Strictly monotonically increasing timestamp since robot start.
Inside of control loops time_step parameter of Robot::control can be used instead.
-
std::array<double, 16> O_T_EE = {}