Frequently Asked Questions¶
This pages provides a user guide of the library through Frequently Asked Questions (FAQ).
What is a minimal working example of RobotDART?¶
You can find a minimal working example at hello_world.cpp. This example is creating a world where a hexapod robot is placed just above a floor and left to fall. The robot has no actuation, and there is the simplest graphics configuration. Let's split it down.
- We first include the appropriate files:
- We then load our hexapod robot:
- We need to place it above the floor to avoid collision (we can use RobotDART's helpers ;)):
- We can now create the simulation object and add the robot and the floor:
- If needed or wanted, we can add a graphics component to visualize the scene:
- Once everything is configured, we can run our simulation for a few seconds:
- Here's how it looks:
What robots are supported in RobotDART?¶
RobotDART supports any robot that can be described by a URDF, SDF, SKEL or MJCF file. Nevertheless, we have a curated list of robots with edited and optimized models to be used with RobotDART (see the robots page for details and examples).
How can I load my own URDF/SDF/SKEL/MJCF file?¶
See the robots page for details.
How do I enable graphics in my code?¶
To enable graphics in your code, you need to do the following:
- Install Magnum. See the installation page for details.
- Create and set a graphics object in the simulation object. Here's an example:
I want to have multiple camera sensors. Is it possible?¶
Having multiple camera sensors is indeed possible. We can add as many cameras as we wish along the main camera defined in How do I record a video:
How do I record a video?¶
In order to record a video (1) of what the main or any other camera "sees", you need to call the function record_video(path)
of the graphics class:
- Make sure that you have
ffmpeg
installed on your system.
Or the camera class:
How can I position a camera to the environment?¶
In order to position a camera inside the world, we need to use the lookAt
method of the camera/graphics object:
How can I attach a camera to a moving link?¶
Cameras can be easily attached to a moving link:
tf = dartpy.math.Isometry3()
rot = dartpy.math.AngleAxis(3.14, [1., 0., 0.])
rot = rot.multiply(dartpy.math.AngleAxis(1.57, [0., 0., 1.])).to_rotation_matrix()
tf.set_translation([0., 0., 0.1])
tf.set_rotation(rot)
camera.attach_to_body(robot.body_node("iiwa_link_ee"), tf) # cameras are looking towards -z by default
How can I manipulate the camera object?¶
Every camera has its own parameters, i.e a Near plane, a far plane, a Field Of View (FOV), a width and a height (that define the aspect ratio), you can manipulate each one separately:
or all at once:
You can find a complete example at cameras.cpp and cameras.py.
How can I interact with the camera?¶
We can move translate the cameras with the WASD
keys, zoom in and out using the mouse wheel
and rotate the camera with holding the left mouse key
and moving the mouse.
What do the numbers in the status bar mean?¶
The status bar looks like this:
Where simulation time gives us the total simulated time (in seconds), wall time gives us the total time (in seconds) that has passed in real-time once we have started simulating. The next number X.Xx gives us the real-time factor: for example, 1.1x means that the simulation runs 1.1 times faster than real-time, whereas 0.7x means that the simulation runs slower than real-time. The value it: XX ms reports the time it took the last iteration (in milliseconds). The last part gives us whether the simulation tries to adhere to real-time or not. sync means that RobotDART will slow down the simulation in order for it to be in real-time, whereas no-sync means that RobotDART will try to run the simulation as fast as possible.
How can I alter the graphics scene (e.g., change lighting conditions)?¶
When creating a graphics object, you can pass a GraphicsConfiguration
object that changes the default values:
robot_dart::gui::magnum::GraphicsConfiguration configuration;
// We can change the width/height of the window (or camera image dimensions)
configuration.width = 1280;
configuration.height = 960;
configuration.title = "Graphics Tutorial"; // We can set a title for our window
// We can change the configuration for shadows
configuration.shadowed = true;
configuration.transparent_shadows = true;
configuration.shadow_map_size = 1024;
// We can also alter some specifications for the lighting
configuration.max_lights = 3; // maximum number of lights for our scene [default=3]
configuration.specular_strength = 0.25; // strength of the specular component
// Some extra configuration for the main camera
configuration.draw_main_camera = true;
configuration.draw_debug = true;
configuration.draw_text = true;
// We can also change the background color [default=black]
configuration.bg_color = Eigen::Vector4d{1.0, 1.0, 1.0, 1.0};
// Create the graphics object with the configuration as parameter
auto graphics = std::make_shared<robot_dart::gui::magnum::Graphics>(configuration);
configuration = rd.gui.GraphicsConfiguration()
# We can change the width/height of the window (or camera, dimensions)
configuration.width = 1280
configuration.height = 960
configuration.title = "Graphics Tutorial" # We can set a title for our window
# We can change the configuration for shadows
configuration.shadowed = True
configuration.transparent_shadows = True
configuration.shadow_map_size = 1024
# We can also alter some specifications for the lighting
configuration.max_lights = 3 # maximum number of lights for our scene
configuration.specular_strength = 0.25 # strength og the specular component
# Some extra configuration for the main camera
configuration.draw_main_camera = True
configuration.draw_debug = True
configuration.draw_text = True
# We can also change the background color [default = black]
configuration.bg_color = [1., 1., 1., 1.]
# create the graphics object with the configuration as a parameter
graphics = rd.gui.Graphics(configuration)
You can disable or enable shadows on the fly as well:
You can also add your own lights. The application by default creates 2 light sources and the maximum number of lights is 3 (you can change this once before the creation of the graphics object via the GraphicsConfiguration
object). So usually before you add your lights, you have to clear the default lights:
Then you must create a custom light material:
Now you can add on ore more of the following lights:
Point Light:
// Create point light
Magnum::Vector3 position = {0.f, 0.f, 2.f};
Magnum::Float intensity = 1.f;
Magnum::Vector3 attenuation_terms = {1.f, 0.f, 0.f};
auto point_light = robot_dart::gui::magnum::gs::create_point_light(position, custom_material, intensity, attenuation_terms);
graphics->add_light(point_light);
Spot Light:
// Create spot light
Magnum::Vector3 position = {0.f, 0.f, 1.f};
Magnum::Vector3 direction = {-1.f, -1.f, -1.f};
Magnum::Float intensity = 1.f;
Magnum::Vector3 attenuation_terms = {1.f, 0.f, 0.f};
Magnum::Float spot_exponent = M_PI;
Magnum::Float spot_cut_off = M_PI / 8;
auto spot_light = robot_dart::gui::magnum::gs::create_spot_light(position, custom_material, direction, spot_exponent, spot_cut_off, intensity, attenuation_terms);
graphics->add_light(spot_light);
# Create spot light
position = magnum.Vector3(0., 0., 1.)
direction = magnum.Vector3(-1, -1, -1)
intensity = 1.
attenuation_terms = magnum.Vector3(1., 0., 0.)
spot_exponent = np.pi
spot_cut_off = np.pi / 8
spot_light = rd.gui.create_spot_light(position, custom_material, direction, spot_exponent, spot_cut_off, intensity, attenuation_terms)
graphics.add_light(spot_light)
Directional Light:
I want to visualize a target configuration of my robot, is this possible?¶
Yes this is possible. RobotDART gives the ability to create a clone of your robot that has no physics, no contacts, just visuals:
How can I control my robot ?¶
PD control
// add a PD-controller to the arm
// set desired positions
Eigen::VectorXd ctrl = robot_dart::make_vector({0., M_PI / 4., 0., -M_PI / 4., 0., M_PI / 2., 0., 0.});
// add the controller to the robot
auto controller = std::make_shared<robot_dart::control::PDControl>(ctrl);
robot->add_controller(controller);
controller->set_pd(300., 50.);
Simple control
Robot control
class MyController : public robot_dart::control::RobotControl {
public:
MyController() : robot_dart::control::RobotControl() {}
MyController(const Eigen::VectorXd& ctrl, bool full_control) : robot_dart::control::RobotControl(ctrl, full_control) {}
MyController(const Eigen::VectorXd& ctrl, const std::vector<std::string>& dof_names) : robot_dart::control::RobotControl(ctrl, dof_names) {}
void configure() override
{
_active = true;
}
Eigen::VectorXd calculate(double) override
{
auto robot = _robot.lock();
Eigen::VectorXd cmd = 100. * (_ctrl - robot->positions(_controllable_dofs));
return cmd;
}
std::shared_ptr<robot_dart::control::RobotControl> clone() const override
{
return std::make_shared<MyController>(*this);
}
};
class MyController(rd.RobotControl):
def __init__(self, ctrl, full_control):
rd.RobotControl.__init__(self, ctrl, full_control)
def __init__(self, ctrl, controllable_dofs):
rd.RobotControl.__init__(self, ctrl, controllable_dofs)
def configure(self):
self._active = True
def calculate(self, t):
target = np.array([self._ctrl])
cmd = 100*(target-self.robot().positions(self._controllable_dofs))
return cmd[0]
# TO-DO: This is NOT working at the moment!
def clone(self):
return MyController(self._ctrl, self._controllable_dofs)
Is there a way to control the simulation timestep?¶
When creating a RobotDARTSimu object you choose the simulation timestep:
which can later be modified by:
I want to simulate a mars environment, is it possible to change the gravitational force of the simulation environment?¶
Yes you can modify the gravitational forces 3-dimensional vector of the simulation:
Which collision detectors are available? What are their differences? How can I choose between them?¶
DART | FCL | ODE | Bullet |
---|---|---|---|
Support only basic shapes | Full-featured collision detector fully integrated by DART | External collision detector of ODE | External collision detector of Bullet |
This is building along with DART | This is a required dependency of DART | Needs an external library | Needs an external library |
Very fast for small scenes | Accurate detailed collisions, but not very fast | Fast collision detection (the integration is not complete) | Fast and accurate collision detection (works well for wheels as well) |
We can easily select one of the available collision detectors using the simulator object:
My robot does not self-collide. How can I change this?¶
One possible cause may be the fact that self collision is disabled, you can check and change this:
How can I compute kinematic/dynamic properties of my robot (e.g., Jacobians, Mass Matrix)?¶
Kinematic Properties:
// Get Joint Positions(Angles)
auto joint_positions = robot->positions();
// Get Joint Velocities
auto joint_vels = robot->velocities();
// Get Joint Accelerations
auto joint_accs = robot->accelerations();
// Get link_name(str) Transformation matrix with respect to the world frame.
auto eef_tf = robot->body_pose(link_name);
// Get translation vector from transformation matrix
auto eef_pos = eef_tf.translation();
// Get rotation matrix from tranformation matrix
auto eef_rot = eef_tf.rotation();
// Get link_name 6d pose vector [logmap(eef_tf.linear()), eef_tf.translation()]
auto eef_pose_vec = robot->body_pose_vec(link_name);
// Get link_name 6d velocity vector [angular, cartesian]
auto eef_vel = robot->body_velocity(link_name);
// Get link_name 6d acceleration vector [angular, cartesian]
auto eef_acc = robot->body_acceleration(link_name);
// Jacobian targeting the origin of link_name(str)
auto jacobian = robot->jacobian(link_name);
// Jacobian time derivative
auto jacobian_deriv = robot->jacobian_deriv(link_name);
// Center of Mass Jacobian
auto com_jacobian = robot->com_jacobian();
// Center of Mass Jacobian Time Derivative
auto com_jacobian_deriv = robot->com_jacobian_deriv();
# Get Joint Positions(Angles)
joint_positions = robot.positions()
# Get Joint Velocities
joint_vels = robot.velocities()
# Get Joint Accelerations
joint_accs = robot.accelerations()
# Get link_name(str) Transformation matrix with respect to the world frame.
eef_tf = robot.body_pose(link_name)
# Get translation vector from transformation matrix
eef_pos = eef_tf.translation()
# Get rotation matrix from tranformation matrix
eef_rot = eef_tf.rotation()
# Get link_name 6d pose vector [logmap(eef_tf.linear()), eef_tf.translation()]
eef_pose_vec = robot.body_pose_vec(link_name)
# Get link_name 6d velocity vector [angular, cartesian]
eef_vel = robot.body_velocity(link_name)
# Get link_name 6d acceleration vector [angular, cartesian]
eef_acc = robot.body_acceleration(link_name)
# Jacobian targeting the origin of link_name(str)
jacobian = robot.jacobian(link_name)
# Jacobian time derivative
jacobian_deriv = robot.jacobian_deriv(link_name)
# Center of Mass Jacobian
com_jacobian = robot.com_jacobian()
# Center of Mass Jacobian Time Derivative
com_jacobian_deriv = robot.com_jacobian_deriv()
Dynamic Properties:
// Get Joint Forces
auto joint_forces = robot->forces();
// Get link's mass
auto eef_mass = robot->body_mass(link_name);
// Mass Matrix of robot
auto mass_matrix = robot->mass_matrix();
// Inverse of Mass Matrix
auto inv_mass_matrix = robot->inv_mass_matrix();
// Augmented Mass matrix
auto aug_mass_matrix = robot->aug_mass_matrix();
// Inverse of Augmented Mass matrix
auto inv_aug_mass_matrix = robot->inv_aug_mass_matrix();
// Coriolis Force vector
auto coriolis = robot->coriolis_forces();
// Gravity Force vector
auto gravity = robot->gravity_forces();
// Combined vector of Coriolis Force and Gravity Force
auto coriolis_gravity = robot->coriolis_gravity_forces();
// Constraint Force Vector
auto constraint_forces = robot->constraint_forces();
# Get Joint Forces
joint_forces = robot.forces()
# Get link's mass
eef_mass = robot.body_mass(link_name)
# Mass Matrix of robot
mass_matrix = robot.mass_matrix()
# Inverse of Mass Matrix
inv_mass_matrix = robot.inv_mass_matrix()
# Augmented Mass matrix
aug_mass_matrix = robot.aug_mass_matrix()
# Inverse of Augmented Mass matrix
inv_aug_mass_matrix = robot.inv_aug_mass_matrix()
# Coriolis Force vector
coriolis = robot.coriolis_forces()
# Gravity Force vector
gravity = robot.gravity_forces()
# Combined vector of Coriolis Force and Gravity Force
coriolis_gravity = robot.coriolis_gravity_forces()
# NOT IMPLEMENTED
# # Constraint Force Vector
# constraint_forces = robot.constraint_forces()
Is there a way to change the joint properties (e.g., actuation, friction)?¶
There are 6 types of actuators available, you can set the same actuator to multiple joints at once, or you can set each sensor separately:
To enable position and velocity limits for the actuators:
Every DOF's limits (position, velocity, acceleration, force) can be modified:
// Modify Position Limits
Eigen::VectorXd pos_upper_lims(7);
pos_upper_lims << 2.096, 2.096, 2.096, 2.096, 2.096, 2.096, 2.096;
robot->set_position_upper_limits(pos_upper_lims, dof_names);
robot->set_position_lower_limits(-pos_upper_lims, dof_names);
// Modify Velocity Limits
Eigen::VectorXd vel_upper_lims(7);
vel_upper_lims << 1.5, 1.5, 1.5, 1.5, 1.5, 1.5, 1.5;
robot->set_velocity_upper_limits(vel_upper_lims, dof_names);
robot->set_velocity_lower_limits(-vel_upper_lims, dof_names);
// Modify Force Limits
Eigen::VectorXd force_upper_lims(7);
force_upper_lims << 150, 150, 150, 150, 150, 150, 150;
robot->set_force_upper_limits(force_upper_lims, dof_names);
robot->set_force_lower_limits(-force_upper_lims, dof_names);
// Modify Acceleration Limits
Eigen::VectorXd acc_upper_lims(7);
acc_upper_lims << 1500, 1500, 1500, 1500, 1500, 1500, 1500;
robot->set_acceleration_upper_limits(acc_upper_lims, dof_names);
robot->set_acceleration_lower_limits(-acc_upper_lims, dof_names);
# Modify Position Limits
pos_upper_lims = np.array([2.096, 2.096, 2.096, 2.096, 2.096, 2.096, 2.096])
robot.set_position_upper_limits(pos_upper_lims, dof_names)
robot.set_position_lower_limits(-1*pos_upper_lims, dof_names)
# Modify Velocity Limits
vel_upper_lims = np.array([1.5, 1.5, 1.5, 1.5, 1.5, 1.5, 1.5])
robot.set_velocity_upper_limits(vel_upper_lims, dof_names)
robot.set_velocity_lower_limits(-1*vel_upper_lims, dof_names)
# Modify Force Limits
force_upper_lims = np.array([150, 150, 150, 150, 150, 150, 150])
robot.set_force_upper_limits(force_upper_lims, dof_names)
robot.set_force_lower_limits(-1*force_upper_lims, dof_names)
# Modify Acceleration Limits
acc_upper_lims = np.array([1500, 1500, 1500, 1500, 1500, 1500, 1500])
robot.set_acceleration_upper_limits(acc_upper_lims, dof_names)
robot.set_acceleration_lower_limits(-1*acc_upper_lims, dof_names)
You can also modify the damping coefficients, coulomb frictions and spring stiffness of every DOF:
// Modify Damping Coefficients
std::vector<double> damps = {0.4, 0.4, 0.4, 0.4, 0.4, 0.4, 0.4};
robot->set_damping_coeffs(damps, dof_names);
// Modify Coulomb Frictions
std::vector<double> cfrictions = {0.001, 0.001, 0.001, 0.001, 0.001, 0.001, 0.001};
robot->set_coulomb_coeffs(cfrictions, dof_names);
// Modify Spring Stiffness
std::vector<double> stiffnesses = {0.001, 0.001, 0.001, 0.001, 0.001, 0.001, 0.001};
robot->set_spring_stiffnesses(stiffnesses, dof_names);
# Modify Damping Coefficients
damps = [0.4, 0.4, 0.4, 0.4, 0.4, 0.4, 0.4]
robot.set_damping_coeffs(damps, dof_names)
# Modify Coulomb Frictions
cfrictions = [0.001, 0.001, 0.001, 0.001, 0.001, 0.001, 0.001]
robot.set_coulomb_coeffs(cfrictions, dof_names)
# Modify Spring Stiffness
stiffnesses = [0.001, 0.001, 0.001, 0.001, 0.001, 0.001, 0.001]
robot.set_spring_stiffnesses(stiffnesses, dof_names)
What are the supported sensors? How can I use an IMU?¶
Sensors in RobotDART can be added only through the simulator object. All of the sensors can be added without being attached to any body or joint but some of them can operate only when attached to something (e.g. ForceTorque
sensors).
Torque sensor¶
Torque sensors can be added to every joint of the robot:
Torque sensors measure the torque \(\tau \in \rm I\!R^n\) of the attached joint (where \(n\) is the DOFs of the joint):
Force-Torque sensor¶
Force-Torque sensors can be added to every joint of the robot:
Torque sensors measure the force \(\boldsymbol{F} \in \rm I\!R^3\), the torque \(\boldsymbol{\tau} \in \rm I\!R^3\) and the wrench \(\boldsymbol{\mathcal{F}} =\begin{bmatrix} \tau, F\end{bmatrix}\in \rm I\!R^6\) of the attached joint:
// matrix that contains the torque measurement for every joint (3d vector)
Eigen::MatrixXd ft_torques_measure(robot->num_dofs(), 3);
// matrix that contains the force measurement for every joint (3d vector)
Eigen::MatrixXd ft_forces_measure(robot->num_dofs(), 3);
// matrix that contains the wrench measurement for every joint (6d vector)[torque, force]
Eigen::MatrixXd ft_wrench_measure(robot->num_dofs(), 6);
ct = 0;
for (const auto& f_tq_sens : f_tq_sensors) {
ft_torques_measure.block<1, 3>(ct, 0) = f_tq_sens->torque();
ft_forces_measure.block<1, 3>(ct, 0) = f_tq_sens->force();
ft_wrench_measure.block<1, 6>(ct, 0) = f_tq_sens->wrench();
ct++;
}
# matrix that contains the torque measurement for every joint (3d vector)
ft_torques_measure = np.empty([robot.num_dofs(), 3])
# matrix that contains the force measurement for every joint (3d vector)
ft_forces_measure = np.empty([robot.num_dofs(), 3])
# matrix that contains the wrench measurement for every joint (6d vector)[torque, force]
ft_wrench_measure = np.empty([robot.num_dofs(), 6])
ct = 0
for f_tq_sens in f_tq_sensors:
ft_torques_measure[ct, :] = f_tq_sens.torque()
ft_forces_measure[ct, :] = f_tq_sens.force()
ft_wrench_measure[ct, :] = f_tq_sens.wrench()
ct += 1
IMU sensor¶
IMU sensors can be added to every link of the robot:
// Add IMU sensors to the robot
ct = 0;
std::vector<std::shared_ptr<robot_dart::sensor::IMU>> imu_sensors(robot->num_bodies());
for (const auto& body_node : robot->body_names()) {
// _imu(std::make_shared<sensor::IMU>(sensor::IMUConfig(body_node("head"), frequency))),
imu_sensors[ct++] = simu.add_sensor<robot_dart::sensor::IMU>(robot_dart::sensor::IMUConfig(robot->body_node(body_node), 1000));
}
IMU sensors measure the angular position vector \(\boldsymbol{\theta} \in \rm I\!R^3\), the angular velocity \(\boldsymbol{\omega} \in \rm I\!R^3\) and the linear acceleration \(\boldsymbol{\alpha} \in \rm I\!R^3\) of the attached link:
Eigen::MatrixXd imu_angular_positions_measure(robot->num_bodies(), 3);
Eigen::MatrixXd imu_angular_velocities_measure(robot->num_bodies(), 3);
Eigen::MatrixXd imu_linear_acceleration_measure(robot->num_bodies(), 3);
ct = 0;
for (const auto& imu_sens : imu_sensors) {
imu_angular_positions_measure.block<1, 3>(ct, 0) = imu_sens->angular_position_vec();
imu_angular_velocities_measure.block<1, 3>(ct, 0) = imu_sens->angular_velocity();
imu_linear_acceleration_measure.block<1, 3>(ct, 0) = imu_sens->linear_acceleration();
ct++;
}
imu_angular_positions_measure = np.empty([robot.num_bodies(), 3])
imu_angular_velocities_measure = np.empty([robot.num_bodies(), 3])
imu_linear_acceleration_measure = np.empty([robot.num_bodies(), 3])
ct = 0
for imu_sens in imu_sensors:
imu_angular_positions_measure[ct,:] = imu_sens.angular_position_vec()
imu_angular_velocities_measure[ct, :] = imu_sens.angular_velocity()
imu_linear_acceleration_measure[ct,:] = imu_sens.linear_acceleration()
ct += 1
RGB sensor¶
Any camera can be used as an RGB sensor:
We can easily save the image and/or transform it to grayscale:
RGB_D sensor¶
Any camera can also be configured to also record depth:
We can then read the RGB and depth images:
// get the depth image from a camera
// with a version for visualization or bigger differences in the output
auto rgb_d_image = camera->depth_image();
// and the raw values that can be used along with the camera parameters to transform the image to point-cloud
auto rgb_d_image_raw = camera->raw_depth_image();
We can save the depth images as well:
How can I spawn multiple robots in parallel?¶
Robot Pool (only in C++)¶
The best way to do so is to create a Robot pool. With a robot pool you:
- Minimize the overhead of loading robots (it happens only once!) or cloning robots (it never happens)
- Make sure that your robots are "clean" once released from each thread
- Focus on the important stuff rather than handling robots and threads
Let's see a more practical example:
- First we need to include the proper header:
- Then we create a
creator
function and the pool object:
namespace pool {
// This function should load one robot: here we load Talos
inline std::shared_ptr<robot_dart::Robot> robot_creator()
{
return std::make_shared<robot_dart::robots::Talos>();
}
// To create the object we need to pass the robot_creator function and the number of maximum parallel threads
robot_dart::RobotPool robot_pool(robot_creator, NUM_THREADS);
} // namespace pool
The creator
function is the function responsible for loading your robot. This should basically look like a standalone code to load or create a robot.
- Next, we create a few threads that utilize the robots (in your code you might be using OpenMP or TBB):
- An example evaluation function:
inline void eval_robot(int i)
{
// We get one available robot
auto robot = pool::robot_pool.get_robot();
std::cout << "Robot " << i << " got [" << robot->skeleton() << "]" << std::endl;
/// --- some robot_dart code ---
simulate_robot(robot);
// --- do something with the result
std::cout << "End of simulation " << i << std::endl;
// CRITICAL : free your robot !
pool::robot_pool.free_robot(robot);
std::cout << "Robot " << i << " freed!" << std::endl;
}
Python¶
We have not implemented this feature in Python
yet. One can emulate the RobotPool
behavior or create a custom parallel robot loader.
I need to simulate many worlds with camera sensors in parallel. How can I do this?¶
Below you can find an example showcasing the use of many worlds with camera sensors in parallel.
// Load robot from URDF
auto global_robot = std::make_shared<robot_dart::robots::Iiwa>();
std::vector<std::thread> workers;
// Set maximum number of parallel GL contexts (this is GPU-dependent)
robot_dart::gui::magnum::GlobalData::instance()->set_max_contexts(4);
// We want 15 parallel simulations with different GL context each
size_t N_workers = 15;
std::mutex mutex;
size_t id = 0;
// Launch the workers
for (size_t i = 0; i < N_workers; i++) {
workers.push_back(std::thread([&] {
mutex.lock();
size_t index = id++;
mutex.unlock();
// Get the GL context -- this is a blocking call
// will wait until one GL context is available
// get_gl_context(gl_context); // this call will not sleep between failed queries
get_gl_context_with_sleep(gl_context, 20); // this call will sleep 20ms between each failed query
// Do the simulation
auto robot = global_robot->clone();
robot_dart::RobotDARTSimu simu(0.001);
Eigen::VectorXd ctrl = robot_dart::make_vector({0., M_PI / 3., 0., -M_PI / 4., 0., 0., 0.});
auto controller = std::make_shared<robot_dart::control::PDControl>(ctrl);
robot->add_controller(controller);
controller->set_pd(300., 50.);
// Magnum graphics
robot_dart::gui::magnum::GraphicsConfiguration configuration = robot_dart::gui::magnum::WindowlessGraphics::default_configuration();
configuration.width = 1024;
configuration.height = 768;
auto graphics = std::make_shared<robot_dart::gui::magnum::WindowlessGraphics>(configuration);
simu.set_graphics(graphics);
// Position the camera differently for each thread to visualize the difference
graphics->look_at({0.4 * index, 3.5 - index * 0.1, 2.}, {0., 0., 0.25});
// record images from main camera/graphics
// graphics->set_recording(true); // WindowlessGLApplication records images by default
simu.add_robot(robot);
simu.run(6);
// Save the image for verification
robot_dart::gui::save_png_image("camera_" + std::to_string(index) + ".png",
graphics->image());
// Release the GL context for another thread to use
release_gl_context(gl_context);
}));
}
// Wait for all the workers
for (size_t i = 0; i < workers.size(); i++) {
workers[i].join();
}
robot = rd.Robot("arm.urdf", "arm", False)
robot.fix_to_world()
def test():
pid = os.getpid()
ii = pid%15
# create the controller
pdcontrol = rd.PDControl([0.0, 1.0, -1.5, 1.0], False)
# clone the robot
grobot = robot.clone()
# add the controller to the robot
grobot.add_controller(pdcontrol, 1.)
pdcontrol.set_pd(200., 20.)
# create the simulation object
simu = rd.RobotDARTSimu(0.001)
# set the graphics
graphics = rd.gui.WindowlessGraphics()
simu.set_graphics(graphics)
graphics.look_at([0.4 * ii, 3.5 - ii * 0.1, 2.], [0., 0., 0.25], [0., 0., 1.])
# add the robot and the floor
simu.add_robot(grobot)
simu.add_checkerboard_floor()
# run
simu.run(20.)
# save last frame for visualization purposes
img = graphics.image()
rd.gui.save_png_image('camera-' + str(ii) + '.png', img)
# helper function to run in parallel
def runInParallel(N):
proc = []
for i in range(N):
# rd.gui.run_with_gl_context accepts 2 parameters:
# (func, wait_time_in_ms)
# the func needs to be of the following format: void(), aka no return, no arguments
p = Process(target=rd.gui.run_with_gl_context, args=(test, 20))
p.start()
proc.append(p)
for p in proc:
p.join()
print('Running parallel evaluations')
N = 15
start = timer()
runInParallel(N)
end = timer()
print('Time:', end-start)
In C++ you are also able to pre-allocate a custom number of OpenGL contexts so that you can take advantage of stronger GPUs.
I do not know how to use waf. How can I detect RobotDART from CMake?¶
You need to use waf
to build RobotDART, but when installing the library a CMake module is installed. Thus it is possible use RobotDART in your code using CMake. You can find a complete example at cmake/example. In short the CMake would look like this:
Prerequisites:¶
- Ensure
RobotDart
andMagnum
are installed. - If
RobotDart
andMagnum
are not installed in standard locations, you can either: - Set the
CMAKE_PREFIX_PATH
environment variable: - Or, specify the paths directly when running
cmake
:
cmake_minimum_required(VERSION 3.10 FATAL_ERROR)
project(robot_dart_example)
# we ask for Magnum because we want to build the graphics
find_package(RobotDART REQUIRED OPTIONAL_COMPONENTS Magnum)
add_executable(robot_dart_example example.cpp)
target_link_libraries(robot_dart_example
RobotDART::Simu
)
if(RobotDART_Magnum_FOUND)
add_executable(robot_dart_example_graphics example.cpp)
target_link_libraries(robot_dart_example_graphics
RobotDART::Simu
RobotDART::Magnum
)
endif()
Where can I find complete working examples for either c++ or python?¶
Known Issues¶
Graphics issues on Mac¶
Recent versions of macOS do not fully support OpenGL (see here). RobotDART is using OpenGL for its graphical interface. For this reason, you might experience one of the following issues:
- Segfaults when shadows are enabled (see here). For this reason, on Mac PCs we are disabling by default the shadows.
- Status bar not showing correctly or not at all (see here)
- When using RobotDART with a graphics window (remember that you can use RobotDART with graphics without any window!), saving images or videos might not work properly (see here)
Finally, although not an issue, but this is related to Mac not fully supporting OpenGL, Windowsless GLContext
is unsupported in Mac. Thus, a few examples (like example_parallel.py
, see here) are not working on Mac PCs.
Graphics issues on WSL (Windows)¶
You might experience some issues with the graphical interface (see here).