Dynamics Model#
The Model class provides robot dynamics model for computing kinematics and dynamics quantities.
Class Definition#
- class pylibfranka.Model#
Bases:
pybind11_objectRobot dynamics model for computing dynamics quantities.
- coriolis(self: pylibfranka._pylibfranka.Model, arg0: pylibfranka._pylibfranka.RobotState) List[float[7]]#
Compute Coriolis force vector.
@param robot_state Current robot state @return Coriolis force vector [Nm] as numpy array (7,)
- gravity(self: pylibfranka._pylibfranka.Model, arg0: pylibfranka._pylibfranka.RobotState) List[float[7]]#
Compute gravity force vector.
@param robot_state Current robot state @return Gravity force vector [Nm] as numpy array (7,)
- mass(self: pylibfranka._pylibfranka.Model, arg0: pylibfranka._pylibfranka.RobotState) List[float[49]]#
Compute mass matrix.
@param robot_state Current robot state @return Mass matrix [kg*m²] as numpy array (7, 7)
- zero_jacobian(*args, **kwargs)#
Overloaded function.
zero_jacobian(self: pylibfranka._pylibfranka.Model, arg0: pylibfranka._pylibfranka.RobotState) -> List[float[42]]
Compute zero Jacobian for end effector frame.
@param robot_state Current robot state @return Jacobian matrix as numpy array (6, 7)
zero_jacobian(self: pylibfranka._pylibfranka.Model, arg0: franka::Frame, arg1: pylibfranka._pylibfranka.RobotState) -> List[float[42]]
Compute zero Jacobian for specified frame.
@param frame Frame to compute Jacobian for @param robot_state Current robot state @return Jacobian matrix as numpy array (6, 7)
Overview#
The Model class allows computation of various dynamics quantities including:
Mass matrix
Coriolis and centrifugal forces
Gravity torques
Forward kinematics (Jacobian)
To obtain a Model instance, use Robot.load_model().
Methods#
coriolis#
- Model.coriolis(robot_state)
Compute Coriolis force vector \(c(q, \dot{q})\).
- Parameters:
robot_state (RobotState) – Current robot state
- Returns:
Coriolis force vector [Nm] as numpy array (7,)
- Return type:
The Coriolis vector represents centrifugal and Coriolis forces acting on the robot.
Example:
import pylibfranka robot = pylibfranka.Robot("172.16.0.2") model = robot.load_model() state = robot.read_once() # Compute Coriolis forces coriolis = model.coriolis(state) print("Coriolis forces [Nm]:", coriolis)
gravity#
- Model.gravity(robot_state)
Compute gravity force vector \(g(q)\).
- Parameters:
robot_state (RobotState) – Current robot state
- Returns:
Gravity force vector [Nm] as numpy array (7,)
- Return type:
The gravity vector contains the joint torques required to compensate for gravitational forces. This is provided for dynamics analysis and computation purposes. When using torque control, gravity is automatically compensated by the controller, so you should not add gravity to your commands.
Example:
import pylibfranka robot = pylibfranka.Robot("172.16.0.2") model = robot.load_model() state = robot.read_once() # Compute gravity for analysis purposes gravity = model.gravity(state) print("Gravity torques [Nm]:", gravity)
mass#
- Model.mass(robot_state)
Compute mass matrix \(M(q)\).
- Parameters:
robot_state (RobotState) – Current robot state
- Returns:
Mass matrix [kg·m²] as numpy array (7, 7)
- Return type:
The mass matrix (also called inertia matrix) relates joint accelerations to joint torques.
Example:
import pylibfranka import numpy as np robot = pylibfranka.Robot("172.16.0.2") model = robot.load_model() state = robot.read_once() # Compute mass matrix M = model.mass(state) print("Mass matrix shape:", M.shape) # (7, 7) print("Mass matrix:\n", M) # Example: Compute required torques for desired accelerations ddq_desired = np.array([0.1, 0, 0, 0, 0, 0, 0]) # [rad/s²] tau = M @ ddq_desired print("Required torques:", tau)
zero_jacobian#
- Model.zero_jacobian(robot_state)
- Model.zero_jacobian(frame, robot_state)
Compute zero Jacobian \(^0J\) for specified frame.
- Parameters:
frame (Frame) – Frame to compute Jacobian for (optional, default: end effector)
robot_state (RobotState) – Current robot state
- Returns:
Jacobian matrix as numpy array (6, 7)
- Return type:
The Jacobian maps joint velocities to end-effector twist (linear and angular velocities).
The returned Jacobian has shape (6, 7) where:
Rows 0-2: Linear velocity mapping [m/s per rad/s]
Rows 3-5: Angular velocity mapping [rad/s per rad/s]
Example:
import pylibfranka import numpy as np robot = pylibfranka.Robot("172.16.0.2") model = robot.load_model() state = robot.read_once() # Compute end-effector Jacobian J = model.zero_jacobian(state) print("Jacobian shape:", J.shape) # (6, 7) # Compute end-effector velocity from joint velocities dq = np.array(state.dq) # Joint velocities [rad/s] dx = J @ dq # End-effector twist [m/s, rad/s] v_linear = dx[:3] # Linear velocity [m/s] w_angular = dx[3:] # Angular velocity [rad/s] print("Linear velocity [m/s]:", v_linear) print("Angular velocity [rad/s]:", w_angular)
See Also#
Robot– Main robot interface (useRobot.load_model()to get Model)RobotState– Robot state used as input for dynamics computationActiveControlBase– Control interface for sending computed torques