tinyrobotics is a lightweight C++ library which provides core robotics algorithms for kinematics and dynamics.
The goal of tinyrobotics is to be as simple as possible while still being incredibly fast and versatile.
The core algorithms of tinyrobotics are listed below, for detailed documentation on all the available functions, see documentation.
Function | Description |
---|---|
import_urdf |
Generate a tinyrobotics model from a URDF robot description. |
Function | Description |
---|---|
forward_kinematics |
Compute homogeneous transform between links. |
inverse_kinematics |
Solve joint positions for desired pose between links. |
jacobian |
Compute geometric jacobian to a link from base. |
center_of_mass |
Compute center of mass of model. |
Function | Description |
---|---|
forward_dynamics |
Compute joint accelerations given joint positions, velocities and torques. |
inverse_dynamics |
Compute joint torques given joint positions, velocities and accelerations. |
mass_matrix |
Compute mass matrix given joint positions. |
kinetic_energy |
Compute kinetic energy given joint positions and velocity. |
potential_energy |
Compute potential energy given joint positions and velocity. |
total_energy |
Compute total energy (kinetic + potential) given joint positions and velocities. |
sudo apt install -y libeigen3-dev catch2 libtinyxml2-dev
git clone https://github.com/Tom0Brien/tinyrobotics.git && cd tinyrobotics
mkdir build && cd build
cmake ..
make
sudo make install # copies files in the include folder to /usr/local/include*
The code below demonstrates how to generate a model via a URDF and use kinematics and dynamics functions.
Numerous other examples are provided in the examples
folder.
// Parse URDF
const int n_joints = 5;
auto model = import_urdf<double, n_joints>("5_link.urdf");
// Create test configuration, velocity, acceleration and torque vectors
auto q = model.random_configuration();
auto dq = Eigen::Matrix<double, n_joints, 1>::Zero();
auto ddq = Eigen::Matrix<double, n_joints, 1>::Zero();
auto tau = Eigen::Matrix<double, n_joints, 1>::Zero();
// Forward Kinematics
std::string source_link = "base";
std::string target_link = "end_effector";
auto H = forward_kinematics(model, q, target_link, source_link);
// Center of Mass
auto com = center_of_mass(model, q);
// Inverse Kinematics
InverseKinematicsOptions<double, n_joints> options;
options.max_iterations = 1000;
options.tolerance = 1e-4;
options.method = InverseKinematicsMethod::LEVENBERG_MARQUARDT;
auto q_solution = inverse_kinematics(model, target_link, source_link, H, q, options);
// Jacobian
auto J = jacobian(model, q, target_link);
// Forward Dynamics
auto acceleration = forward_dynamics(model, q, dq, tau);
// Inverse Dynamics
auto torque = inverse_dynamics(model, q, dq, ddq);
// Mass Matrix
auto M = mass_matrix(model, q);
// Kinetic Energy
auto T = kinetic_energy(model, q, dq);
// Potential Energy
auto V = potential_energy(model, q);
// Total Energy
auto E = total_energy(model, q, dq);