Robot Model

Type and Loading

ModernRoboticsBook.RobotType
Robot

A data container holding the kinematic and dynamic parameters of a serial-chain robot in the conventions of the Modern Robotics textbook.

Fields

  • name::String: robot name.
  • n_joints::Int: number of actuated joints.
  • home_ee_pose::Matrix{Float64}: end-effector pose $M \in SE(3)$ when all joint positions are zero (4×4).
  • screw_axes_space::Matrix{Float64}: joint screw axes in the space (base) frame at the home configuration (6×n).
  • screw_axes_body::Matrix{Float64}: joint screw axes in the end-effector (body) frame at the home configuration (6×n).
  • link_frames::Vector{Matrix{Float64}}: transforms $M_{i-1,i}$ between consecutive link frames (n+1 matrices).
  • spatial_inertias::Vector{Matrix{Float64}}: spatial inertia matrices $G_i$ for each link (n 6×6 matrices).
  • gravity::Vector{Float64}: gravity vector (default [0, 0, -9.81]).
  • joint_names::Vector{String}: joint names.
  • joint_types::Vector{Symbol}: joint types (:revolute or :prismatic).
  • joint_limits::Vector{Tuple{Float64,Float64}}: (lower, upper) position limits per joint.
source
ModernRoboticsBook.load_robotMethod
load_robot(path::AbstractString; gravity=[0.0, 0.0, -9.81]) -> Robot

Load a robot model from a JSON file.

The JSON file should contain the robot's kinematic and dynamic parameters serialized by the companion Python converter script (robots/convert.py).

The gravity keyword argument sets the gravity vector for the robot's operating environment. Defaults to Earth gravity [0, 0, -9.81].

source
ModernRoboticsBook.load_robotMethod
load_robot(name::Symbol; gravity=[0.0, 0.0, -9.81]) -> Robot

Load a bundled robot model by name (e.g., load_robot(:ur5)).

Bundled models are stored in the robots/models/ directory of this package.

source

Convenience Wrappers

The following functions accept a Robot as their first argument, automatically supplying the robot's kinematic and dynamic parameters. See the corresponding chapter pages for algorithmic details.

ModernRoboticsBook.computed_torqueMethod
computed_torque(robot::Robot, joint_positions, joint_velocities, error_integral, desired_joint_positions, desired_joint_velocities, desired_joint_accelerations, Kp, Ki, Kd; gravity) -> Vector

Robot wrapper for computed_torque — supplies robot.link_frames, robot.spatial_inertias, and robot.screw_axes_space automatically. Defaults gravity to robot.gravity.

source
ModernRoboticsBook.forward_dynamics_abaMethod
forward_dynamics_aba(robot::Robot, joint_positions, joint_velocities, joint_torques; gravity, tip_wrench) -> Vector

Robot wrapper for forward_dynamics_aba — supplies robot.link_frames, robot.spatial_inertias, and robot.screw_axes_space automatically. Defaults gravity to robot.gravity and tip_wrench to zero.

source
ModernRoboticsBook.forward_dynamics_crbaMethod
forward_dynamics_crba(robot::Robot, joint_positions, joint_velocities, joint_torques; gravity, tip_wrench) -> Vector

Robot wrapper for forward_dynamics_crba — supplies robot.link_frames, robot.spatial_inertias, and robot.screw_axes_space automatically. Defaults gravity to robot.gravity and tip_wrench to zero.

source
ModernRoboticsBook.forward_dynamics_trajectoryMethod
forward_dynamics_trajectory(robot::Robot, joint_positions, joint_velocities, joint_torque_traj, timestep, integration_resolution; gravity, tip_wrench_traj) -> Tuple

Robot wrapper for forward_dynamics_trajectory — supplies robot.link_frames, robot.spatial_inertias, and robot.screw_axes_space automatically. Defaults gravity to robot.gravity and tip_wrench_traj to zero.

source
ModernRoboticsBook.inverse_dynamics_rneaMethod
inverse_dynamics_rnea(robot::Robot, joint_positions, joint_velocities, joint_accelerations; gravity, tip_wrench)

Robot wrapper for inverse_dynamics_rnea — supplies robot.link_frames, robot.spatial_inertias, and robot.screw_axes_space automatically. Defaults gravity to robot.gravity and tip_wrench to zero.

source
ModernRoboticsBook.simulate_controlMethod
simulate_control(robot::Robot, joint_positions, joint_velocities, tip_wrench_traj, desired_joint_position_traj, desired_joint_velocity_traj, desired_joint_acceleration_traj, estimated_robot::Robot, Kp, Ki, Kd, timestep, integration_resolution; gravity, estimated_gravity) -> Tuple

Robot wrapper for simulate_control — supplies kinematic and dynamic parameters from both the true robot and the estimated_robot. Defaults gravity to robot.gravity and estimated_gravity to estimated_robot.gravity.

source