Skip to content

martantoine/Minc

Folders and files

NameName
Last commit message
Last commit date

Latest commit

 

History

2 Commits
 
 
 
 
 
 
 
 
 
 
 
 
 
 

Repository files navigation

MINC: MuJoCo Inverse Kinematics in C++

License

MINC (MuJoCo Inverse Kinematics in C++) is a C++ library for differential inverse kinematics based on MuJoCo. It is a port of the Python library Mink to C++, hence the name change from "k" to "c".

Overview

MINC provides a fast and efficient implementation of differential inverse kinematics for robotics applications. The library leverages MuJoCo's physics simulation capabilities to compute accurate inverse kinematics solutions for complex robotic systems.

Key Features

  • Differential Inverse Kinematics: Compute joint velocities to achieve desired end-effector motions
  • Task-based Control: Support for multiple simultaneous tasks with different priorities
  • Constraint Handling: Built-in support for joint limits, velocity limits, and collision avoidance
  • MuJoCo Integration: Direct integration with MuJoCo physics simulation
  • High Performance: Optimized C++ implementation for real-time applications

Relation to Mink

This library is inspired by and ports the functionality of Mink, a Python inverse kinematics library created by Kevin Zakka. MINC brings the same powerful inverse kinematics capabilities to C++ applications, providing better performance for real-time robotics applications.

Reference: kevinzakka/mink: Python inverse kinematics based on MuJoCo

Dependencies

MINC is built on top of several key libraries:

  • MuJoCo (v3.3.5): Physics simulation and robot modeling
  • DAQP (v0.7.2): Dual Active-set algorithm for Quadratic Programming
  • Eigen3: Linear algebra library for matrix operations

These dependencies are automatically fetched and built using CMake's FetchContent.

Building the Project

Prerequisites

  • CMake 3.16 or higher
  • C++20 compatible compiler (GCC 10+, Clang 12+, or MSVC 2019+)
  • Eigen3 (will be found automatically or can be installed system-wide)

Build Instructions

  1. Clone the repository:

    git clone https://github.com/martantoine/Minc
    cd minc
  2. Create a build directory:

    mkdir build
    cd build
  3. Configure and build:

    cmake ..
    make -j$(nproc)
  4. Run tests (optional):

    ./tests/run_tests

Build Options

  • MINC_BUILD_TESTS: Enable/disable building tests (default: ON)

Example with custom options:

cmake -DMINC_BUILD_TESTS=OFF ..
make -j

Library Architecture

MINC is organized into several key components:

Core Components

  • Configuration: Robot configuration management and MuJoCo model interface
  • Tasks: Different types of inverse kinematics tasks
    • FrameTask: Position and orientation control for robot frames
    • PostureTask: Joint space posture control
    • ComTask: Center of mass control
    • RelativeFrameTask: Relative positioning between frames
    • DampingTask: Joint velocity damping
    • EqualityConstraintTask: Linear equality constraints

Lie Group Operations

  • SE(3): Special Euclidean group operations for 3D transformations
  • SO(3): Special Orthogonal group operations for 3D rotations

Limits and Constraints

  • ConfigurationLimit: Joint position limits
  • VelocityLimit: Joint velocity limits
  • CollisionAvoidanceLimit: Collision avoidance constraints

Solver Interface

The main solver interface provides a simple API similar to the original Mink library:

#include "minc.h"

// Create configuration from MuJoCo model
minc::Configuration config("path/to/model.xml");

// Define tasks
auto frame_task = std::make_shared<minc::tasks::FrameTask>(
    "end_effector", "site", target_position, target_orientation
);

// Solve inverse kinematics
std::vector<std::shared_ptr<minc::tasks::Task>> tasks = {frame_task};
Eigen::VectorXd joint_velocities = minc::solve_ik(config, tasks, dt);

Usage Example

#include "minc.h"
#include <iostream>

int main() {
    // Load robot model
    minc::Configuration config("robot_model.xml");
    
    // Define target pose
    Eigen::Vector3d target_pos(0.5, 0.0, 0.3);
    Eigen::Vector3d target_orient(0.0, 0.0, 0.0); // Euler angles
    
    // Create frame task
    auto task = std::make_shared<minc::tasks::FrameTask>(
        "end_effector", "site", target_pos, target_orient, 1.0, 1.0
    );
    
    // Solve IK
    std::vector<std::shared_ptr<minc::tasks::Task>> tasks = {task};
    double dt = 0.01;
    
    Eigen::VectorXd qvel = minc::solve_ik(config, tasks, dt);
    
    std::cout << "Joint velocities: " << qvel.transpose() << std::endl;
    
    return 0;
}

Using MINC in Your Project

With CMake

Add this to your CMakeLists.txt:

find_package(minc REQUIRED)
target_link_libraries(your_target minc::minc)

Manual Linking

g++ -std=c++20 your_code.cpp -lminc -lmujoco -ldaqp -o your_program

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.

License

This project is licensed under the Apache License 2.0 - see the LICENSE file for details.

Citation

If you use MINC in your research, please cite:

@software{minc2025,
  title={MINC: MuJoCo Inverse Kinematics in C++},
  author={[Antoine Vincent Martin]},
  year={2025},
  url={https://github.com/martantoine/Minc}
}

Acknowledgments

About

No description, website, or topics provided.

Resources

License

Stars

Watchers

Forks

Packages

No packages published

Languages