Robot State#
Robot state information including joint positions, velocities, torques, and Cartesian poses.
RobotState Class#
- class pylibfranka.RobotState#
Bases:
pybind11_objectCurrent state of the Franka robot.
Contains all robot state information including joint positions, velocities, torques, Cartesian poses, and error states. All arrays are NumPy arrays.
- property EE_T_K#
- property F_T_EE#
- property F_T_NE#
- property F_x_Cee#
- property F_x_Cload#
- property F_x_Ctotal#
- property I_ee#
- property I_load#
- property I_total#
- property K_F_ext_hat_K#
- property NE_T_EE#
- property O_F_ext_hat_K#
- property O_T_EE#
- property O_T_EE_c#
- property O_T_EE_d#
- property O_dP_EE_c#
- property O_dP_EE_d#
- property O_ddP_EE_c#
- property O_ddP_O#
- property cartesian_collision#
- property cartesian_contact#
- property control_command_success_rate#
- property current_errors#
- property ddelbow_c#
- property ddq_d#
- property delbow_c#
- property dq#
- property dq_d#
- property dtau_J#
- property dtheta#
- property elbow#
- property elbow_c#
- property elbow_d#
- property joint_collision#
- property joint_contact#
- property last_motion_errors#
- property m_ee#
- property m_load#
- property m_total#
- property q#
- property q_d#
- property robot_mode#
- property tau_J#
- property tau_J_d#
- property tau_ext_hat_filtered#
- property theta#
- property time#
The RobotState contains the complete state of the Franka robot at a given time instant.
All arrays are NumPy arrays for seamless integration with scientific Python libraries.
Obtaining Robot State#
Robot state can be obtained in two ways:
Outside control loop: Use
Robot.read_once()Inside control loop: Use
ActiveControlBase.readOnce()
Example:
import pylibfranka
robot = pylibfranka.Robot("172.16.0.2")
# Method 1: Read once outside control loop
state = robot.read_once()
print("Joint positions:", state.q)
# Method 2: Inside control loop
control = robot.start_torque_control()
state, duration = control.readOnce()
State Attributes#
Joint State#
- RobotState.q: numpy.ndarray
Measured joint positions [rad] (7,)
Example:
state = robot.read_once() print("Joint 1 position:", state.q[0], "rad")
- RobotState.q_d: numpy.ndarray
Desired joint positions [rad] (7,)
Last commanded position from motion generator.
- RobotState.dq: numpy.ndarray
Measured joint velocities [rad/s] (7,)
- RobotState.dq_d: numpy.ndarray
Desired joint velocities [rad/s] (7,)
- RobotState.ddq_d: numpy.ndarray
Desired joint accelerations [rad/s²] (7,)
Joint Torques#
- RobotState.tau_J: numpy.ndarray
Measured link-side joint torques [Nm] (7,)
These are the torques measured at the joints including friction.
- RobotState.tau_J_d: numpy.ndarray
Desired link-side joint torques [Nm] (7,)
Last commanded torques from controller.
- RobotState.dtau_J: numpy.ndarray
Derivative of measured link-side joint torques [Nm/s] (7,)
- RobotState.tau_ext_hat_filtered: numpy.ndarray
External torque estimate (filtered) [Nm] (7,)
Estimated external torques acting on the robot, low-pass filtered. Useful for contact detection and force sensing.
Example:
state = robot.read_once() ext_torque = state.tau_ext_hat_filtered if np.linalg.norm(ext_torque) > 5.0: print("External contact detected!")
Motor State#
- RobotState.theta: numpy.ndarray
Motor positions [rad] (7,)
- RobotState.dtheta: numpy.ndarray
Motor velocities [rad/s] (7,)
End Effector Poses#
- RobotState.O_T_EE: numpy.ndarray
End effector pose in base frame \(^OT_{EE}\) (16,)
Homogeneous transformation matrix (4×4) in column-major format.
Example:
import numpy as np state = robot.read_once() # Convert to 4×4 matrix O_T_EE = state.O_T_EE.reshape(4, 4).T position = O_T_EE[:3, 3] rotation = O_T_EE[:3, :3] print("End-effector position [m]:", position) print("End-effector rotation:\n", rotation)
- RobotState.O_T_EE_d: numpy.ndarray
Desired end effector pose in base frame \(^OT_{EE}^d\) (16,)
- RobotState.O_T_EE_c: numpy.ndarray
Commanded end effector pose in base frame \(^OT_{EE}^c\) (16,)
- RobotState.F_T_EE: numpy.ndarray
End effector pose in flange frame \(^FT_{EE}\) (16,)
Set via
Robot.set_EE()
- RobotState.F_T_NE: numpy.ndarray
Nominal end effector pose in flange frame \(^FT_{NE}\) (16,)
- RobotState.NE_T_EE: numpy.ndarray
End effector pose in nominal end effector frame \(^{NE}T_{EE}\) (16,)
- RobotState.EE_T_K: numpy.ndarray
Stiffness frame pose in end effector frame \(^{EE}T_K\) (16,)
Set via
Robot.set_K()
Inertial Properties#
- RobotState.m_ee: float
End effector mass [kg]
- RobotState.I_ee: numpy.ndarray
End effector inertia tensor [kg·m²] (9,)
Column-major 3×3 inertia matrix.
- RobotState.F_x_Cee: numpy.ndarray
Center of mass of end effector in flange frame [m] (3,)
- RobotState.m_load: float
External load mass [kg]
Set via
Robot.set_load()
- RobotState.I_load: numpy.ndarray
External load inertia tensor [kg·m²] (9,)
- RobotState.F_x_Cload: numpy.ndarray
Center of mass of external load in flange frame [m] (3,)
- RobotState.m_total: float
Total mass (end effector + load) [kg]
- RobotState.I_total: numpy.ndarray
Total inertia tensor [kg·m²] (9,)
- RobotState.F_x_Ctotal: numpy.ndarray
Total center of mass in flange frame [m] (3,)
Elbow Configuration#
- RobotState.elbow: numpy.ndarray
Current elbow configuration (2,)
- RobotState.elbow_d: numpy.ndarray
Desired elbow configuration (2,)
- RobotState.elbow_c: numpy.ndarray
Commanded elbow configuration (2,)
- RobotState.delbow_c: numpy.ndarray
Commanded elbow velocity (2,)
- RobotState.ddelbow_c: numpy.ndarray
Commanded elbow acceleration (2,)
Collision and Contact#
- RobotState.joint_contact: numpy.ndarray
Joint-level contact detection flags (7,)
True if contact detected at corresponding joint.
- RobotState.cartesian_contact: numpy.ndarray
Cartesian contact detection flags (6,)
Contact in (x, y, z, roll, pitch, yaw).
- RobotState.joint_collision: numpy.ndarray
Joint-level collision detection flags (7,)
- RobotState.cartesian_collision: numpy.ndarray
Cartesian collision detection flags (6,)
External Forces#
- RobotState.O_F_ext_hat_K: numpy.ndarray
External wrench in stiffness frame, expressed in base frame [N, Nm] (6,)
Format: [fx, fy, fz, τx, τy, τz]
- RobotState.K_F_ext_hat_K: numpy.ndarray
External wrench in stiffness frame [N, Nm] (6,)
End Effector Velocity#
- RobotState.O_dP_EE_d: numpy.ndarray
Desired end effector twist in base frame [m/s, rad/s] (6,)
Format: [vx, vy, vz, ωx, ωy, ωz]
- RobotState.O_dP_EE_c: numpy.ndarray
Commanded end effector twist in base frame [m/s, rad/s] (6,)
- RobotState.O_ddP_EE_c: numpy.ndarray
Commanded end effector acceleration in base frame [m/s², rad/s²] (6,)
- RobotState.O_ddP_O: numpy.ndarray
Base acceleration [m/s², rad/s²] (6,)
Error and Mode#
- RobotState.current_errors: Errors
Current robot errors
Example:
state = robot.read_once() if state.current_errors: print("Active errors:", state.current_errors)
- RobotState.last_motion_errors: Errors
Errors from last motion
- RobotState.control_command_success_rate: float
Success rate of control commands [0.0, 1.0]
Indicates the percentage of successfully received control commands.
- RobotState.robot_mode: RobotMode
Current robot operating mode
- RobotState.time: Duration
Timestamp of the state
Errors Class#
- class pylibfranka.Errors#
Bases:
pybind11_objectRobot error state containing boolean flags for all possible errors.
- property base_acceleration_initialization_timeout#
- property base_acceleration_invalid_reading#
- property cartesian_motion_generator_acceleration_discontinuity#
- property cartesian_motion_generator_elbow_limit_violation#
- property cartesian_motion_generator_elbow_sign_inconsistent#
- property cartesian_motion_generator_joint_acceleration_discontinuity#
- property cartesian_motion_generator_joint_position_limits_violation#
- property cartesian_motion_generator_joint_velocity_discontinuity#
- property cartesian_motion_generator_joint_velocity_limits_violation#
- property cartesian_motion_generator_start_elbow_invalid#
- property cartesian_motion_generator_velocity_discontinuity#
- property cartesian_motion_generator_velocity_limits_violation#
- property cartesian_position_limits_violation#
- property cartesian_position_motion_generator_invalid_frame#
- property cartesian_position_motion_generator_start_pose_invalid#
- property cartesian_reflex#
- property cartesian_spline_motion_generator_violation#
- property cartesian_velocity_profile_safety_violation#
- property cartesian_velocity_violation#
- property communication_constraints_violation#
- property controller_torque_discontinuity#
- property force_control_safety_violation#
- property force_controller_desired_force_tolerance_violation#
- property instability_detected#
- property joint_motion_generator_acceleration_discontinuity#
- property joint_motion_generator_position_limits_violation#
- property joint_motion_generator_velocity_discontinuity#
- property joint_motion_generator_velocity_limits_violation#
- property joint_move_in_wrong_direction#
- property joint_p2p_insufficient_torque_for_planning#
- property joint_position_limits_violation#
- property joint_position_motion_generator_start_pose_invalid#
- property joint_reflex#
- property joint_velocity_violation#
- property joint_via_motion_generator_planning_joint_limit_violation#
- property max_goal_pose_deviation_violation#
- property max_path_pose_deviation_violation#
- property power_limit_violation#
- property self_collision_avoidance_violation#
- property start_elbow_sign_inconsistent#
- property tau_j_range_violation#
The Errors class contains boolean flags for all possible robot errors.
Methods#
- Errors.__bool__()#
Check if any error is present.
- Returns:
True if any error flag is set
- Return type:
Example:
state = robot.read_once() if state.current_errors: print("Robot has errors!") print(state.current_errors)
Error Attributes#
The Errors class has numerous boolean attributes for different error conditions. Key attributes include:
joint_position_limits_violationcartesian_position_limits_violationself_collision_avoidance_violationjoint_velocity_violationcartesian_velocity_violationforce_control_safety_violationjoint_reflexcartesian_reflexcommunication_constraints_violationpower_limit_violationinstability_detected
See the full list in the source code or via autocompletion.
Example:
state = robot.read_once()
errors = state.current_errors
if errors.joint_position_limits_violation:
print("Joint position limit violated!")
if errors.cartesian_reflex:
print("Cartesian reflex triggered!")
RobotMode Enum#
- class pylibfranka.RobotMode#
Bases:
pybind11_objectRobot operating mode.
Members:
Other : Other mode
Idle : Idle mode
Move : Move mode
Guiding : Guiding mode
Reflex : Reflex mode
UserStopped : User stopped mode
AutomaticErrorRecovery : Automatic error recovery mode
- AutomaticErrorRecovery = RobotMode.AutomaticErrorRecovery#
- Guiding = RobotMode.Guiding#
- Idle = RobotMode.Idle#
- Move = RobotMode.Move#
- Other = RobotMode.Other#
- Reflex = RobotMode.Reflex#
- UserStopped = RobotMode.UserStopped#
- property name#
(self: handle) -> str
Operating mode of the robot.
Values#
RobotMode.Other- Other/unknown modeRobotMode.Idle- Robot is idleRobotMode.Move- Robot is executing a motionRobotMode.Guiding- Robot is in guiding mode (hand-guided)RobotMode.Reflex- Robot triggered a reflexRobotMode.UserStopped- User stopped the robotRobotMode.AutomaticErrorRecovery- Automatic error recovery in progress
Example:
state = robot.read_once()
if state.robot_mode == pylibfranka.RobotMode.Idle:
print("Robot is idle")
elif state.robot_mode == pylibfranka.RobotMode.Move:
print("Robot is moving")
Duration Class#
- class pylibfranka.Duration#
Bases:
pybind11_objectTime duration representation.
- to_sec(self: pylibfranka._pylibfranka.Duration) float#
Convert duration to seconds.
@return Duration in seconds as float
Time duration representation.
Methods#
- Duration.to_sec()
Convert duration to seconds.
- Returns:
Duration in seconds as float
- Return type:
Example:
state = robot.read_once()
time_sec = state.time.to_sec()
print(f"Timestamp: {time_sec:.3f} s")
Complete Examples#
Example 1: Monitoring Robot State#
import pylibfranka
import numpy as np
def main():
robot = pylibfranka.Robot("172.16.0.2")
for i in range(10):
state = robot.read_once()
print(f"\n=== Iteration {i+1} ===")
print(f"Joint positions [rad]: {state.q}")
print(f"Joint velocities [rad/s]: {state.dq}")
print(f"Joint torques [Nm]: {state.tau_J}")
print(f"External torques [Nm]: {state.tau_ext_hat_filtered}")
# End-effector position
O_T_EE = state.O_T_EE.reshape(4, 4).T
position = O_T_EE[:3, 3]
print(f"EE position [m]: {position}")
# Robot mode
print(f"Robot mode: {state.robot_mode}")
# Errors
if state.current_errors:
print(f"Errors: {state.current_errors}")
if __name__ == "__main__":
main()
Example 2: Logging State Data#
import pylibfranka
import numpy as np
import csv
def main():
robot = pylibfranka.Robot("172.16.0.2")
model = robot.load_model()
# Prepare data logging
data_log = []
control = robot.start_torque_control()
try:
for i in range(1000):
state, duration = control.readOnce()
# Log state
data_log.append({
'time': state.time.to_sec(),
'q': state.q.copy(),
'dq': state.dq.copy(),
'tau_J': state.tau_J.copy(),
'tau_ext': state.tau_ext_hat_filtered.copy()
})
# Control (gravity is automatically compensated)
tau = pylibfranka.Torques([0, 0, 0, 0, 0, 0, 0])
control.writeOnce(tau)
finally:
robot.stop()
# Save to CSV
with open('robot_data.csv', 'w', newline='') as f:
writer = csv.writer(f)
writer.writerow(['time', 'q1', 'q2', 'q3', 'q4', 'q5', 'q6', 'q7',
'tau1', 'tau2', 'tau3', 'tau4', 'tau5', 'tau6', 'tau7'])
for data in data_log:
row = [data['time']] + list(data['q']) + list(data['tau_J'])
writer.writerow(row)
print(f"Logged {len(data_log)} samples to robot_data.csv")
if __name__ == "__main__":
main()
See Also#
Robot– UseRobot.read_once()to get stateActiveControlBase– UseActiveControlBase.readOnce()in control loopsModel– Use state for dynamics computations