Robot Model
Type and Loading
ModernRoboticsBook.Robot — Type
RobotA 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 (:revoluteor:prismatic).joint_limits::Vector{Tuple{Float64,Float64}}:(lower, upper)position limits per joint.
ModernRoboticsBook.load_robot — Method
load_robot(path::AbstractString; gravity=[0.0, 0.0, -9.81]) -> RobotLoad 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].
ModernRoboticsBook.load_robot — Method
load_robot(name::Symbol; gravity=[0.0, 0.0, -9.81]) -> RobotLoad a bundled robot model by name (e.g., load_robot(:ur5)).
Bundled models are stored in the robots/models/ directory of this package.
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_torque — Method
computed_torque(robot::Robot, joint_positions, joint_velocities, error_integral, desired_joint_positions, desired_joint_velocities, desired_joint_accelerations, Kp, Ki, Kd; gravity) -> VectorRobot wrapper for computed_torque — supplies robot.link_frames, robot.spatial_inertias, and robot.screw_axes_space automatically. Defaults gravity to robot.gravity.
ModernRoboticsBook.end_effector_forces — Method
end_effector_forces(robot::Robot, joint_positions, tip_wrench) -> VectorRobot wrapper for end_effector_forces — supplies robot.link_frames, robot.spatial_inertias, and robot.screw_axes_space automatically.
ModernRoboticsBook.forward_dynamics_aba — Method
forward_dynamics_aba(robot::Robot, joint_positions, joint_velocities, joint_torques; gravity, tip_wrench) -> VectorRobot 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.
ModernRoboticsBook.forward_dynamics_crba — Method
forward_dynamics_crba(robot::Robot, joint_positions, joint_velocities, joint_torques; gravity, tip_wrench) -> VectorRobot 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.
ModernRoboticsBook.forward_dynamics_trajectory — Method
forward_dynamics_trajectory(robot::Robot, joint_positions, joint_velocities, joint_torque_traj, timestep, integration_resolution; gravity, tip_wrench_traj) -> TupleRobot 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.
ModernRoboticsBook.forward_kinematics_body! — Method
forward_kinematics_body!(T, robot::Robot, joint_positions)In-place Robot wrapper for forward_kinematics_body!. Writes the result into T.
ModernRoboticsBook.forward_kinematics_body — Method
forward_kinematics_body(robot::Robot, joint_positions) -> MatrixRobot wrapper for forward_kinematics_body — supplies robot.home_ee_pose and robot.screw_axes_body automatically.
ModernRoboticsBook.forward_kinematics_space! — Method
forward_kinematics_space!(T, robot::Robot, joint_positions)In-place Robot wrapper for forward_kinematics_space!. Writes the result into T.
ModernRoboticsBook.forward_kinematics_space — Method
forward_kinematics_space(robot::Robot, joint_positions) -> MatrixRobot wrapper for forward_kinematics_space — supplies robot.home_ee_pose and robot.screw_axes_space automatically.
ModernRoboticsBook.gravity_forces — Method
gravity_forces(robot::Robot, joint_positions; gravity) -> VectorRobot wrapper for gravity_forces — supplies robot.link_frames, robot.spatial_inertias, and robot.screw_axes_space automatically. Defaults gravity to robot.gravity.
ModernRoboticsBook.inverse_dynamics_rnea — Method
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.
ModernRoboticsBook.inverse_dynamics_trajectory — Method
inverse_dynamics_trajectory(robot::Robot, joint_position_traj, joint_velocity_traj, joint_acceleration_traj; gravity, tip_wrench_traj) -> MatrixRobot wrapper for inverse_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.
ModernRoboticsBook.inverse_kinematics_body — Method
inverse_kinematics_body(robot::Robot, target_config, initial_guess, angular_tolerance, linear_tolerance)Robot wrapper for inverse_kinematics_body — supplies robot.screw_axes_body and robot.home_ee_pose automatically.
ModernRoboticsBook.inverse_kinematics_space — Method
inverse_kinematics_space(robot::Robot, target_config, initial_guess, angular_tolerance, linear_tolerance)Robot wrapper for inverse_kinematics_space — supplies robot.screw_axes_space and robot.home_ee_pose automatically.
ModernRoboticsBook.jacobian_body! — Method
jacobian_body!(J, robot::Robot, joint_positions)In-place Robot wrapper for jacobian_body!. Writes the result into J.
ModernRoboticsBook.jacobian_body — Method
jacobian_body(robot::Robot, joint_positions) -> MatrixRobot wrapper for jacobian_body — supplies robot.screw_axes_body automatically.
ModernRoboticsBook.jacobian_space! — Method
jacobian_space!(J, robot::Robot, joint_positions)In-place Robot wrapper for jacobian_space!. Writes the result into J.
ModernRoboticsBook.jacobian_space — Method
jacobian_space(robot::Robot, joint_positions) -> MatrixRobot wrapper for jacobian_space — supplies robot.screw_axes_space automatically.
ModernRoboticsBook.mass_matrix_crba! — Method
mass_matrix_crba!(M, robot::Robot, joint_positions, Ai, AdTi, Gc)In-place Robot wrapper for mass_matrix_crba!. Writes the result into M.
ModernRoboticsBook.mass_matrix_crba — Method
mass_matrix_crba(robot::Robot, joint_positions) -> MatrixRobot wrapper for mass_matrix_crba — supplies robot.link_frames, robot.spatial_inertias, and robot.screw_axes_space automatically.
ModernRoboticsBook.simulate_control — Method
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) -> TupleRobot 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.
ModernRoboticsBook.velocity_quadratic_forces — Method
velocity_quadratic_forces(robot::Robot, joint_positions, joint_velocities) -> VectorRobot wrapper for velocity_quadratic_forces — supplies robot.link_frames, robot.spatial_inertias, and robot.screw_axes_space automatically.