modern_robotics
Modern Robotics C++

Ubuntu22 Ubuntu24

A comprehensive Modern C++ implementation of robotics algorithms from the textbook Modern Robotics: Mechanics, Planning, and Control by Kevin Lynch and Frank Park (Cambridge University Press 2017).

Author: Jingkun Liu

๐Ÿ“– Documentation

๐Ÿ› ๏ธ Requirements

Component Minimum Version Tested Version
OS Ubuntu 22.04+ Ubuntu 22.04.5 LTS
CMake 3.16+ 3.22.1
Compiler GCC 9+ or Clang 10+ GCC 11.4.0
Armadillo 9.900+ 10.8.2

๐Ÿš€ Features

This library provides a complete implementation of fundamental robotics algorithms organized by textbook chapters:

Core Modules

  • ๐Ÿ”„ Rigid-Body Motions (Chapter 3)
    • Rotation matrices and homogeneous transformations
    • Screw theory and exponential coordinates
    • Adjoint representations
  • ๐ŸŽฏ Forward Kinematics (Chapter 4)
    • Product of exponentials formula
    • Open-chain manipulator kinematics
    • Body and space frame representations
  • โšก Velocity Kinematics & Statics (Chapter 5)
    • Jacobian computation and analysis
    • Velocity relationships and singularities
    • Static force analysis
  • ๐Ÿ“ˆ Inverse Kinematics (Chapter 6)
    • Newton-Raphson iterative algorithms
    • Numerical inverse kinematics solutions
  • ๐Ÿ”ง Dynamics of Open Chains (Chapter 8)
    • Forward and inverse dynamics
    • Mass matrix computation
    • Coriolis and gravitational effects
  • ๐Ÿ“Š Trajectory Generation (Chapter 9)
    • Point-to-point trajectory planning
    • Cubic and quintic polynomial time scaling
    • Joint space, screw motion, and Cartesian trajectories
  • ๐ŸŽฎ Robot Control (Chapter 11)
    • Computed torque control implementation
    • PID feedback control with feedforward
    • Control simulation and trajectory tracking
  • ๐Ÿ”ง Utilities
    • Mathematical constants and tolerance settings
    • Vector normalization and near-zero checking
    • Common robotics utility functions

๐Ÿ“ฆ Installation

Prerequisites

Install required dependencies on Ubuntu:

# Install build tools and dependencies
sudo apt update
sudo apt install build-essential cmake git
sudo apt install libarmadillo-dev

Build from Source

# Clone the repository
git clone https://github.com/nu-jliu/modern-robotics-cpp.git
cd modern-robotics-cpp
# Configure and build
mkdir build && cd build
cmake -DCMAKE_BUILD_TYPE=Release -DBUILD_TESTS=ON -DBUILD_DOCS=ON ..
make -j$(nproc)
# Install system-wide (optional)
sudo make install

Build Options

  • -DBUILD_TESTS=ON - Build unit tests
  • -DBUILD_DOCS=ON - Generate API documentation
  • -DCMAKE_BUILD_TYPE=Release - Optimized release build

๐Ÿ’ก Quick Start

Basic Usage Examples

Rigid Body Motions

#include <iostream>
int main() {
// Create a rotation matrix
arma::mat33 R = {{1, 0, 0},
{0, 0, -1},
{0, 1, 0}};
// Convert to axis-angle representation
arma::vec3 omg;
double theta;
mr::AxisAng3(R, omg, theta);
std::cout << "Rotation axis: " << omg.t();
std::cout << "Rotation angle: " << theta << " rad" << std::endl;
return 0;
}
const std::tuple< const arma::vec3, double > AxisAng3(const arma::vec3 &expc3)
Converts a 3-vector of exponential coordinates for rotation into axis-angle form.
Definition: rigid_body_motions.cpp:38

Trajectory Generation

// Generate a joint space trajectory
arma::vec thetastart = {0, 0, 0};
arma::vec thetaend = {1.57, 0.5, -0.3};
double Tf = 3.0; // 3 seconds
size_t N = 100; // 100 points
auto trajectory = mr::JointTrajectory(thetastart, thetaend, Tf, N,
const std::vector< arma::vec > JointTrajectory(const arma::vec &thetastart, const arma::vec &thetaend, const double Tf, const size_t N, const Method &method)
Computes a straight-line trajectory in joint space.
Definition: trajectory_generation.cpp:36
@ Quintic
cubic time scaling using 3rd-order polynomial

Robot Control

// Compute control torques using PID + feedforward
arma::vec tau = mr::ComputeTorque(thetalist, dthetalist, eint, g,
Mlist, Glist, Slist,
thetalistd, dthetalistd, ddthetalistd,
kp, ki, kd);
const arma::vec ComputeTorque(const arma::vec &thetalist, const arma::vec &dthetalist, const arma::vec &eint, const arma::vec3 &g, const std::vector< arma::mat44 > &Mlist, const std::vector< arma::mat66 > &Glist, const std::vector< arma::vec6 > &Slist, const arma::vec &thetalistd, const arma::vec &dthetalistd, const arma::vec &ddthetalistd, const double kp, const double ki, const double kd)
Computes the joint control torques at a particular time instant.
Definition: robot_control.cpp:6

CMake Integration

find_package(modern_robotics REQUIRED)
add_executable(your_robot_app src/main.cpp)
target_link_libraries(your_robot_app PUBLIC modern_robotics::modern_robotics)

Testing Your Installation

# Run all tests
cd build && ctest
# Run specific module tests
./build/tests/test_rigid_body_motions
./build/tests/test_forward_kinematics

๐Ÿ—๏ธ Project Structure

modern-robotics-cpp/
โ”œโ”€โ”€ include/modern_robotics/ # Public headers
โ”‚ โ”œโ”€โ”€ all.hpp # Convenience header (includes everything)
โ”‚ โ”œโ”€โ”€ rigid_body_motions.hpp # Chapter 3: Rotations & transformations
โ”‚ โ”œโ”€โ”€ forward_kinematics.hpp # Chapter 4: Forward kinematics
โ”‚ โ”œโ”€โ”€ velocity_kinematics_and_statics.hpp # Chapter 5: Jacobians & velocity
โ”‚ โ”œโ”€โ”€ inverse_kinematics.hpp # Chapter 6: Inverse kinematics
โ”‚ โ”œโ”€โ”€ dynamics_of_open_chains.hpp # Chapter 8: Dynamics algorithms
โ”‚ โ”œโ”€โ”€ trajectory_generation.hpp # Chapter 9: Motion planning
โ”‚ โ”œโ”€โ”€ robot_control.hpp # Chapter 11: Control algorithms
โ”‚ โ””โ”€โ”€ utils.hpp # Mathematical utilities
โ”œโ”€โ”€ src/ # Implementation files (.cpp)
โ”œโ”€โ”€ tests/ # Unit tests (Catch2 framework)
โ”‚ โ”œโ”€โ”€ test_rigid_body_motions.cpp
โ”‚ โ”œโ”€โ”€ test_forward_kinematics.cpp
โ”‚ โ”œโ”€โ”€ test_velocity_kinematics_and_statics.cpp
โ”‚ โ”œโ”€โ”€ test_inverse_kinematics.cpp
โ”‚ โ”œโ”€โ”€ test_dynamics_of_open_chains.cpp
โ”‚ โ”œโ”€โ”€ test_trajectory_generation.cpp
โ”‚ โ”œโ”€โ”€ test_robot_control.cpp
โ”‚ โ””โ”€โ”€ test_utils.cpp
โ”œโ”€โ”€ build/ # Build directory (generated)
โ”œโ”€โ”€ CMakeLists.txt # CMake configuration
โ”œโ”€โ”€ Doxyfile.in # Doxygen documentation config
โ”œโ”€โ”€ CLAUDE.md # Claude Code development guide
โ””โ”€โ”€ LICENSE # MIT License

๐Ÿงช Development

Running Tests

cd build
ctest --verbose # Run all tests with output
ctest -R rigid_body # Run specific test group
# Run individual test executables
./tests/test_rigid_body_motions
./tests/test_forward_kinematics
./tests/test_velocity_kinematics_and_statics
./tests/test_inverse_kinematics
./tests/test_dynamics_of_open_chains
./tests/test_trajectory_generation
./tests/test_robot_control
./tests/test_utils

Generating Documentation

cd build
make doc # Generates docs in build/docs/html/
# Open documentation: firefox build/docs/html/index.html

Code Architecture & Design

This library follows modern C++ best practices and robotics conventions:

Type System

  • Armadillo matrices: arma::mat33, arma::mat44, arma::mat66 for fixed-size matrices
  • Armadillo vectors: arma::vec3, arma::vec6, arma::vec for dynamic vectors
  • Const correctness: Functions return const values to prevent accidental modification
  • Namespace: All functionality contained within mr namespace

Parameter Conventions

  • Parameter names match textbook notation exactly (e.g., Slist, Blist, thetalist)
  • Slist: Screw axes in space frame (6ร—n matrix as vector of 6-vectors)
  • Blist: Screw axes in body frame (6ร—n matrix as vector of 6-vectors)
  • Mlist: Link frames relative to previous frame (vector of 4ร—4 matrices)
  • Glist: Spatial inertia matrices (vector of 6ร—6 matrices)

Mathematical Constants

  • Global tolerance: mr::tolerance = 1e-6
  • Utility functions for near-zero checking and vector normalization

Testing Framework

  • Catch2 framework for comprehensive unit testing
  • Floating-point comparisons use Catch::Matchers::WithinAbs(expected, TOLERANCE)
  • Each module has corresponding test file with mathematical validation

๐Ÿ“„ License

This project is licensed under the MIT License - see the [LICENSE](LICENSE) file for details.

๐Ÿค Contributing

Contributions are welcome! Please feel free to submit a Pull Request. For major changes, please open an issue first to discuss what you would like to change.

๐Ÿ“š References

  • Lynch, K. M., & Park, F. C. (2017). Modern Robotics: Mechanics, Planning, and Control. Cambridge University Press.
  • Official textbook website: modernrobotics.org

๐Ÿ‘จโ€๐Ÿ’ป Author

Jingkun Liu