Integrate a new robot in mc_rtc

There are three ways to integrate your robot into mc_rtc:

  1. Using the env/object loader
  2. Using a JSON/YAML file and the json loader
  3. Writing a C++ RobotModule implementation

Loader Overview

  • env/object loader: Best suited for simple robots or static objects and environments. Convex hulls can still be generated automatically for collision meshes.
  • json loader: Adds structured metadata to the robot (e.g., joints, sensors, grippers). Supports automatic convex hull generation from URDF meshes.
  • C++ RobotModule: Provides full control over loading, configuration, and logic. Fully supports automatic convex generation and caching.

Using the env/object Loader

To load your robot using this loader, use the following invocation:

#include <mc_rbdyn/RobotLoader.h>

std::string path = "/path/to/description";
std::string name = "name";
auto env = mc_rbdyn::RobotLoader::get_robot_module("env", path, name);

// object will load the robot with a floating base
auto object = mc_rbdyn::RobotLoader::get_robot_module("object", path, name);
import mc_rbdyn

path = "/path/to/description"
name = "name"
env = mc_rbdyn.get_robot_module("env", path, name)

# object will load the robot with a floating base
object = mc_rbdyn.get_robot_module("object", path, name)
["env", "/path/to/description", "name"]

// object will load the robot with a floating base
["object", "/path/to/description", "name"]
[env, /path/to/description, name]

# object will load the robot with a floating base
[object, /path/to/description, name]

Organization of Your Robot Description Package

Given a robot description directory located at LOCATION and a robot named NAME, mc_rtc expects your data to be structured as follows:

  • URDF file: $LOCATION/urdf/$NAME.urdf
  • RSDF files (optional): $LOCATION/rsdf/$NAME/
  • Convex hull files (optional): $LOCATION/convex/$NAME/

For a body named BODY, the corresponding convex file should be named:

BODY-ch.txt

Additional Notes:

  • The RSDF directory can be empty or not exist at all.
  • Not every body requires a convex file.
  • Convex files that can't be matched to any body are ignored.
  • If convexes are missing, they can be generated automatically for any loader type.

Automatic Convex Hull Generation

Regardless of how your robot is loaded (C++, JSON, or env/object), mc_rtc can generate convex hulls automatically from mesh-type collision geometries in the URDF or SRDF.

How It Works

  • Meshes in the robot description are sampled to build convex approximations.
  • These convex hulls are cached to avoid regeneration unless explicitly requested.
  • Convex generation can be triggered automatically or manually depending on loader and setup.

Convex Cache Storage

Generated convexes are stored in a user-specific local share directory. The base directory is platform-specific :

  • Windows: %APPDATA%/mc_rtc/<robot_name>/
  • Linux/macOS: $HOME/.local/share/mc_rtc/<robot_name>/

Convex File Naming

  • For bodies with a single mesh: BODY-ch.txt
  • For bodies with multiple meshes: BODY_0-ch.txt, BODY_1-ch.txt, etc.

Using the json loader

When loading the robot, use the following invokation:

#include <mc_rbdyn/RobotLoader.h>

std::string json_path = "/path/to/file.json";
auto rm_json = mc_rbdyn::RobotLoader::get_robot_module("json", json_path);

std::string yaml_path = "/path/to/file.yaml";
auto rm_yaml = mc_rbdyn::RobotLoader::get_robot_module("json", yaml_path);
import mc_rbdyn

json_path = "/path/to/file.json"
rm_json = mc_rbdyn.get_robot_module("json", json_path)

yaml_path = "/path/to/file.yaml"
rm_yaml = mc_rbdyn.get_robot_module("json", yaml_path)
["json", "/path/to/file.json"]

["json", "/path/to/file.yaml"]
[json, /path/to/file.json]

[json, /path/to/file.yaml]

Data expected in the JSON/YAML file

The json module expects your data to be organized as the env module. However, you can override some expectations by providing the data yourself. Furthermore, you can provide data for force sensors, body sensors, minimal self-collisions set and so-on.

See the JSON/YAML documentation for details on the data expected by the json loader.

Implementing your own RobotModule

In this approach, we will write a C++ class to provide a RobotModule for our robot and overwrite the data members that we wish to provide. As in the minimal example below:

cmake_minimum_required(VERSION 3.1)

find_package(mc_rtc REQUIRED)

add_robot_simple(MyRobot)
# Shortcut for:
#
# add_robot(MyRobot MyRobot.h MyRobot.cpp)
#pragma once

#include <mc_rbdyn/RobotModule.h>
#include <mc_robots/api.h>

struct MC_ROBOTS_DLLAPI MyRobotModule : public mc_rbdyn::RobotModule
{
public:
  MyRobotModule(bool fixed);
};

extern "C"
{
  ROBOT_MODULE_API void MC_RTC_ROBOT_MODULE(std::vector<std::string> & names)
  {
    // Names of the robots exported by this module
    names = {"MyRobot", "MyRobotFixed"};
  }
  ROBOT_MODULE_API void destroy(mc_rbdyn::RobotModule * ptr)
  {
    delete ptr;
  }
  ROBOT_MODULE_API mc_rbdyn::RobotModule * create(const std::string & name)
  {
    // At this point name must be one of the supported robots
    if(name == "MyRobot") { return new MyRobot(false); }
    else
    {
      return new MyRobot(true);
    }
  }
}
#include "MyRobot.h"

#include <RBDyn/parsers/urdf.h>

// MY_PATH can be provided by CMake for example
MyRobotModule::MyRobotModule(bool fixed) : mc_rbdyn::RobotModule(MY_PATH, "my_robot")
{
  init(rbd::parsers::from_urdf_file(urdf_path));

  std::vector<double> default_q = {-0.38, -0.01, 0., 0.72, -0.01, -0.33,  -0.38, 0.02, 0.,    0.72, -0.02, -0.33, 0.,
                                   0.13,  0.,    0., 0.,   0.,    -0.052, -0.17, 0.,   -0.52, 0.,   0.,    0.,    0.,
                                   0.,    0.,    0., 0.,   0.,    -0.052, 0.17,  0.,   -0.52, 0.,   0.,    0.,    0.,
                                   0.,    0.,    0., 0.,   0.,    0.,     0.,    0.,   0.,    0.,   0.};
  const auto & rjo = ref_joint_order();
  for(size_t i = 0; i < rjo.size(); ++i) { _stance[rjo[i]] = {default_q[i]}; }
  _default_attitude = {{1., 0., 0., 0., 0., 0., 0.8275}};
  _forceSensors.push_back(mc_rbdyn::ForceSensor("RightFootForceSensor", "R_ANKLE_P_S", sva::PTransformd::Identity()));
  _forceSensors.push_back(mc_rbdyn::ForceSensor("LeftFootForceSensor", "L_ANKLE_P_S", sva::PTransformd::Identity()));
  _forceSensors.push_back(mc_rbdyn::ForceSensor("RightHandForceSensor", "R_WRIST_Y_S", sva::PTransformd::Identity()));
  _forceSensors.push_back(mc_rbdyn::ForceSensor("LeftHandForceSensor", "L_WRIST_Y_S", sva::PTransformd::Identity()));

  _bodySensors.emplace_back("Accelerometer", "PELVIS_S", sva::PTransformd(Eigen::Vector3d(-0.0325, 0, 0.1095)));
  _bodySensors.emplace_back("FloatingBase", "PELVIS_S", sva::PTransformd::Identity());

  _minimalSelfCollisions = {
      {"WAIST_R_S", "L_SHOULDER_Y_S", 0.02, 0.001, 0.}, {"WAIST_R_S", "R_SHOULDER_Y_S", 0.02, 0.001, 0.},
      {"PELVIS_S", "R_ELBOW_P_S", 0.05, 0.001, 0.},     {"PELVIS_S", "L_ELBOW_P_S", 0.05, 0.001, 0.},
      {"R_WRIST_Y_S", "R_HIP_Y_S", 0.05, 0.025, 0.},    {"L_WRIST_Y_S", "L_HIP_Y_S", 0.05, 0.025, 0.}};
  _commonSelfCollisions = _minimalSelfCollisions;
  _grippers = {{"l_gripper", {"L_UTHUMB"}, true}, {"r_gripper", {"R_UTHUMB"}, false}};
}

See mc_rbdyn::RobotModule documentation for all members that can be provided.

Get started

Use the mc-rtc/new-robot-module template project to get started quickly. This template provides the barebone structure for a C++ RobotModule or a YAML RobotModule