Supported robots¶
Every robot is a defined as a URDF, which will be installed $PREFIX/share/utheque
. All robots have pre-defined "robot classes" that define sensors and other properties; for your custom/new robots, you will have to add the sensors/properties via the generic robot class (or create a new robot class).
The URDF files are loaded using the following rules (see utheque::path()
):
- First check in the current directory
- If not found, check in
current_directory/utheque
- If not found, check in
$ROBOT_DART_PATH/utheque
- If not found, check in the robot dart installation path/robots (e.g.,
/usr/share/utheque
or$HOME/share/utheque
) - Otherwise, report failure
utheque
is a separate header-only library that gets installed together with RobotDART (or even alone), that can be used in libraries that do not want to interfere with RobotDART and use the curated URDF files.
Talos (PAL Robotics)¶
Talos is a humanoid robot made by PAL Robotics.
- Datasheet: [pdf]
- 32 degrees of freedom (6 for each leg, 7 for each arm, 2 for the waist, 2 for the neck, 1 for each gripper)
- 175 cm / 95 kg
- IMU in the torso
- Torque sensors in all joints except head, wrist and gripper (22 torque sensors total)
- 1 force/torque sensor in each ankle
- 1 force/torque sensor in each wrist
We have two URDF files:
utheque/talos/talos.urdf
:- accurate (simplified but made of polygons) collision meshes
- mimic joints for the gripper
- Not compatible the DART collision detector (you need to use FCL collision detector - shipped with DART)
- URDF: [talos.urdf]
- Example: [talos.cpp] [talos.py]
utheque/talos/talos_fast.urdf
:- no collision except for the feet, which are approximated by boxes
- grippers are fixed (no movement is allowed)
- compatible with the DART collision detector
- URDF: [talos_fast.urdf]
- Example: [talos_fast.cpp]
talos_fast.urdf
is faster because it makes it possible to use the DART collision detector (and has much collision shapes). You should prefer it except if you want to use the grippers (e.g., for manipulation) or are working on self-collisions.
utheque/talos/talos_fast_collision.urdf
:- all bodies are approximated by boxes
- grippers are fixed (no movement is allowed)
- compatible with the DART collision detector
- URDF: [talos_fast_collision.urdf]
- Example: [talos_fast_collision.cpp] [talos_fast_collision.py]
talos_fast_collision.urdf
is faster than talos.urdf
but slower than talos_fast.urdf
. You should use it when you need more detail collisions but faster simulation times.
Load Talos Fast
Please note that the mesh files (.glb) require assimp 5.x (and not assimp4.x usually shipped with ROS). If you cannot load the URDF, please check your assimp version.
Panda (Franka Emika)¶
The Franka is a modern manipulator made by Franka Emika Panda. It is commonly found in many robotics labs.
- Datasheet: [pdf]
- 7 degrees of freedom
- Can be controlled in torque
- 18 kg
- workspace: 855 mm (horizontal), 1190 mm (vertical)
- URDF: [franka.urdf]
- Example: [franka.cpp] [franka.py] The URDF includes the gripper.
LBR iiwa (KUKA)¶
The LBR iiwa is manufactured by KUKA. It is similar to the Panda and is also very common in robotics labs.
- Datasheet: [pdf]
- We implement the 14 kg version
- 29.5 kg
- 7 degrees of freedom
- URDF: [iiwa.urdf]
- Example: [iiwa.cpp] [iiwa.py]
iCub (IIT)¶
The iCub is a open source humanoid robot made by the Instituto Italiano di Tecnologia. There are currently 42 iCUbs in the world, and many versions.
- Datasheet (rev 2.3) [pdf]
- 6 force/torque sensors (upper arms, upper legs, ankles)
- IMU in the head
- We do to simulate the skin
- We do not simulate the hands
- Our model is close to the Inria's iCub, but it has not been checked in detail.
- URDF: [icub.urdf]
- Example [icub.cpp] [icub.py]
Please note that the mesh files (.glb) require assimp 5.x (and not assimp4.x usually shipped with ROS). If you cannot load the URDF, please check your assimp version.
Load iCub
auto robot = std::make_shared<robot_dart::robots::ICub>();
// Set actuator types to VELOCITY motors so that they stay in position without any controller
robot->set_actuator_types("velocity");
robot_dart::RobotDARTSimu simu(0.001);
simu.set_collision_detector("fcl");
Print IMU sensor measurements
std::cout << "Angular Position: " << robot->imu().angular_position_vec().transpose().format(fmt) << std::endl;
std::cout << "Angular Velocity: " << robot->imu().angular_velocity().transpose().format(fmt) << std::endl;
std::cout << "Linear Acceleration: " << robot->imu().linear_acceleration().transpose().format(fmt) << std::endl;
std::cout << "=================================" << std::endl;
Print Force-Torque sensor measurements
std::cout << "FT ( force): " << robot->ft_foot_left().force().transpose().format(fmt) << std::endl;
std::cout << "FT (torque): " << robot->ft_foot_left().torque().transpose().format(fmt) << std::endl;
std::cout << "=================================" << std::endl;
Unitree A1¶
A1 is a quadruped robot made by the Unitree Robotics.
- IMU in the torso
- We do not simulate the foot pressure sensors (yet)
- One can easily add a depth camera on the head
- URDF: [a1.urdf]
- Example [a1.cpp] [a1.py]
Print IMU sensor measurements
std::cout << "Angular Position: " << robot->imu().angular_position_vec().transpose().format(fmt) << std::endl;
std::cout << "Angular Velocity: " << robot->imu().angular_velocity().transpose().format(fmt) << std::endl;
std::cout << "Linear Acceleration: " << robot->imu().linear_acceleration().transpose().format(fmt) << std::endl;
std::cout << "=================================" << std::endl;
Add a depth camera on the head
Please note that the mesh files (.glb) require assimp 5.x (and not assimp4.x usually shipped with ROS). If you cannot load the URDF, please check your assimp version.
Dynamixel-based hexapod robot (Inria and others)¶
This hexapod is a simple 6-legged robot based on dynamixel actuators. It is similar to the robot used in the paper `Robots that can adapt like animals' (Cully et al., 2015).
- 6 legs, 3 degrees of freedom for each leg (18 degrees of freedom)
- simple URDF (no meshes)
- URDF: [pexod.urdf]
- Example: [hexapod.cpp] [hexapod.py]
Load Pexod
Vx-300¶
The ViperX-300 is a versatile robotic arm developed by Interbotix. It is designed for a range of applications including education, research, and light industrial tasks.
- 5 degrees of freedom plus a gripper
- URDF: [vx300.urdf]
- Example: [vx300.cpp] [vx300.py]
Tiago (PAL Robotics)¶
Tiago is a mobile manipulator robot developed by PAL Robotics, designed for tasks such as navigation, object manipulation, and human-robot interaction.
- Datasheet: pdf
- Height: 110 - 145 cm
- Weight: 70 kg
- Degrees of Freedom (DoF): 7 (Arm), 2 (Head), 2 (Mobile Base)
- Force/Torque sensor in the gripper
- URDF: [tiago.urdf]
- Example: [tiago.cpp] [tiago.py]
Simple arm¶
- A simple arm for educational or debugging purposes
- 5 degrees of freedom
- simple URDF (no meshes)
- URDF: [arm.urdf]
- Example: [arm.cpp] [arm.py]
Loading Custom Robots¶
RobotDART gives you the ability to load custom robots that are defined in URDF, SDF, SKEL or MJCF files. For example, you can load a urdf model using:
Load custom Robot
Load custom Robot with packages (e.g STL, DAE meshes)
std::vector<std::pair<std::string, std::string>> your_model_packages = ('model', 'path/to/model/dir');
auto your_robot = std::make_shared<robot_dart::Robot>("path/to/model.urdf", your_model_packages, "packages");
Known issues¶
For DART versions 6.14.4 and below, one might see the following error when loading meshes with negative scaling:
./dart/dynamics/MeshShape.cpp:240: void dart::dynamics::MeshShape::setScale(const Eigen::Vector3d&): Assertion `(scale.array() > 0.0).all()' failed.
Aborted (core dumped)
There are two solutions to this:
- Download and build the latest DART master or a version greater than 6.14.4
- Edit your meshes to not have negative scale