From 4dbdd7f833853436c74e0f423745e1d425a5e912 Mon Sep 17 00:00:00 2001 From: Konstantinos Chatzilygeroudis Date: Fri, 2 Feb 2024 12:22:59 +0200 Subject: [PATCH] Update website --- docs/index.html | 2 +- docs/search/search_index.json | 2 +- docs/sitemap.xml | 590 +++++++++++++++++----------------- docs/sitemap.xml.gz | Bin 342 -> 342 bytes src/docs/docs/index.md | 2 +- 5 files changed, 298 insertions(+), 298 deletions(-) diff --git a/docs/index.html b/docs/index.html index dabe4efe..dbfed667 100644 --- a/docs/index.html +++ b/docs/index.html @@ -887,7 +887,7 @@ }

RobotDART

-

RobotDART is a C++11 robot simulator (with optional Python bindings) built on top of the DART physics engine. The RobotDART simulator is intended to be used by Robotics and Machine Learning researchers who want to write controllers or test learning algorithms without the delays and overhead that usually comes with other simulators (e.g., Gazebo, Coppelia-sim).

+

RobotDART is a C++ robot simulator (with optional Python bindings) built on top of the DART physics engine. The RobotDART simulator is intended to be used by Robotics and Machine Learning researchers who want to write controllers or test learning algorithms without the delays and overhead that usually comes with other simulators (e.g., Gazebo, Coppelia-sim).

For this reason, the simulator runs headless by default, and there is the possibility of rendering the scene (e.g., through a camera sensor) without opening a graphics window. All RobotDART's code is thread-safe (including graphics and camera sensors), and thus enables its users to use their code in parallel jobs in multicore computers.

Talos humanoid robot

In a few words, RobotDART combines:

diff --git a/docs/search/search_index.json b/docs/search/search_index.json index 315bd578..e93680a4 100644 --- a/docs/search/search_index.json +++ b/docs/search/search_index.json @@ -1 +1 @@ -{"config":{"lang":["en"],"separator":"[\\s\\-]+","pipeline":["stopWordFilter"]},"docs":[{"location":"","title":"Home","text":""},{"location":"#robotdart","title":"RobotDART","text":"

RobotDART is a C++11 robot simulator (with optional Python bindings) built on top of the DART physics engine. The RobotDART simulator is intended to be used by Robotics and Machine Learning researchers who want to write controllers or test learning algorithms without the delays and overhead that usually comes with other simulators (e.g., Gazebo, Coppelia-sim).

For this reason, the simulator runs headless by default, and there is the possibility of rendering the scene (e.g., through a camera sensor) without opening a graphics window. All RobotDART's code is thread-safe (including graphics and camera sensors), and thus enables its users to use their code in parallel jobs in multicore computers.

In a few words, RobotDART combines:

"},{"location":"#main-features","title":"Main Features","text":""},{"location":"#what-robotdart-is-not","title":"What RobotDART is not","text":""},{"location":"faq/","title":"FAQ","text":""},{"location":"faq/#frequently-asked-questions","title":"Frequently Asked Questions","text":"

This pages provides a user guide of the library through Frequently Asked Questions (FAQ).

"},{"location":"faq/#what-is-a-minimal-working-example-of-robotdart","title":"What is a minimal working example of RobotDART?","text":"

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.

C++Python
#include <robot_dart/robot_dart_simu.hpp>\n#ifdef GRAPHIC\n#include <robot_dart/gui/magnum/graphics.hpp>\n#endif\n
import RobotDART as rd\n
C++Python
auto robot = std::make_shared<robot_dart::Robot>(\"pexod.urdf\");\n
robot = rd.Robot(\"pexod.urdf\");\n
C++Python
robot->set_base_pose(robot_dart::make_tf({0., 0., 0.2}));\n
robot.set_base_pose([0., 0., 0., 0., 0., 0.2])\n
C++Python
robot_dart::RobotDARTSimu simu(0.001); // dt=0.001, 1KHz simulation\nsimu.add_floor();\nsimu.add_robot(robot);\n
simu = rd.RobotDARTSimu(0.001); # dt=0.001, 1KHz simulation\nsimu.add_floor();\nsimu.add_robot(robot);\n
C++Python
auto graphics = std::make_shared<robot_dart::gui::magnum::Graphics>();\nsimu.set_graphics(graphics);\ngraphics->look_at({0.5, 3., 0.75}, {0.5, 0., 0.2});\n
graphics = rd.gui.Graphics()\nsimu.set_graphics(graphics)\ngraphics.look_at([0.5, 3., 0.75], [0.5, 0., 0.2])\n
C++Python
simu.run(10.);\n
simu.run(10.)\n

"},{"location":"faq/#what-robots-are-supported-in-robotdart","title":"What robots are supported in RobotDART?","text":"

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).

"},{"location":"faq/#how-can-i-load-my-own-urdfsdfskelmjcf-file","title":"How can I load my own URDF/SDF/SKEL/MJCF file?","text":"

See the robots page for details.

"},{"location":"faq/#how-do-i-enable-graphics-in-my-code","title":"How do I enable graphics in my code?","text":"

To enable graphics in your code, you need to do the following:

C++Python
auto graphics = std::make_shared<robot_dart::gui::magnum::Graphics>();\nsimu.set_graphics(graphics);\ngraphics->look_at({0.5, 3., 0.75}, {0.5, 0., 0.2});\n
graphics = rd.gui.Graphics()\nsimu.set_graphics(graphics)\ngraphics.look_at([0.5, 3., 0.75], [0.5, 0., 0.2])\n
"},{"location":"faq/#i-want-to-have-multiple-camera-sensors-is-it-possible","title":"I want to have multiple camera sensors. Is it possible?","text":"

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:

C++Python
// Add camera\nauto camera = std::make_shared<robot_dart::sensor::Camera>(graphics->magnum_app(), 256, 256);\n
# Add camera\ncamera = rd.sensor.Camera(graphics.magnum_app(), 32, 32)\n
"},{"location":"faq/#how-do-i-record-a-video","title":"How do I record a video?","text":"

In order to record a video of what the main or any other camera \"sees\", you need to call the function record_video(path) of the graphics class:

C++Python
graphics->record_video(\"talos_dancing.mp4\");\n
graphics.record_video(\"talos_dancing.mp4\")\n

Or the camera class:

C++Python
// cameras can also record video\ncamera->record_video(\"video-camera.mp4\");\n
# cameras can also record video\ncamera.record_video(\"video-camera.mp4\")\n
"},{"location":"faq/#how-can-i-position-a-camera-to-the-environment","title":"How can I position a camera to the environment?","text":"

In order to position a camera inside the world, we need to use the lookAt method of the camera/graphics object:

C++Python
// set the position of the camera, and the position where the main camera is looking at\nEigen::Vector3d cam_pos = {-0.5, -3., 0.75};\nEigen::Vector3d cam_looks_at = {0.5, 0., 0.2};\ncamera->look_at(cam_pos, cam_looks_at);\n
# set the position of the camera, and the position where the main camera is looking at\ncam_pos = [-0.5, -3., 0.75]\ncam_looks_at = [0.5, 0., 0.2]\ncamera.look_at(cam_pos, cam_looks_at)\n
"},{"location":"faq/#how-can-i-attach-a-camera-to-a-moving-link","title":"How can I attach a camera to a moving link?","text":"

Cameras can be easily attached to a moving link:

C++Python
Eigen::Isometry3d tf;\ntf = Eigen::AngleAxisd(3.14, Eigen::Vector3d{1., 0., 0.});\ntf *= Eigen::AngleAxisd(1.57, Eigen::Vector3d{0., 0., 1.});\ntf.translation() = Eigen::Vector3d(0., 0., 0.1);\ncamera->attach_to_body(robot->body_node(\"iiwa_link_ee\"), tf); // cameras are looking towards -z by default\n
tf = dartpy.math.Isometry3()\nrot =  dartpy.math.AngleAxis(3.14, [1., 0., 0.])\nrot = rot.multiply( dartpy.math.AngleAxis(1.57, [0., 0., 1.])).to_rotation_matrix()\ntf.set_translation([0., 0., 0.1])\ncamera.attach_to_body(robot.body_node(\"iiwa_link_ee\"), tf) # cameras are looking towards -z by default\n
"},{"location":"faq/#how-can-i-manipulate-the-camera-object","title":"How can I manipulate the camera object?","text":"

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:

C++Python
camera->camera().set_far_plane(5.f);\ncamera->camera().set_near_plane(0.01f);\ncamera->camera().set_fov(60.0f);\n
camera.camera().set_far_plane(5.)\ncamera.camera().set_near_plane(0.01)\ncamera.camera().set_fov(60.0)\n

or all at once:

C++Python
camera->camera().set_camera_params(5., // far plane\n0.01f, // near plane\n60.0f, // field of view\n600, // width\n400 // height\n);\n
camera.camera().set_camera_params(5., #far plane\n0.01, #near plane\n60.0, # field of view\n600, # width\n400) #height\n

You can find a complete example at cameras.cpp.

"},{"location":"faq/#how-can-i-interact-with-the-camera","title":"How can I interact with the camera?","text":"

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.

"},{"location":"faq/#what-do-the-numbers-in-the-status-bar-mean","title":"What do the numbers in the status bar mean?","text":"

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.

"},{"location":"faq/#how-can-i-alter-the-graphics-scene-eg-change-lighting-conditions","title":"How can I alter the graphics scene (e.g., change lighting conditions)?","text":"

When creating a graphics object, you can pass a GraphicsConfiguration object that changes the default values:

C++Python
robot_dart::gui::magnum::GraphicsConfiguration configuration;\n// We can change the width/height of the window (or camera image dimensions)\nconfiguration.width = 1280;\nconfiguration.height = 960;\nconfiguration.title = \"Graphics Tutorial\"; // We can set a title for our window\n// We can change the configuration for shadows\nconfiguration.shadowed = true;\nconfiguration.transparent_shadows = true;\nconfiguration.shadow_map_size = 1024;\n// We can also alter some specifications for the lighting\nconfiguration.max_lights = 3; // maximum number of lights for our scene [default=3]\nconfiguration.specular_strength = 0.25; // strength of the specular component\n// Some extra configuration for the main camera\nconfiguration.draw_main_camera = true;\nconfiguration.draw_debug = true;\nconfiguration.draw_text = true;\n// We can also change the background color [default=black]\nconfiguration.bg_color = Eigen::Vector4d{1.0, 1.0, 1.0, 1.0};\n// Create the graphics object with the configuration as parameter\nauto graphics = std::make_shared<robot_dart::gui::magnum::Graphics>(configuration);\n
configuration = rd.gui.GraphicsConfiguration()\n# We can change the width/height of the window (or camera, dimensions)\nconfiguration.width = 1280\nconfiguration.height = 960\nconfiguration.title = \"Graphics Tutorial\"  # We can set a title for our window\n# We can change the configuration for shadows\nconfiguration.shadowed = True\nconfiguration.transparent_shadows = True\nconfiguration.shadow_map_size = 1024\n# We can also alter some specifications for the lighting\nconfiguration.max_lights = 3  # maximum number of lights for our scene\nconfiguration.specular_strength = 0.25  # strength og the specular component\n#  Some extra configuration for the main camera\nconfiguration.draw_main_camera = True\nconfiguration.draw_debug = True\nconfiguration.draw_text = True\n# We can also change the background color [default = black]\nconfiguration.bg_color = [1., 1., 1., 1.]\n# create the graphics object with the configuration as a parameter\ngraphics = rd.gui.Graphics(configuration)\n

You can disable or enable shadows on the fly as well:

C++Python
// Disable shadows\ngraphics->enable_shadows(false, false);\nsimu.run(1.);\n// Enable shadows only for non-transparent objects\ngraphics->enable_shadows(true, false);\nsimu.run(1.);\n// Enable shadows for transparent objects as well\ngraphics->enable_shadows(true, true);\nsimu.run(1.);\n
# Disable shadows\ngraphics.enable_shadows(False, False)\nsimu.run(1.)\n# Enable shadows only for non-transparent objects\ngraphics.enable_shadows(True, False)\nsimu.run(1.)\n# Enable shadows for transparent objects as well\ngraphics.enable_shadows(True, True)\nsimu.run(1.)\n

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:

C++Python
// Clear Lights\ngraphics->clear_lights();\n
# Clear Lights\ngraphics.clear_lights()\n

Then you must create a custom light material:

C++Python
// Create Light material\nMagnum::Float shininess = 1000.f;\nMagnum::Color4 white = {1.f, 1.f, 1.f, 1.f};\n// ambient, diffuse, specular\nauto custom_material = robot_dart::gui::magnum::gs::Material(white, white, white, shininess);\n
# Clear Light material\nshininess = 1000.\nwhite = magnum.Color4(1., 1., 1., 1.)\n# ambient, diffuse, specular\ncustom_material = rd.gui.Material(white, white, white, shininess)\n

Now you can add on ore more of the following lights:

Point Light:

C++Python
// Create point light\nMagnum::Vector3 position = {0.f, 0.f, 2.f};\nMagnum::Float intensity = 1.f;\nMagnum::Vector3 attenuation_terms = {1.f, 0.f, 0.f};\nauto point_light = robot_dart::gui::magnum::gs::create_point_light(position, custom_material, intensity, attenuation_terms);\ngraphics->add_light(point_light);\n
# Create point light\nposition = magnum.Vector3(0., 0., 2.)\nintensity = 1.\nattenuation_terms = magnum.Vector3(1., 0., 0.)\npoint_light = rd.gui.create_point_light(position, custom_material, intensity, attenuation_terms)\ngraphics.add_light(point_light)\n

Spot Light:

C++Python
// Create spot light\nMagnum::Vector3 position = {0.f, 0.f, 1.f};\nMagnum::Vector3 direction = {-1.f, -1.f, -1.f};\nMagnum::Float intensity = 1.f;\nMagnum::Vector3 attenuation_terms = {1.f, 0.f, 0.f};\nMagnum::Float spot_exponent = M_PI;\nMagnum::Float spot_cut_off = M_PI / 8;\nauto spot_light = robot_dart::gui::magnum::gs::create_spot_light(position, custom_material, direction, spot_exponent, spot_cut_off, intensity, attenuation_terms);\ngraphics->add_light(spot_light);\n
# Create spot light\nposition = magnum.Vector3(0., 0., 1.)\ndirection = magnum.Vector3(-1, -1, -1)\nintensity = 1.\nattenuation_terms = magnum.Vector3(1., 0., 0.)\nspot_exponent = np.pi\nspot_cut_off = np.pi / 8\nspot_light = rd.gui.create_spot_light(position, custom_material, direction, spot_exponent, spot_cut_off, intensity, attenuation_terms)\ngraphics.add_light(spot_light)\n

Directional Light:

C++Python
// Create directional light\nMagnum::Vector3 direction = {-1.f, -1.f, -1.f};\nauto directional_light = robot_dart::gui::magnum::gs::create_directional_light(direction, custom_material);\ngraphics->add_light(directional_light);\n
# Create directional light\ndirection = magnum.Vector3(-1, -1, -1)\ndirectional_light = rd.gui.create_directional_light(direction, custom_material)\ngraphics.add_light(directional_light)\n
"},{"location":"faq/#i-want-to-visualize-a-target-configuration-of-my-robot-is-this-possible","title":"I want to visualize a target configuration of my robot, is this possible?","text":"

Yes this is possible. RobotDART gives the ability to create a clone of your robot that has no physics, no contacts, just visuals:

C++Python
// Add a ghost robot; only visuals, no dynamics, no collision\nauto ghost = robot->clone_ghost();\nsimu.add_robot(ghost);\n
# Add a ghost robot; only visuals, no dynamics, no collision\nghost = robot.clone_ghost()\nsimu.add_robot(ghost)\n
"},{"location":"faq/#how-can-i-control-my-robot","title":"How can I control my robot ?","text":"

PD control

C++Python
// add a PD-controller to the arm\n// set desired positions\nEigen::VectorXd ctrl = robot_dart::make_vector({0., M_PI / 4., 0., -M_PI / 4., 0., M_PI / 2., 0., 0.});\n// add the controller to the robot\nauto controller = std::make_shared<robot_dart::control::PDControl>(ctrl);\nrobot->add_controller(controller);\ncontroller->set_pd(300., 50.);\n
# add a PD-controller to the arm\n# set desired positions\nctrl = [0., np.pi / 4., 0., -np.pi / 4., 0., np.pi / 2., 0., 0.]\n# add the controller to the robot\ncontroller = rd.PDControl(ctrl)\nrobot.add_controller(controller)\ncontroller.set_pd(300., 50.)\n

Simple control

C++Python
auto controller1 = std::make_shared<robot_dart::control::SimpleControl>(ctrl);\nrobot->add_controller(controller1);\n
controller1 = rd.SimpleControl(ctrl)\nrobot.add_controller(controller1)\n

Robot control

C++Python
class MyController : public robot_dart::control::RobotControl {\npublic:\nMyController() : robot_dart::control::RobotControl() {}\nMyController(const Eigen::VectorXd& ctrl, bool full_control) : robot_dart::control::RobotControl(ctrl, full_control) {}\nMyController(const Eigen::VectorXd& ctrl, const std::vector<std::string>& dof_names) : robot_dart::control::RobotControl(ctrl, dof_names) {}\nvoid configure() override\n{\n_active = true;\n}\nEigen::VectorXd calculate(double) override\n{\nauto robot = _robot.lock();\nEigen::VectorXd cmd = 100. * (_ctrl - robot->positions(_controllable_dofs));\nreturn cmd;\n}\nstd::shared_ptr<robot_dart::control::RobotControl> clone() const override\n{\nreturn std::make_shared<MyController>(*this);\n}\n};\n
class MyController(rd.RobotControl):\ndef __init__(self, ctrl, full_control):\nrd.RobotControl.__init__(self, ctrl, full_control)\ndef __init__(self, ctrl, controllable_dofs):\nrd.RobotControl.__init__(self, ctrl, controllable_dofs)\ndef configure(self):\nself._active = True\ndef calculate(self, t):\ntarget = np.array([self._ctrl])\ncmd = 100*(target-self.robot().positions(self._controllable_dofs))\nreturn cmd[0]\n# TO-DO: This is NOT working at the moment!\ndef clone(self):\nreturn MyController(self._ctrl, self._controllable_dofs)\n
"},{"location":"faq/#is-there-a-way-to-control-the-simulation-timestep","title":"Is there a way to control the simulation timestep?","text":"

When creating a RobotDARTSimu object you choose the simulation timestep:

C++Python
// choose time step of 0.001 seconds\nrobot_dart::RobotDARTSimu simu(0.001);\n
# choose time step of 0.001 seconds\nsimu = rd.RobotDARTSimu(0.001)\n

which can later be modified by:

C++Python
// set timestep to 0.005 and update control frequency(bool)\nsimu.set_timestep(0.005, true);\n
# set timestep to 0.005 and update control frequency(bool)\nsimu.set_timestep(0.005, True)\n
"},{"location":"faq/#i-want-to-simulate-a-mars-environment-is-it-possible-to-change-the-gravitational-force-of-the-simulation-environment","title":"I want to simulate a mars environment, is it possible to change the gravitational force of the simulation environment?","text":"

Yes you can modify the gravitational forces 3-dimensional vector of the simulation:

C++Python
// Set gravitational force of mars\nEigen::Vector3d mars_gravity = {0., 0., -3.721};\nsimu.set_gravity(mars_gravity);\n
# set gravitational force of mars\nmars_gravity = [0., 0., -3.721]\nsimu.set_gravity(mars_gravity)\n
"},{"location":"faq/#which-collision-detectors-are-available-what-are-their-differences-how-can-i-choose-between-them","title":"Which collision detectors are available? What are their differences? How can I choose between them?","text":"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:

C++Python
simu.set_collision_detector(\"fcl\"); // collision_detector can be \"dart\", \"fcl\", \"ode\" or \"bullet\" (case does not matter)\n
simu.set_collision_detector(\"fcl\") # collision_detector can be \"dart\", \"fcl\", \"ode\" or \"bullet\" (case does not matter)\n
"},{"location":"faq/#my-robot-does-not-self-collide-how-can-i-change-this","title":"My robot does not self-collide. How can I change this?","text":"

One possible cause may be the fact that self collision is disabled, you can check and change this:

C++Python
if (!robot->self_colliding()) {\nstd::cout << \"Self collision is not enabled\" << std::endl;\n// set self collisions to true and adjacent collisions to false\nrobot->set_self_collision(true, false);\n}\n
if(not robot.self_colliding()):\nprint(\"Self collision is not enabled\")\n# set self collisions to true and adjacent collisions to false\nrobot.set_self_collision(True, False)\n
"},{"location":"faq/#how-can-i-compute-kinematicdynamic-properties-of-my-robot-eg-jacobians-mass-matrix","title":"How can I compute kinematic/dynamic properties of my robot (e.g., Jacobians, Mass Matrix)?","text":"

Kinematic Properties:

C++Python
// Get Joint Positions(Angles)\nauto joint_positions = robot->positions();\n// Get Joint Velocities\nauto joint_vels = robot->velocities();\n// Get Joint Accelerations\nauto joint_accs = robot->accelerations();\n// Get link_name(str) Transformation matrix with respect to the world frame.\nauto eef_tf = robot->body_pose(link_name);\n// Get translation vector from transformation matrix\nauto eef_pos = eef_tf.translation();\n// Get rotation matrix from tranformation matrix\nauto eef_rot = eef_tf.rotation();\n// Get link_name 6d pose vector [logmap(eef_tf.linear()), eef_tf.translation()]\nauto eef_pose_vec = robot->body_pose_vec(link_name);\n// Get link_name 6d velocity vector [angular, cartesian]\nauto eef_vel = robot->body_velocity(link_name);\n// Get link_name 6d acceleration vector [angular, cartesian]\nauto eef_acc = robot->body_acceleration(link_name);\n// Jacobian targeting the origin of link_name(str)\nauto jacobian = robot->jacobian(link_name);\n// Jacobian time derivative\nauto jacobian_deriv = robot->jacobian_deriv(link_name);\n// Center of Mass Jacobian\nauto com_jacobian = robot->com_jacobian();\n// Center of Mass Jacobian Time Derivative\nauto com_jacobian_deriv = robot->com_jacobian_deriv();\n
# Get Joint Positions(Angles)\njoint_positions = robot.positions()\n# Get Joint Velocities\njoint_vels = robot.velocities()\n# Get Joint Accelerations\njoint_accs = robot.accelerations()\n# Get link_name(str) Transformation matrix with respect to the world frame.\neef_tf = robot.body_pose(link_name)\n# Get translation vector from transformation matrix\neef_pos = eef_tf.translation()\n# Get rotation matrix from tranformation matrix\neef_rot = eef_tf.rotation()\n# Get link_name 6d pose vector [logmap(eef_tf.linear()), eef_tf.translation()]\neef_pose_vec = robot.body_pose_vec(link_name)\n# Get link_name 6d velocity vector [angular, cartesian]\neef_vel = robot.body_velocity(link_name)\n# Get link_name 6d acceleration vector [angular, cartesian]\neef_acc = robot.body_acceleration(link_name)\n# Jacobian targeting the origin of link_name(str)\njacobian = robot.jacobian(link_name)\n# Jacobian time derivative\njacobian_deriv = robot.jacobian_deriv(link_name)\n# Center of Mass Jacobian\ncom_jacobian = robot.com_jacobian()\n# Center of Mass Jacobian Time Derivative\ncom_jacobian_deriv = robot.com_jacobian_deriv()\n

Dynamic Properties:

C++Python
// Get Joint Forces\nauto joint_forces = robot->forces();\n// Get link's mass\nauto eef_mass = robot->body_mass(link_name);\n// Mass Matrix of robot\nauto mass_matrix = robot->mass_matrix();\n// Inverse of Mass Matrix\nauto inv_mass_matrix = robot->inv_mass_matrix();\n// Augmented Mass matrix\nauto aug_mass_matrix = robot->aug_mass_matrix();\n// Inverse of Augmented Mass matrix\nauto inv_aug_mass_matrix = robot->inv_aug_mass_matrix();\n// Coriolis Force vector\nauto coriolis = robot->coriolis_forces();\n// Gravity Force vector\nauto gravity = robot->gravity_forces();\n// Combined vector of Coriolis Force and Gravity Force\nauto coriolis_gravity = robot->coriolis_gravity_forces();\n// Constraint Force Vector\nauto constraint_forces = robot->constraint_forces();\n
# Get Joint Forces\njoint_forces = robot.forces()\n# Get link's mass\neef_mass = robot.body_mass(link_name)\n# Mass Matrix of robot\nmass_matrix = robot.mass_matrix()\n# Inverse of Mass Matrix\ninv_mass_matrix = robot.inv_mass_matrix()\n# Augmented Mass matrix\naug_mass_matrix = robot.aug_mass_matrix()\n# Inverse of Augmented Mass matrix\ninv_aug_mass_matrix = robot.inv_aug_mass_matrix()\n# Coriolis Force vector\ncoriolis = robot.coriolis_forces()\n# Gravity Force vector\ngravity = robot.gravity_forces()\n# Combined vector of Coriolis Force and Gravity Force\ncoriolis_gravity = robot.coriolis_gravity_forces()\n# NOT IMPLEMENTED\n# # Constraint Force Vector\n# constraint_forces = robot.constraint_forces()\n
"},{"location":"faq/#is-there-a-way-to-change-the-joint-properties-eg-actuation-friction","title":"Is there a way to change the joint properties (e.g., actuation, friction)?","text":"

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:

C++Python
// Set all DoFs to same actuator\nrobot->set_actuator_types(\"servo\"); // actuator types can be \"servo\", \"torque\", \"velocity\", \"passive\", \"locked\", \"mimic\"\n// You can also set actuator types separately\nrobot->set_actuator_type(\"torque\", \"iiwa_joint_5\");\n
# Set all DoFs to same actuator\n# actuator types can be \"servo\", \"torque\", \"velocity\", \"passive\", \"locked\", \"mimic\"\nrobot.set_actuator_types(\"servo\")\n# You can also set actuator types separately\nrobot.set_actuator_type(\"torque\", \"iiwa_joint_5\")\n

To enable position and velocity limits for the actuators:

C++Python
// \u0395nforce joint position and velocity limits\nrobot->set_position_enforced(true);\n
# \u0395nforce joint position and velocity limits\nrobot.set_position_enforced(True)\n

Every DOF's limits (position, velocity, acceleration, force) can be modified:

C++Python
// Modify Position Limits\nEigen::VectorXd pos_upper_lims(7);\npos_upper_lims << 2.096, 2.096, 2.096, 2.096, 2.096, 2.096, 2.096;\nrobot->set_position_upper_limits(pos_upper_lims, dof_names);\nrobot->set_position_lower_limits(-pos_upper_lims, dof_names);\n// Modify Velocity Limits\nEigen::VectorXd vel_upper_lims(7);\nvel_upper_lims << 1.5, 1.5, 1.5, 1.5, 1.5, 1.5, 1.5;\nrobot->set_velocity_upper_limits(vel_upper_lims, dof_names);\nrobot->set_velocity_lower_limits(-vel_upper_lims, dof_names);\n// Modify Force Limits\nEigen::VectorXd force_upper_lims(7);\nforce_upper_lims << 150, 150, 150, 150, 150, 150, 150;\nrobot->set_force_upper_limits(force_upper_lims, dof_names);\nrobot->set_force_lower_limits(-force_upper_lims, dof_names);\n// Modify Acceleration Limits\nEigen::VectorXd acc_upper_lims(7);\nacc_upper_lims << 1500, 1500, 1500, 1500, 1500, 1500, 1500;\nrobot->set_acceleration_upper_limits(acc_upper_lims, dof_names);\nrobot->set_acceleration_lower_limits(-acc_upper_lims, dof_names);\n
# Modify Position Limits\npos_upper_lims = np.array([2.096, 2.096, 2.096, 2.096, 2.096, 2.096, 2.096])\nrobot.set_position_upper_limits(pos_upper_lims, dof_names)\nrobot.set_position_lower_limits(-1*pos_upper_lims, dof_names)\n# Modify Velocity Limits\nvel_upper_lims = np.array([1.5, 1.5, 1.5, 1.5, 1.5, 1.5, 1.5])\nrobot.set_velocity_upper_limits(vel_upper_lims, dof_names)\nrobot.set_velocity_lower_limits(-1*vel_upper_lims, dof_names)\n# Modify Force Limits\nforce_upper_lims = np.array([150, 150, 150, 150, 150, 150, 150])\nrobot.set_force_upper_limits(force_upper_lims, dof_names)\nrobot.set_force_lower_limits(-1*force_upper_lims, dof_names)\n# Modify Acceleration Limits\nacc_upper_lims = np.array([1500, 1500, 1500, 1500, 1500, 1500, 1500])\nrobot.set_acceleration_upper_limits(acc_upper_lims, dof_names)\nrobot.set_acceleration_lower_limits(-1*acc_upper_lims, dof_names)\n

You can also modify the damping coefficients, coulomb frictions and spring stiffness of every DOF:

C++Python
// Modify Damping Coefficients\nstd::vector<double> damps = {0.4, 0.4, 0.4, 0.4, 0.4, 0.4, 0.4};\nrobot->set_damping_coeffs(damps, dof_names);\n// Modify Coulomb Frictions\nstd::vector<double> cfrictions = {0.001, 0.001, 0.001, 0.001, 0.001, 0.001, 0.001};\nrobot->set_coulomb_coeffs(cfrictions, dof_names);\n// Modify  Spring Stiffness\nstd::vector<double> stiffnesses = {0.001, 0.001, 0.001, 0.001, 0.001, 0.001, 0.001};\nrobot->set_spring_stiffnesses(stiffnesses, dof_names);\n
# Modify Damping Coefficients\ndamps = [0.4, 0.4, 0.4, 0.4, 0.4, 0.4, 0.4]\nrobot.set_damping_coeffs(damps, dof_names)\n# Modify Coulomb Frictions\ncfrictions = [0.001, 0.001, 0.001, 0.001, 0.001, 0.001, 0.001]\nrobot.set_coulomb_coeffs(cfrictions, dof_names)\n# Modify  Spring Stiffness\nstiffnesses = [0.001, 0.001, 0.001, 0.001, 0.001, 0.001, 0.001]\nrobot.set_spring_stiffnesses(stiffnesses, dof_names)\n
"},{"location":"faq/#what-are-the-supported-sensors-how-can-i-use-an-imu","title":"What are the supported sensors? How can I use an IMU?","text":"

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).

"},{"location":"faq/#torque-sensor","title":"Torque sensor","text":"

Torque sensors can be added to every joint of the robot:

C++Python
// Add torque sensors to the robot\nint ct = 0;\nstd::vector<std::shared_ptr<robot_dart::sensor::Torque>> tq_sensors(robot->num_dofs());\nfor (const auto& joint : robot->dof_names())\ntq_sensors[ct++] = simu.add_sensor<robot_dart::sensor::Torque>(robot, joint, 1000);\n
# Add torque sensors to the robot\ntq_sensors = np.empty(robot.num_dofs(), dtype=rd.sensor.Torque)\nct = 0\nfor joint in robot.dof_names():\nsimu.add_sensor(rd.sensor.Torque(robot, joint, 1000))\ntq_sensors[ct] = simu.sensors()[-1]\nct += 1\n

Torque sensors measure the torque \\(\\tau \\in \\rm I\\!R^n\\) of the attached joint (where \\(n\\) is the DOFs of the joint):

C++Python
// vector that contains the torque measurement for every joint (scalar)\nEigen::VectorXd torques_measure(robot->num_dofs());\nfor (const auto& tq_sens : tq_sensors)\ntorques_measure.block<1, 1>(ct++, 0) = tq_sens->torques();\n
# vector that contains the torque measurement for every joint (scalar)\ntorques_measure = np.empty(robot.num_dofs())\nct = 0\nfor tq_sens in tq_sensors:\ntorques_measure[ct] = tq_sens.torques()\nct += 1\n
"},{"location":"faq/#force-torque-sensor","title":"Force-Torque sensor","text":"

Force-Torque sensors can be added to every joint of the robot:

C++Python
// Add force-torque sensors to the robot\nct = 0;\nstd::vector<std::shared_ptr<robot_dart::sensor::ForceTorque>> f_tq_sensors(robot->num_dofs());\nfor (const auto& joint : robot->dof_names())\nf_tq_sensors[ct++] = simu.add_sensor<robot_dart::sensor::ForceTorque>(robot, joint, 1000, \"parent_to_child\");\n
# Add force-torque sensors to the robot\nf_tq_sensors = np.empty(robot.num_dofs(), dtype=rd.sensor.ForceTorque)\nct = 0\nfor joint in robot.dof_names():\nsimu.add_sensor(rd.sensor.ForceTorque(\nrobot, joint, 1000, \"parent_to_child\"))\nf_tq_sensors[ct] = simu.sensors()[-1]\nprint(f_tq_sensors)\nct += 1\n

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:

C++Python
//  matrix that contains the torque measurement for every joint (3d vector)\nEigen::MatrixXd ft_torques_measure(robot->num_dofs(), 3);\n//  matrix that contains the force measurement for every joint (3d vector)\nEigen::MatrixXd ft_forces_measure(robot->num_dofs(), 3);\n//  matrix that contains the wrench measurement for every joint (6d vector)[torque, force]\nEigen::MatrixXd ft_wrench_measure(robot->num_dofs(), 6);\nct = 0;\nfor (const auto& f_tq_sens : f_tq_sensors) {\nft_torques_measure.block<1, 3>(ct, 0) = f_tq_sens->torque();\nft_forces_measure.block<1, 3>(ct, 0) = f_tq_sens->force();\nft_wrench_measure.block<1, 6>(ct, 0) = f_tq_sens->wrench();\nct++;\n}\n
#  matrix that contains the torque measurement for every joint (3d vector)\nft_torques_measure = np.empty([robot.num_dofs(), 3])\n#  matrix that contains the force measurement for every joint (3d vector)\nft_forces_measure = np.empty([robot.num_dofs(), 3])\n#  matrix that contains the wrench measurement for every joint (6d vector)[torque, force]\nft_wrench_measure = np.empty([robot.num_dofs(), 6])\nct = 0\nfor f_tq_sens in f_tq_sensors:\nft_torques_measure[ct, :] = f_tq_sens.torque()\nft_forces_measure[ct, :] = f_tq_sens.force()\nft_wrench_measure[ct, :] = f_tq_sens.wrench()\nct += 1\n
"},{"location":"faq/#imu-sensor","title":"IMU sensor","text":"

IMU sensors can be added to every link of the robot:

C++Python
// Add IMU sensors to the robot\nct = 0;\nstd::vector<std::shared_ptr<robot_dart::sensor::IMU>> imu_sensors(robot->num_bodies());\nfor (const auto& body_node : robot->body_names()) {\n// _imu(std::make_shared<sensor::IMU>(sensor::IMUConfig(body_node(\"head\"), frequency))),\nimu_sensors[ct++] = simu.add_sensor<robot_dart::sensor::IMU>(robot_dart::sensor::IMUConfig(robot->body_node(body_node), 1000));\n}\n
# Add IMU sensors to the robot\nct = 0\nimu_sensors = np.empty(robot.num_bodies(), dtype=rd.sensor.IMU)\nfor body_node in robot.body_names():\nsimu.add_sensor(rd.sensor.IMU(\nrd.sensor.IMUConfig(robot.body_node(body_node), 1000)))\nimu_sensors[ct] = simu.sensors()[-1]\nct += 1\n

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:

C++Python
Eigen::MatrixXd imu_angular_positions_measure(robot->num_bodies(), 3);\nEigen::MatrixXd imu_angular_velocities_measure(robot->num_bodies(), 3);\nEigen::MatrixXd imu_linear_acceleration_measure(robot->num_bodies(), 3);\nct = 0;\nfor (const auto& imu_sens : imu_sensors) {\nimu_angular_positions_measure.block<1, 3>(ct, 0) = imu_sens->angular_position_vec();\nimu_angular_velocities_measure.block<1, 3>(ct, 0) = imu_sens->angular_velocity();\nimu_linear_acceleration_measure.block<1, 3>(ct, 0) = imu_sens->linear_acceleration();\nct++;\n}\n
imu_angular_positions_measure = np.empty([robot.num_bodies(), 3])\nimu_angular_velocities_measure = np.empty([robot.num_bodies(), 3])\nimu_linear_acceleration_measure = np.empty([robot.num_bodies(), 3])\nct = 0\nfor imu_sens in imu_sensors:\nimu_angular_positions_measure[ct,:] = imu_sens.angular_position_vec()\nimu_angular_velocities_measure[ct, :] = imu_sens.angular_velocity()\nimu_linear_acceleration_measure[ct,:] = imu_sens.linear_acceleration()\nct += 1\n
"},{"location":"faq/#rgb-sensor","title":"RGB sensor","text":"

Any camera can be used as an RGB sensor:

C++Python
// a nested std::vector (w*h*3) of the last image taken can be retrieved\nauto rgb_image = camera->image();\n
# a nested array (w*h*3) of the last image taken can be retrieved\nrgb_image = camera.image()\n

We can easily save the image and/or transform it to grayscale:

C++Python
// a nested std::vector (w*h*3) of the last image taken can be retrieved\nauto rgb_image = camera->image();\n
# a nested array (w*h*3) of the last image taken can be retrieved\nrgb_image = camera.image()\n
"},{"location":"faq/#rgb_d-sensor","title":"RGB_D sensor","text":"

Any camera can also be configured to also record depth:

C++Python
camera->camera().record(true, true); // cameras are recording color images by default, enable depth images as well for this example\n
# cameras are recording color images by default, enable depth images as well for this example\ncamera.camera().record(True, True)\n

We can then read the RGB and depth images:

C++Python
// get the depth image from a camera\n// with a version for visualization or bigger differences in the output\nauto rgb_d_image = camera->depth_image();\n// and the raw values that can be used along with the camera parameters to transform the image to point-cloud\nauto rgb_d_image_raw = camera->raw_depth_image();\n
# get the depth image from a camera\n# with a version for visualization or bigger differences in the output\nrgb_d_image = camera.depth_image()\n# and the raw values that can be used along with the camera parameters to transform the image to point-cloud\nrgb_d_image_raw = camera.raw_depth_image()\n

We can save the depth images as well:

C++Python
robot_dart::gui::save_png_image(\"camera-depth.png\", rgb_d_image);\nrobot_dart::gui::save_png_image(\"camera-depth-raw.png\", rgb_d_image_raw);\n
rd.gui.save_png_image(\"camera-depth.png\", rgb_d_image)\nrd.gui.save_png_image(\"camera-depth-raw.png\", rgb_d_image_raw)\n
"},{"location":"faq/#how-can-i-spawn-multiple-robots-in-parallel","title":"How can I spawn multiple robots in parallel?","text":""},{"location":"faq/#robot-pool-only-in-c","title":"Robot Pool (only in C++)","text":"

The best way to do so is to create a Robot pool. With a robot pool you:

Let's see a more practical example:

C++
#include <robot_dart/robot_pool.hpp>\n
C++
namespace pool {\n// This function should load one robot: here we load Talos\ninline std::shared_ptr<robot_dart::Robot> robot_creator()\n{\nreturn std::make_shared<robot_dart::robots::Talos>();\n}\n// To create the object we need to pass the robot_creator function and the number of maximum parallel threads\nrobot_dart::RobotPool robot_pool(robot_creator, NUM_THREADS);\n} // namespace pool\n

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.

C++
// for the example, we run NUM_THREADS threads of eval_robot()\nstd::vector<std::thread> threads(NUM_THREADS * 2); // *2 to see some reuse\nfor (size_t i = 0; i < threads.size(); ++i)\nthreads[i] = std::thread(eval_robot, i); // eval_robot is the function that uses the robot\n
C++
inline void eval_robot(int i)\n{\n// We get one available robot\nauto robot = pool::robot_pool.get_robot();\nstd::cout << \"Robot \" << i << \" got [\" << robot->skeleton() << \"]\" << std::endl;\n/// --- some robot_dart code ---\nsimulate_robot(robot);\n// --- do something with the result\nstd::cout << \"End of simulation \" << i << std::endl;\n// CRITICAL : free your robot !\npool::robot_pool.free_robot(robot);\nstd::cout << \"Robot \" << i << \" freed!\" << std::endl;\n}\n
"},{"location":"faq/#python","title":"Python","text":"

We have not implemented this feature in Python yet. One can emulate the RobotPool behavior or create a custom parallel robot loader.

"},{"location":"faq/#i-need-to-simulate-many-worlds-with-camera-sensors-in-parallel-how-can-i-do-this","title":"I need to simulate many worlds with camera sensors in parallel. How can I do this?","text":"

Below you can find an example showcasing the use of many worlds with camera sensors in parallel.

C++Python
// Load robot from URDF\nauto global_robot = std::make_shared<robot_dart::robots::Iiwa>();\nstd::vector<std::thread> workers;\n// Set maximum number of parallel GL contexts (this is GPU-dependent)\nrobot_dart::gui::magnum::GlobalData::instance()->set_max_contexts(4);\n// We want 15 parallel simulations with different GL context each\nsize_t N_workers = 15;\nstd::mutex mutex;\nsize_t id = 0;\n// Launch the workers\nfor (size_t i = 0; i < N_workers; i++) {\nworkers.push_back(std::thread([&] {\nmutex.lock();\nsize_t index = id++;\nmutex.unlock();\n// Get the GL context -- this is a blocking call\n// will wait until one GL context is available\n// get_gl_context(gl_context); // this call will not sleep between failed queries\nget_gl_context_with_sleep(gl_context, 20); // this call will sleep 20ms between each failed query\n// Do the simulation\nauto robot = global_robot->clone();\nrobot_dart::RobotDARTSimu simu(0.001);\nEigen::VectorXd ctrl = robot_dart::make_vector({0., M_PI / 3., 0., -M_PI / 4., 0., 0., 0.});\nauto controller = std::make_shared<robot_dart::control::PDControl>(ctrl);\nrobot->add_controller(controller);\ncontroller->set_pd(300., 50.);\n// Magnum graphics\nrobot_dart::gui::magnum::GraphicsConfiguration configuration = robot_dart::gui::magnum::WindowlessGraphics::default_configuration();\nconfiguration.width = 1024;\nconfiguration.height = 768;\nauto graphics = std::make_shared<robot_dart::gui::magnum::WindowlessGraphics>(configuration);\nsimu.set_graphics(graphics);\n// Position the camera differently for each thread to visualize the difference\ngraphics->look_at({0.4 * index, 3.5 - index * 0.1, 2.}, {0., 0., 0.25});\n// record images from main camera/graphics\n// graphics->set_recording(true); // WindowlessGLApplication records images by default\nsimu.add_robot(robot);\nsimu.run(6);\n// Save the image for verification\nrobot_dart::gui::save_png_image(\"camera_\" + std::to_string(index) + \".png\",\ngraphics->image());\n// Release the GL context for another thread to use\nrelease_gl_context(gl_context);\n}));\n}\n// Wait for all the workers\nfor (size_t i = 0; i < workers.size(); i++) {\nworkers[i].join();\n}\n
robot = rd.Robot(\"arm.urdf\", \"arm\", False)\nrobot.fix_to_world()\ndef test():\npid = os.getpid()\nii = pid%15\n# create the controller\npdcontrol = rd.PDControl([0.0, 1.0, -1.5, 1.0], False)\n# clone the robot\ngrobot = robot.clone()\n# add the controller to the robot\ngrobot.add_controller(pdcontrol, 1.)\npdcontrol.set_pd(200., 20.)\n# create the simulation object\nsimu = rd.RobotDARTSimu(0.001)\n# set the graphics\ngraphics = rd.gui.WindowlessGraphics()\nsimu.set_graphics(graphics)\ngraphics.look_at([0.4 * ii, 3.5 - ii * 0.1, 2.], [0., 0., 0.25], [0., 0., 1.])\n# add the robot and the floor\nsimu.add_robot(grobot)\nsimu.add_checkerboard_floor()\n# run\nsimu.run(20.)\n# save last frame for visualization purposes\nimg = graphics.image()\nrd.gui.save_png_image('camera-' + str(ii) + '.png', img)\n# helper function to run in parallel\ndef runInParallel(N):\nproc = []\nfor i in range(N):\n# rd.gui.run_with_gl_context accepts 2 parameters:\n#    (func, wait_time_in_ms)\n#    the func needs to be of the following format: void(), aka no return, no arguments\np = Process(target=rd.gui.run_with_gl_context, args=(test, 20))\np.start()\nproc.append(p)\nfor p in proc:\np.join()\nprint('Running parallel evaluations')\nN = 15\nstart = timer()\nrunInParallel(N)\nend = timer()\nprint('Time:', end-start)\n

In C++ you are also able to pre-allocate a custom number of OpenGL contexts so that you can take advantage of stronger GPUs.

"},{"location":"faq/#i-do-not-know-how-to-use-waf-how-can-i-detect-robotdart-from-cmake","title":"I do not know how to use waf. How can I detect RobotDART from CMake?","text":"

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:

cmake_minimum_required(VERSION 3.10 FATAL_ERROR)\nproject(robot_dart_example)\n# we ask for Magnum because we want to build the graphics\nfind_package(RobotDART REQUIRED OPTIONAL_COMPONENTS Magnum)\nadd_executable(robot_dart_example example.cpp)\ntarget_link_libraries(robot_dart_example\nRobotDART::Simu\n)\nif(RobotDART_Magnum_FOUND)\nadd_executable(robot_dart_example_graphics example.cpp)\ntarget_link_libraries(robot_dart_example_graphics\nRobotDART::Simu\nRobotDART::Magnum\n)\nendif()\n
"},{"location":"faq/#where-can-i-find-complete-working-examples-for-either-c-or-python","title":"Where can I find complete working examples for either c++ or python?","text":"

C++ examples

Python examples

"},{"location":"install/","title":"Manual Installation","text":""},{"location":"install/#manual-installation-of-robotdart","title":"Manual Installation of RobotDART","text":"

For the quick installation manual, see the quick installation page.

"},{"location":"install/#dependencies","title":"Dependencies","text":""},{"location":"install/#required","title":"Required","text":""},{"location":"install/#optional","title":"Optional","text":""},{"location":"install/#installation-of-the-dependencies","title":"Installation of the dependencies","text":"

Note: The following instructions are high-level and assume people with some experience in building/installing software.

"},{"location":"install/#installing-system-wide-packages","title":"Installing system-wide packages","text":"

For Ubuntu-based distributions (>=20.04) we should use the following commands:

sudo apt-get update\nsudo apt-get install build-essential cmake pkg-config git libboost-regex-dev libboost-system-dev libboost-test-dev pybind11-dev\nsudo apt-get install libdart-all-dev\n

For OSX with brew:

brew install dartsim\n
"},{"location":"install/#installing-magnum","title":"Installing Magnum","text":"

Magnum depends on Corrade and we are going to use a few plugins and extras from the library. We are also going to use Glfw and Glx for the back-end. Follow the instrutions below:

#installation of Glfw and OpenAL\n# Ubuntu\nsudo apt-get install libglfw3-dev libglfw3 libassimp-dev libopenal-dev libglfw3-dev libsdl2-dev libopenexr-dev libdevil-dev libpng-dev libfaad-dev libfreetype6-dev\n# Mac OSX\nbrew install glfw3 openal-soft assimp\n\n# installation of Corrade\ncd /path/to/tmp/folder\ngit clone https://github.com/mosra/corrade.git\ncd corrade\nmkdir build && cd build\ncmake -DCMAKE_BUILD_TYPE=Release ..\nmake -j\nsudo make install\n\n# installation of Magnum\ncd /path/to/tmp/folder\ngit clone https://github.com/mosra/magnum.git\ncd magnum\nmkdir build && cd build\n# Ubuntu\ncmake -DCMAKE_BUILD_TYPE=Release -DWITH_AUDIO=ON -DWITH_DEBUGTOOLS=ON -DWITH_GL=ON -DWITH_MESHTOOLS=ON -DWITH_PRIMITIVES=ON -DWITH_SCENEGRAPH=ON -DWITH_SHADERS=ON -DWITH_TEXT=ON -DWITH_TEXTURETOOLS=ON -DWITH_TRADE=ON -DWITH_GLFWAPPLICATION=ON -DWITH_WINDOWLESSEGLAPPLICATION=ON -DWITH_OPENGLTESTER=ON -DWITH_ANYAUDIOIMPORTER=ON -DWITH_ANYIMAGECONVERTER=ON -DWITH_ANYIMAGEIMPORTER=ON -DWITH_ANYSCENEIMPORTER=ON -DWITH_MAGNUMFONT=ON -DWITH_OBJIMPORTER=ON -DWITH_TGAIMPORTER=ON -DWITH_WAVAUDIOIMPORTER=ON -DTARGET_EGL=ON .. # this will enable almost all features of Magnum that are not necessarily needed for robot_dart (please refer to the documentation of Magnum for more details on selecting only the ones that you need)\n# Mac OSX\ncmake -DCMAKE_BUILD_TYPE=Release -DWITH_AUDIO=ON -DWITH_DEBUGTOOLS=ON -DWITH_GL=ON -DWITH_MESHTOOLS=ON -DWITH_PRIMITIVES=ON -DWITH_SCENEGRAPH=ON -DWITH_SHADERS=ON -DWITH_TEXT=ON -DWITH_TEXTURETOOLS=ON -DWITH_TRADE=ON -DWITH_GLFWAPPLICATION=ON -DWITH_WINDOWLESSCGLAPPLICATION=ON -DWITH_OPENGLTESTER=ON -DWITH_ANYAUDIOIMPORTER=ON -DWITH_ANYIMAGECONVERTER=ON -DWITH_ANYIMAGEIMPORTER=ON -DWITH_ANYSCENEIMPORTER=ON -DWITH_MAGNUMFONT=ON -DWITH_OBJIMPORTER=ON -DWITH_TGAIMPORTER=ON -DWITH_WAVAUDIOIMPORTER=ON .. # this will enable almost all features of Magnum that are not necessarily needed for robot_dart (please refer to the documentation of Magnum for more details on selecting only the ones that you need)\nmake -j\nsudo make install\n\n# installation of Magnum Plugins\ncd /path/to/tmp/folder\ngit clone https://github.com/mosra/magnum-plugins.git\ncd magnum-plugins\nmkdir build && cd build\ncmake -DCMAKE_BUILD_TYPE=Release -DWITH_ASSIMPIMPORTER=ON -DWITH_DDSIMPORTER=ON -DWITH_JPEGIMPORTER=ON -DWITH_OPENGEXIMPORTER=ON -DWITH_PNGIMPORTER=ON -DWITH_TINYGLTFIMPORTER=ON -DWITH_STBTRUETYPEFONT=ON .. # this will enable quite a few Magnum Plugins that are not necessarily needed for robot_dart (please refer to the documentation of Magnum for more details on selecting only the ones that you need)\nmake -j\nsudo make install\n\n# installation of Magnum DART Integration (DART needs to be installed) and Eigen Integration\ncd /path/to/tmp/folder\ngit clone https://github.com/mosra/magnum-integration.git\ncd magnum-integration\nmkdir build && cd build\ncmake -DCMAKE_BUILD_TYPE=Release -DWITH_DART=ON -DWITH_EIGEN=ON ..\nmake -j\nsudo make install\n
"},{"location":"install/#compilation-and-running-the-examples","title":"Compilation and running the examples","text":"

The compilation of the library is straight-forward:

To build the examples, execute this: ./waf examples

Now you can run the examples. For example, to run the arm example you need to type the following: ./build/arm (or ./build/arm_plain to run it without graphics).

"},{"location":"install/#installing-the-library","title":"Installing the library","text":"

To install the library (assuming that you have already compiled it), you need only to run:

By default the library will be installed in /usr/local/lib (for this maybe sudo ./waf install might be needed) and a static library will be generated. You can change the defaults as follows:

In short, with --prefix you can change the directory where the library will be installed and if --shared is present a shared library will be created instead of a static one.

"},{"location":"install/#compiling-the-python-bindings","title":"Compiling the python bindings","text":"

For the python bindings of robot_dart, we need numpy to be installed, pybind11 and the python bindings of DART (dartpy).

For numpy one can install it with pip or standard packages. dartpy should be installed via the packages above. If not, please see the installation instructions on the main DART website.

Then the compilation of robot_dart is almost identical as before:

To run the python examples (for the python examples you need to have enabled the graphics, that is, install Magnum library), run:

"},{"location":"install/#common-issues-with-python-bindings","title":"Common Issues with Python bindings","text":"

One of the most common issue with the python bindings is the fact that DART bindings might be compiled and installed for python 3 and the robot_dart ones for python 2. To force the usage of python 3 for robot_dart, you use python3 ./waf instead of just ./waf in all the commands above.

"},{"location":"quick_install/","title":"Installation","text":""},{"location":"quick_install/#scripts-for-quick-installation-of-robotdart","title":"Scripts for Quick Installation of RobotDART","text":"

In this page we provide standalone scripts for installing RobotDART for Ubuntu (>=20.04) and OSX. The scripts will install all the required dependencies and RobotDART. Notably, all dependencies that need to be compiled by source and RobotDART will be installed inside the /opt folder. This way, one can be rest assured that their system will be clean.

"},{"location":"quick_install/#ubuntu-2004","title":"Ubuntu >=20.04","text":"

To quickly install RobotDART on Ubuntu >=20.04, we just need to run ./scripts/install_ubuntu.sh from the root of the repo. In more detail:

This will install everything needed! Once the script is successfully executed, one should add the following to their ~/.bashrc or ~/.zshrc file (you may need to swap the python version to yours1):

export PATH=/opt/magnum/bin:$PATH\nexport LD_LIBRARY_PATH=/opt/magnum/lib:/opt/robot_dart/lib:$LD_LIBRARY_PATH\nexport PYTHONPATH=/opt/robot_dart/lib/python3.10/site-packages:$PYTHONPATH\n
"},{"location":"quick_install/#osx","title":"OSX","text":"

Coming soon

  1. You can run python --version to see your version. We only keep the major.minor (ignoring the patch version)\u00a0\u21a9

"},{"location":"robots/","title":"Supported robots","text":""},{"location":"robots/#supported-robots","title":"Supported robots","text":"

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()):

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.

"},{"location":"robots/#talos-pal-robotics","title":"Talos (PAL Robotics)","text":"

Talos is a humanoid robot made by PAL Robotics.

We have two URDF files:

Load Talos

C++
auto robot = std::make_shared<robot_dart::robots::Talos>();\n
Python
robot = rd.Talos()\n

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.

Load Talos Fast

C++
// load talos fast\nauto robot = std::make_shared<robot_dart::robots::TalosFastCollision>();\n
Python
robot = rd.TalosFastCollision()\n

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.

"},{"location":"robots/#panda-franka-emika","title":"Panda (Franka Emika)","text":"

The Franka is a modern manipulator made by Franka Emika Panda. It is commonly found in many robotics labs.

Load Franka

C++
auto robot = std::make_shared<robot_dart::robots::Franka>();\n
Python
robot = rd.Franka()\n
"},{"location":"robots/#lbr-iiwa-kuka","title":"LBR iiwa (KUKA)","text":"

The LBR iiwa is manufactured by KUKA. It is similar to the Panda and is also very common in robotics labs.

Load Iiwa

C++
auto robot = std::make_shared<robot_dart::robots::Iiwa>();\n
Python
robot = rd.Iiwa()\n
"},{"location":"robots/#icub-iit","title":"iCub (IIT)","text":"

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.

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

C++
auto robot = std::make_shared<robot_dart::robots::ICub>();\n// Set actuator types to VELOCITY motors so that they stay in position without any controller\nrobot->set_actuator_types(\"velocity\");\nrobot_dart::RobotDARTSimu simu(0.001);\nsimu.set_collision_detector(\"fcl\");\n
Python
robot = rd.ICub()\n# Set actuator types to VELOCITY motors so that they stay in position without any controller\nrobot.set_actuator_types(\"velocity\")\nsimu = rd.RobotDARTSimu(0.001)\nsimu.set_collision_detector(\"fcl\")\n

Print IMU sensor measurements

C++
std::cout << \"Angular    Position: \" << robot->imu().angular_position_vec().transpose().format(fmt) << std::endl;\nstd::cout << \"Angular    Velocity: \" << robot->imu().angular_velocity().transpose().format(fmt) << std::endl;\nstd::cout << \"Linear Acceleration: \" << robot->imu().linear_acceleration().transpose().format(fmt) << std::endl;\nstd::cout << \"=================================\" << std::endl;\n
Python
print(\"Angular    Position: \",  robot.imu().angular_position_vec().transpose())\nprint(\"Angular    Velocity: \",  robot.imu().angular_velocity().transpose())\nprint(\"Linear Acceleration: \",  robot.imu().linear_acceleration().transpose())\nprint(\"=================================\" )\n

Print Force-Torque sensor measurements

C++
std::cout << \"FT ( force): \" << robot->ft_foot_left().force().transpose().format(fmt) << std::endl;\nstd::cout << \"FT (torque): \" << robot->ft_foot_left().torque().transpose().format(fmt) << std::endl;\nstd::cout << \"=================================\" << std::endl;\n
Python
print(\"FT ( force): \",  robot.ft_foot_left().force().transpose())\nprint(\"FT (torque): \",  robot.ft_foot_left().torque().transpose())\nprint(\"=================================\")\n
"},{"location":"robots/#unitree-a1","title":"Unitree A1","text":"

A1 is a quadruped robot made by the Unitree Robotics.

Load A1

C++
auto robot = std::make_shared<robot_dart::robots::A1>();\n
Python
robot = rd.A1()\n

Print IMU sensor measurements

C++
std::cout << \"Angular    Position: \" << robot->imu().angular_position_vec().transpose().format(fmt) << std::endl;\nstd::cout << \"Angular    Velocity: \" << robot->imu().angular_velocity().transpose().format(fmt) << std::endl;\nstd::cout << \"Linear Acceleration: \" << robot->imu().linear_acceleration().transpose().format(fmt) << std::endl;\nstd::cout << \"=================================\" << std::endl;\n
Python
print( \"Angular    Position: \", robot.imu().angular_position_vec().transpose())\nprint( \"Angular    Velocity: \", robot.imu().angular_velocity().transpose())\nprint( \"Linear Acceleration: \", robot.imu().linear_acceleration().transpose())\nprint( \"=================================\")\n

Add a depth camera on the head

How can I attach a camera to a moving link?

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.

"},{"location":"robots/#dynamixel-based-hexapod-robot-inria-and-others","title":"Dynamixel-based hexapod robot (Inria and others)","text":"

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).

Load Hexapod

C++
auto robot = std::make_shared<robot_dart::robots::Hexapod>();\n
Python
robot = rd.Hexapod()\n

Load Pexod

C++
auto robot = std::make_shared<robot_dart::Robot>(\"pexod.urdf\");\n
Python
robot = rd.Robot(\"pexod.urdf\");\n
"},{"location":"robots/#simple-arm","title":"Simple arm","text":"

Load Simple Arm

C++
auto robot = std::make_shared<robot_dart::robots::Arm>();\n
Python
robot = rd.Arm()\n
"},{"location":"robots/#loading-custom-robots","title":"Loading Custom Robots","text":"

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

C++
    auto your_robot = std::make_shared<robot_dart::Robot>(\"path/to/model.urdf\");\n
Python
    your_robot = robot_dart.Robot(\"path/to/model.urdf\")\n

Load custom Robot with packages (e.g STL, DAE meshes)

C++
    std::vector<std::pair<std::string, std::string>> your_model_packages = ('model', 'path/to/model/dir');\nauto your_robot = std::make_shared<robot_dart::Robot>(\"path/to/model.urdf\", your_model_packages, \"packages\");\n
Python
    your_model_packages = [(\"model\", \"path/to/model/dir\")]\nyour_robot = robot_dart.Robot(\"path/to/model.urdf\", your_model_packages)\n
"},{"location":"api/annotated/","title":"Class List","text":"

Here are the classes, structs, unions and interfaces with brief descriptions:

"},{"location":"api/files/","title":"File List","text":"

Here is a list of all files with brief descriptions:

"},{"location":"api/namespaceMagnum/","title":"Namespace Magnum","text":"

Namespace List > Magnum

"},{"location":"api/namespaceMagnum/#namespaces","title":"Namespaces","text":"Type Name namespace GL namespace Platform namespace SceneGraph namespace Shaders

The documentation for this class was generated from the following file robot_dart/gui/magnum/gs/create_compatibility_shader.hpp

"},{"location":"api/namespaceMagnum_1_1GL/","title":"Namespace Magnum::GL","text":"

Namespace List > Magnum > GL

The documentation for this class was generated from the following file [generated]

"},{"location":"api/namespaceMagnum_1_1Platform/","title":"Namespace Magnum::Platform","text":"

Namespace List > Magnum > Platform

The documentation for this class was generated from the following file [generated]

"},{"location":"api/namespaceMagnum_1_1SceneGraph/","title":"Namespace Magnum::SceneGraph","text":"

Namespace List > Magnum > SceneGraph

The documentation for this class was generated from the following file [generated]

"},{"location":"api/namespaceMagnum_1_1Shaders/","title":"Namespace Magnum::Shaders","text":"

Namespace List > Magnum > Shaders

"},{"location":"api/namespaceMagnum_1_1Shaders/#namespaces","title":"Namespaces","text":"Type Name namespace Implementation

The documentation for this class was generated from the following file robot_dart/gui/magnum/gs/create_compatibility_shader.hpp

"},{"location":"api/namespaceMagnum_1_1Shaders_1_1Implementation/","title":"Namespace Magnum::Shaders::Implementation","text":"

Namespace List > Magnum > Shaders > Implementation

"},{"location":"api/namespaceMagnum_1_1Shaders_1_1Implementation/#public-functions","title":"Public Functions","text":"Type Name GL::Shader createCompatibilityShader (const Utility::Resource & rs, GL::Version version, GL::Shader::Type type)"},{"location":"api/namespaceMagnum_1_1Shaders_1_1Implementation/#public-functions-documentation","title":"Public Functions Documentation","text":""},{"location":"api/namespaceMagnum_1_1Shaders_1_1Implementation/#function-createcompatibilityshader","title":"function createCompatibilityShader","text":"
inline GL::Shader Magnum::Shaders::Implementation::createCompatibilityShader (\nconst Utility::Resource & rs,\nGL::Version version,\nGL::Shader::Type type\n) 

The documentation for this class was generated from the following file robot_dart/gui/magnum/gs/create_compatibility_shader.hpp

"},{"location":"api/namespacedart/","title":"Namespace dart","text":"

Namespace List > dart

"},{"location":"api/namespacedart/#namespaces","title":"Namespaces","text":"Type Name namespace collision namespace dynamics

The documentation for this class was generated from the following file robot_dart/gui/magnum/drawables.hpp

"},{"location":"api/namespacedart_1_1collision/","title":"Namespace dart::collision","text":"

Namespace List > dart > collision

The documentation for this class was generated from the following file [generated]

"},{"location":"api/namespacedart_1_1dynamics/","title":"Namespace dart::dynamics","text":"

Namespace List > dart > dynamics

The documentation for this class was generated from the following file robot_dart/gui/magnum/drawables.hpp

"},{"location":"api/namespacerobot__dart/","title":"Namespace robot_dart","text":"

Namespace List > robot_dart

"},{"location":"api/namespacerobot__dart/#namespaces","title":"Namespaces","text":"Type Name namespace collision_filter namespace control namespace detail namespace gui namespace robots namespace sensor namespace simu"},{"location":"api/namespacerobot__dart/#classes","title":"Classes","text":"Type Name class Assertion class Robot class RobotDARTSimu class RobotPool class Scheduler"},{"location":"api/namespacerobot__dart/#public-attributes","title":"Public Attributes","text":"Type Name auto body_node_get_friction_coeff = = {
    return body-&gt;getFrictionCoeff();\n\n}<br> |\n

| auto | body_node_get_restitution_coeff = = {

    return body-&gt;getRestitutionCoeff();\n\n}<br> |\n

| auto | body_node_set_friction_coeff = = {

    body-&gt;setFrictionCoeff(value);\n\n}<br> |\n

| auto | body_node_set_restitution_coeff = = {

    body-&gt;setRestitutionCoeff(value);\n\n}<br> |\n
"},{"location":"api/namespacerobot__dart/#public-functions","title":"Public Functions","text":"Type Name Eigen::Isometry3d make_tf (const Eigen::Matrix3d & R, const Eigen::Vector3d & t) Eigen::Isometry3d make_tf (const Eigen::Matrix3d & R) Eigen::Isometry3d make_tf (const Eigen::Vector3d & t) Eigen::Isometry3d make_tf (std::initializer_list< double > args) Eigen::VectorXd make_vector (std::initializer_list< double > args)"},{"location":"api/namespacerobot__dart/#public-attributes-documentation","title":"Public Attributes Documentation","text":""},{"location":"api/namespacerobot__dart/#variable-body_node_get_friction_coeff","title":"variable body_node_get_friction_coeff","text":"
auto robot_dart::body_node_get_friction_coeff;\n
"},{"location":"api/namespacerobot__dart/#variable-body_node_get_restitution_coeff","title":"variable body_node_get_restitution_coeff","text":"
auto robot_dart::body_node_get_restitution_coeff;\n
"},{"location":"api/namespacerobot__dart/#variable-body_node_set_friction_coeff","title":"variable body_node_set_friction_coeff","text":"
auto robot_dart::body_node_set_friction_coeff;\n
"},{"location":"api/namespacerobot__dart/#variable-body_node_set_restitution_coeff","title":"variable body_node_set_restitution_coeff","text":"
auto robot_dart::body_node_set_restitution_coeff;\n
"},{"location":"api/namespacerobot__dart/#public-functions-documentation","title":"Public Functions Documentation","text":""},{"location":"api/namespacerobot__dart/#function-make_tf","title":"function make_tf","text":"
inline Eigen::Isometry3d robot_dart::make_tf (\nconst Eigen::Matrix3d & R,\nconst Eigen::Vector3d & t\n) 
"},{"location":"api/namespacerobot__dart/#function-make_tf_1","title":"function make_tf","text":"
inline Eigen::Isometry3d robot_dart::make_tf (\nconst Eigen::Matrix3d & R\n) 
"},{"location":"api/namespacerobot__dart/#function-make_tf_2","title":"function make_tf","text":"
inline Eigen::Isometry3d robot_dart::make_tf (\nconst Eigen::Vector3d & t\n) 
"},{"location":"api/namespacerobot__dart/#function-make_tf_3","title":"function make_tf","text":"
inline Eigen::Isometry3d robot_dart::make_tf (\nstd::initializer_list< double > args\n) 
"},{"location":"api/namespacerobot__dart/#function-make_vector","title":"function make_vector","text":"
inline Eigen::VectorXd robot_dart::make_vector (\nstd::initializer_list< double > args\n) 

The documentation for this class was generated from the following file robot_dart/control/pd_control.cpp

"},{"location":"api/classrobot__dart_1_1Assertion/","title":"Class robot_dart::Assertion","text":"

ClassList > robot_dart > Assertion

Inherits the following classes: std::exception

"},{"location":"api/classrobot__dart_1_1Assertion/#public-functions","title":"Public Functions","text":"Type Name Assertion (const std::string & msg=\"\") const char * what () const"},{"location":"api/classrobot__dart_1_1Assertion/#public-functions-documentation","title":"Public Functions Documentation","text":""},{"location":"api/classrobot__dart_1_1Assertion/#function-assertion","title":"function Assertion","text":"
inline robot_dart::Assertion::Assertion (\nconst std::string & msg=\"\"\n) 
"},{"location":"api/classrobot__dart_1_1Assertion/#function-what","title":"function what","text":"
inline const char * robot_dart::Assertion::what () const\n

The documentation for this class was generated from the following file robot_dart/utils.hpp

"},{"location":"api/classrobot__dart_1_1Robot/","title":"Class robot_dart::Robot","text":"

ClassList > robot_dart > Robot

Inherits the following classes: std::enable_shared_from_this< Robot >

Inherited by the following classes: robot_dart::robots::A1, robot_dart::robots::Arm, robot_dart::robots::Franka, robot_dart::robots::Hexapod, robot_dart::robots::ICub, robot_dart::robots::Iiwa, robot_dart::robots::Pendulum, robot_dart::robots::Talos, robot_dart::robots::Tiago, robot_dart::robots::Ur3e, robot_dart::robots::Vx300

"},{"location":"api/classrobot__dart_1_1Robot/#public-functions","title":"Public Functions","text":"Type Name Robot (const std::string & model_file, const std::vector< std::pair< std::string, std::string > > & packages, const std::string & robot_name=\"robot\", bool is_urdf_string=false, bool cast_shadows=true) Robot (const std::string & model_file, const std::string & robot_name=\"robot\", bool is_urdf_string=false, bool cast_shadows=true) Robot (dart::dynamics::SkeletonPtr skeleton, const std::string & robot_name=\"robot\", bool cast_shadows=true) Eigen::VectorXd acceleration_lower_limits (const std::vector< std::string > & dof_names={}) const Eigen::VectorXd acceleration_upper_limits (const std::vector< std::string > & dof_names={}) const Eigen::VectorXd accelerations (const std::vector< std::string > & dof_names={}) const std::vector< std::shared_ptr< control::RobotControl > > active_controllers () const std::string actuator_type (const std::string & joint_name) const std::vector< std::string > actuator_types (const std::vector< std::string > & joint_names={}) const void add_body_mass (const std::string & body_name, double mass) void add_body_mass (size_t body_index, double mass) void add_controller (const std::shared_ptr< control::RobotControl > & controller, double weight=1.0) void add_external_force (const std::string & body_name, const Eigen::Vector3d & force, const Eigen::Vector3d & offset=Eigen::Vector3d::Zero(), bool force_local=false, bool offset_local=true) void add_external_force (size_t body_index, const Eigen::Vector3d & force, const Eigen::Vector3d & offset=Eigen::Vector3d::Zero(), bool force_local=false, bool offset_local=true) void add_external_torque (const std::string & body_name, const Eigen::Vector3d & torque, bool local=false) void add_external_torque (size_t body_index, const Eigen::Vector3d & torque, bool local=false) bool adjacent_colliding () const Eigen::MatrixXd aug_mass_matrix (const std::vector< std::string > & dof_names={}) const Eigen::Isometry3d base_pose () const Eigen::Vector6d base_pose_vec () const Eigen::Vector6d body_acceleration (const std::string & body_name) const Eigen::Vector6d body_acceleration (size_t body_index) const size_t body_index (const std::string & body_name) const double body_mass (const std::string & body_name) const double body_mass (size_t body_index) const std::string body_name (size_t body_index) const std::vector< std::string > body_names () const dart::dynamics::BodyNode * body_node (const std::string & body_name) dart::dynamics::BodyNode * body_node (size_t body_index) Eigen::Isometry3d body_pose (const std::string & body_name) const Eigen::Isometry3d body_pose (size_t body_index) const Eigen::Vector6d body_pose_vec (const std::string & body_name) const Eigen::Vector6d body_pose_vec (size_t body_index) const Eigen::Vector6d body_velocity (const std::string & body_name) const Eigen::Vector6d body_velocity (size_t body_index) const bool cast_shadows () const void clear_controllers () void clear_external_forces () void clear_internal_forces () std::shared_ptr< Robot > clone () const std::shared_ptr< Robot > clone_ghost (const std::string & ghost_name=\"ghost\", const Eigen::Vector4d & ghost_color={0.3, 0.3, 0.3, 0.7}) const Eigen::Vector3d com () const Eigen::Vector6d com_acceleration () const Eigen::MatrixXd com_jacobian (const std::vector< std::string > & dof_names={}) const Eigen::MatrixXd com_jacobian_deriv (const std::vector< std::string > & dof_names={}) const Eigen::Vector6d com_velocity () const Eigen::VectorXd commands (const std::vector< std::string > & dof_names={}) const Eigen::VectorXd constraint_forces (const std::vector< std::string > & dof_names={}) const std::shared_ptr< control::RobotControl > controller (size_t index) const std::vector< std::shared_ptr< control::RobotControl > > controllers () const Eigen::VectorXd coriolis_forces (const std::vector< std::string > & dof_names={}) const Eigen::VectorXd coriolis_gravity_forces (const std::vector< std::string > & dof_names={}) const std::vector< double > coulomb_coeffs (const std::vector< std::string > & dof_names={}) const std::vector< double > damping_coeffs (const std::vector< std::string > & dof_names={}) const dart::dynamics::DegreeOfFreedom * dof (const std::string & dof_name) dart::dynamics::DegreeOfFreedom * dof (size_t dof_index) size_t dof_index (const std::string & dof_name) const const std::unordered_map< std::string, size_t > & dof_map () const std::string dof_name (size_t dof_index) const std::vector< std::string > dof_names (bool filter_mimics=false, bool filter_locked=false, bool filter_passive=false) const const std::vector< std::pair< dart::dynamics::BodyNode *, double > > & drawing_axes () const Eigen::Vector6d external_forces (const std::string & body_name) const Eigen::Vector6d external_forces (size_t body_index) const void fix_to_world () bool fixed () const Eigen::VectorXd force_lower_limits (const std::vector< std::string > & dof_names={}) const void force_position_bounds () std::pair< Eigen::Vector6d, Eigen::Vector6d > force_torque (size_t joint_index) const Eigen::VectorXd force_upper_limits (const std::vector< std::string > & dof_names={}) const Eigen::VectorXd forces (const std::vector< std::string > & dof_names={}) const bool free () const void free_from_world (const Eigen::Vector6d & pose=Eigen::Vector6d::Zero()) double friction_coeff (const std::string & body_name) double friction_coeff (size_t body_index) Eigen::Vector3d friction_dir (const std::string & body_name) Eigen::Vector3d friction_dir (size_t body_index) bool ghost () const Eigen::VectorXd gravity_forces (const std::vector< std::string > & dof_names={}) const Eigen::MatrixXd inv_aug_mass_matrix (const std::vector< std::string > & dof_names={}) const Eigen::MatrixXd inv_mass_matrix (const std::vector< std::string > & dof_names={}) const Eigen::MatrixXd jacobian (const std::string & body_name, const std::vector< std::string > & dof_names={}) const Eigen::MatrixXd jacobian_deriv (const std::string & body_name, const std::vector< std::string > & dof_names={}) const dart::dynamics::Joint * joint (const std::string & joint_name) dart::dynamics::Joint * joint (size_t joint_index) size_t joint_index (const std::string & joint_name) const const std::unordered_map< std::string, size_t > & joint_map () const std::string joint_name (size_t joint_index) const std::vector< std::string > joint_names () const std::vector< std::string > locked_dof_names () const Eigen::MatrixXd mass_matrix (const std::vector< std::string > & dof_names={}) const std::vector< std::string > mimic_dof_names () const const std::string & model_filename () const const std::vector< std::pair< std::string, std::string > > & model_packages () const const std::string & name () const size_t num_bodies () const size_t num_controllers () const size_t num_dofs () const size_t num_joints () const std::vector< std::string > passive_dof_names () const std::vector< bool > position_enforced (const std::vector< std::string > & dof_names={}) const Eigen::VectorXd position_lower_limits (const std::vector< std::string > & dof_names={}) const Eigen::VectorXd position_upper_limits (const std::vector< std::string > & dof_names={}) const Eigen::VectorXd positions (const std::vector< std::string > & dof_names={}) const void reinit_controllers () void remove_all_drawing_axis () void remove_controller (const std::shared_ptr< control::RobotControl > & controller) void remove_controller (size_t index) virtual void reset () void reset_commands () double restitution_coeff (const std::string & body_name) double restitution_coeff (size_t body_index) double secondary_friction_coeff (const std::string & body_name) double secondary_friction_coeff (size_t body_index) bool self_colliding () const void set_acceleration_lower_limits (const Eigen::VectorXd & accelerations, const std::vector< std::string > & dof_names={}) void set_acceleration_upper_limits (const Eigen::VectorXd & accelerations, const std::vector< std::string > & dof_names={}) void set_accelerations (const Eigen::VectorXd & accelerations, const std::vector< std::string > & dof_names={}) void set_actuator_type (const std::string & type, const std::string & joint_name, bool override_mimic=false, bool override_base=false) void set_actuator_types (const std::string & type, const std::vector< std::string > & joint_names={}, bool override_mimic=false, bool override_base=false) void set_base_pose (const Eigen::Isometry3d & tf) void set_base_pose (const Eigen::Vector6d & pose) set base pose: pose is a 6D vector (first 3D orientation in angle-axis and last 3D translation) void set_body_mass (const std::string & body_name, double mass) void set_body_mass (size_t body_index, double mass) void set_body_name (size_t body_index, const std::string & body_name) void set_cast_shadows (bool cast_shadows=true) void set_color_mode (const std::string & color_mode) void set_color_mode (const std::string & color_mode, const std::string & body_name) void set_commands (const Eigen::VectorXd & commands, const std::vector< std::string > & dof_names={}) void set_coulomb_coeffs (const std::vector< double > & cfrictions, const std::vector< std::string > & dof_names={}) void set_coulomb_coeffs (double cfriction, const std::vector< std::string > & dof_names={}) void set_damping_coeffs (const std::vector< double > & damps, const std::vector< std::string > & dof_names={}) void set_damping_coeffs (double damp, const std::vector< std::string > & dof_names={}) void set_draw_axis (const std::string & body_name, double size=0.25) void set_external_force (const std::string & body_name, const Eigen::Vector3d & force, const Eigen::Vector3d & offset=Eigen::Vector3d::Zero(), bool force_local=false, bool offset_local=true) void set_external_force (size_t body_index, const Eigen::Vector3d & force, const Eigen::Vector3d & offset=Eigen::Vector3d::Zero(), bool force_local=false, bool offset_local=true) void set_external_torque (const std::string & body_name, const Eigen::Vector3d & torque, bool local=false) void set_external_torque (size_t body_index, const Eigen::Vector3d & torque, bool local=false) void set_force_lower_limits (const Eigen::VectorXd & forces, const std::vector< std::string > & dof_names={}) void set_force_upper_limits (const Eigen::VectorXd & forces, const std::vector< std::string > & dof_names={}) void set_forces (const Eigen::VectorXd & forces, const std::vector< std::string > & dof_names={}) void set_friction_coeff (const std::string & body_name, double value) void set_friction_coeff (size_t body_index, double value) void set_friction_coeffs (double value) void set_friction_dir (const std::string & body_name, const Eigen::Vector3d & direction) void set_friction_dir (size_t body_index, const Eigen::Vector3d & direction) void set_ghost (bool ghost=true) void set_joint_name (size_t joint_index, const std::string & joint_name) void set_mimic (const std::string & joint_name, const std::string & mimic_joint_name, double multiplier=1., double offset=0.) void set_position_enforced (const std::vector< bool > & enforced, const std::vector< std::string > & dof_names={}) void set_position_enforced (bool enforced, const std::vector< std::string > & dof_names={}) void set_position_lower_limits (const Eigen::VectorXd & positions, const std::vector< std::string > & dof_names={}) void set_position_upper_limits (const Eigen::VectorXd & positions, const std::vector< std::string > & dof_names={}) void set_positions (const Eigen::VectorXd & positions, const std::vector< std::string > & dof_names={}) void set_restitution_coeff (const std::string & body_name, double value) void set_restitution_coeff (size_t body_index, double value) void set_restitution_coeffs (double value) void set_secondary_friction_coeff (const std::string & body_name, double value) void set_secondary_friction_coeff (size_t body_index, double value) void set_secondary_friction_coeffs (double value) void set_self_collision (bool enable_self_collisions=true, bool enable_adjacent_collisions=false) void set_spring_stiffnesses (const std::vector< double > & stiffnesses, const std::vector< std::string > & dof_names={}) void set_spring_stiffnesses (double stiffness, const std::vector< std::string > & dof_names={}) void set_velocities (const Eigen::VectorXd & velocities, const std::vector< std::string > & dof_names={}) void set_velocity_lower_limits (const Eigen::VectorXd & velocities, const std::vector< std::string > & dof_names={}) void set_velocity_upper_limits (const Eigen::VectorXd & velocities, const std::vector< std::string > & dof_names={}) dart::dynamics::SkeletonPtr skeleton () std::vector< double > spring_stiffnesses (const std::vector< std::string > & dof_names={}) const void update (double t) void update_joint_dof_maps () Eigen::VectorXd vec_dof (const Eigen::VectorXd & vec, const std::vector< std::string > & dof_names) const Eigen::VectorXd velocities (const std::vector< std::string > & dof_names={}) const Eigen::VectorXd velocity_lower_limits (const std::vector< std::string > & dof_names={}) const Eigen::VectorXd velocity_upper_limits (const std::vector< std::string > & dof_names={}) const virtual ~Robot ()"},{"location":"api/classrobot__dart_1_1Robot/#public-static-functions","title":"Public Static Functions","text":"Type Name std::shared_ptr< Robot > create_box (const Eigen::Vector3d & dims, const Eigen::Isometry3d & tf, const std::string & type=\"free\", double mass=1.0, const Eigen::Vector4d & color=dart::Color::Red(1.0), const std::string & box_name=\"box\") std::shared_ptr< Robot > create_box (const Eigen::Vector3d & dims, const Eigen::Vector6d & pose=Eigen::Vector6d::Zero(), const std::string & type=\"free\", double mass=1.0, const Eigen::Vector4d & color=dart::Color::Red(1.0), const std::string & box_name=\"box\") std::shared_ptr< Robot > create_ellipsoid (const Eigen::Vector3d & dims, const Eigen::Isometry3d & tf, const std::string & type=\"free\", double mass=1.0, const Eigen::Vector4d & color=dart::Color::Red(1.0), const std::string & ellipsoid_name=\"ellipsoid\") std::shared_ptr< Robot > create_ellipsoid (const Eigen::Vector3d & dims, const Eigen::Vector6d & pose=Eigen::Vector6d::Zero(), const std::string & type=\"free\", double mass=1.0, const Eigen::Vector4d & color=dart::Color::Red(1.0), const std::string & ellipsoid_name=\"ellipsoid\")"},{"location":"api/classrobot__dart_1_1Robot/#protected-attributes","title":"Protected Attributes","text":"Type Name std::vector< std::pair< dart::dynamics::BodyNode *, double > > _axis_shapes bool _cast_shadows std::vector< std::shared_ptr< control::RobotControl > > _controllers std::unordered_map< std::string, size_t > _dof_map bool _is_ghost std::unordered_map< std::string, size_t > _joint_map std::string _model_filename std::vector< std::pair< std::string, std::string > > _packages std::string _robot_name dart::dynamics::SkeletonPtr _skeleton"},{"location":"api/classrobot__dart_1_1Robot/#protected-functions","title":"Protected Functions","text":"Type Name dart::dynamics::Joint::ActuatorType _actuator_type (size_t joint_index) const std::vector< dart::dynamics::Joint::ActuatorType > _actuator_types () const std::string _get_path (const std::string & filename) const Eigen::MatrixXd _jacobian (const Eigen::MatrixXd & full_jacobian, const std::vector< std::string > & dof_names) const dart::dynamics::SkeletonPtr _load_model (const std::string & filename, const std::vector< std::pair< std::string, std::string > > & packages=std::vector< std::pair< std::string, std::string > >(), bool is_urdf_string=false) Eigen::MatrixXd _mass_matrix (const Eigen::MatrixXd & full_mass_matrix, const std::vector< std::string > & dof_names) const virtual void _post_addition (RobotDARTSimu *) Function called by RobotDARTSimu object when adding the robot to the world. virtual void _post_removal (RobotDARTSimu *) Function called by RobotDARTSimu object when removing the robot to the world. void _set_actuator_type (size_t joint_index, dart::dynamics::Joint::ActuatorType type, bool override_mimic=false, bool override_base=false) void _set_actuator_types (const std::vector< dart::dynamics::Joint::ActuatorType > & types, bool override_mimic=false, bool override_base=false) void _set_actuator_types (dart::dynamics::Joint::ActuatorType type, bool override_mimic=false, bool override_base=false) void _set_color_mode (dart::dynamics::MeshShape::ColorMode color_mode, dart::dynamics::SkeletonPtr skel) void _set_color_mode (dart::dynamics::MeshShape::ColorMode color_mode, dart::dynamics::ShapeNode * sn)"},{"location":"api/classrobot__dart_1_1Robot/#public-functions-documentation","title":"Public Functions Documentation","text":""},{"location":"api/classrobot__dart_1_1Robot/#function-robot-13","title":"function Robot [\u2153]","text":"
robot_dart::Robot::Robot (\nconst std::string & model_file,\nconst std::vector< std::pair< std::string, std::string > > & packages,\nconst std::string & robot_name=\"robot\",\nbool is_urdf_string=false,\nbool cast_shadows=true\n) 
"},{"location":"api/classrobot__dart_1_1Robot/#function-robot-23","title":"function Robot [\u2154]","text":"
robot_dart::Robot::Robot (\nconst std::string & model_file,\nconst std::string & robot_name=\"robot\",\nbool is_urdf_string=false,\nbool cast_shadows=true\n) 
"},{"location":"api/classrobot__dart_1_1Robot/#function-robot-33","title":"function Robot [3/3]","text":"
robot_dart::Robot::Robot (\ndart::dynamics::SkeletonPtr skeleton,\nconst std::string & robot_name=\"robot\",\nbool cast_shadows=true\n) 
"},{"location":"api/classrobot__dart_1_1Robot/#function-acceleration_lower_limits","title":"function acceleration_lower_limits","text":"
Eigen::VectorXd robot_dart::Robot::acceleration_lower_limits (\nconst std::vector< std::string > & dof_names={}\n) const\n
"},{"location":"api/classrobot__dart_1_1Robot/#function-acceleration_upper_limits","title":"function acceleration_upper_limits","text":"
Eigen::VectorXd robot_dart::Robot::acceleration_upper_limits (\nconst std::vector< std::string > & dof_names={}\n) const\n
"},{"location":"api/classrobot__dart_1_1Robot/#function-accelerations","title":"function accelerations","text":"
Eigen::VectorXd robot_dart::Robot::accelerations (\nconst std::vector< std::string > & dof_names={}\n) const\n
"},{"location":"api/classrobot__dart_1_1Robot/#function-active_controllers","title":"function active_controllers","text":"
std::vector< std::shared_ptr< control::RobotControl > > robot_dart::Robot::active_controllers () const\n
"},{"location":"api/classrobot__dart_1_1Robot/#function-actuator_type","title":"function actuator_type","text":"
std::string robot_dart::Robot::actuator_type (\nconst std::string & joint_name\n) const\n
"},{"location":"api/classrobot__dart_1_1Robot/#function-actuator_types","title":"function actuator_types","text":"
std::vector< std::string > robot_dart::Robot::actuator_types (\nconst std::vector< std::string > & joint_names={}\n) const\n
"},{"location":"api/classrobot__dart_1_1Robot/#function-add_body_mass-12","title":"function add_body_mass [\u00bd]","text":"
void robot_dart::Robot::add_body_mass (\nconst std::string & body_name,\ndouble mass\n) 
"},{"location":"api/classrobot__dart_1_1Robot/#function-add_body_mass-22","title":"function add_body_mass [2/2]","text":"
void robot_dart::Robot::add_body_mass (\nsize_t body_index,\ndouble mass\n) 
"},{"location":"api/classrobot__dart_1_1Robot/#function-add_controller","title":"function add_controller","text":"
void robot_dart::Robot::add_controller (\nconst std::shared_ptr< control::RobotControl > & controller,\ndouble weight=1.0\n) 
"},{"location":"api/classrobot__dart_1_1Robot/#function-add_external_force-12","title":"function add_external_force [\u00bd]","text":"
void robot_dart::Robot::add_external_force (\nconst std::string & body_name,\nconst Eigen::Vector3d & force,\nconst Eigen::Vector3d & offset=Eigen::Vector3d::Zero(),\nbool force_local=false,\nbool offset_local=true\n) 
"},{"location":"api/classrobot__dart_1_1Robot/#function-add_external_force-22","title":"function add_external_force [2/2]","text":"
void robot_dart::Robot::add_external_force (\nsize_t body_index,\nconst Eigen::Vector3d & force,\nconst Eigen::Vector3d & offset=Eigen::Vector3d::Zero(),\nbool force_local=false,\nbool offset_local=true\n) 
"},{"location":"api/classrobot__dart_1_1Robot/#function-add_external_torque-12","title":"function add_external_torque [\u00bd]","text":"
void robot_dart::Robot::add_external_torque (\nconst std::string & body_name,\nconst Eigen::Vector3d & torque,\nbool local=false\n) 
"},{"location":"api/classrobot__dart_1_1Robot/#function-add_external_torque-22","title":"function add_external_torque [2/2]","text":"
void robot_dart::Robot::add_external_torque (\nsize_t body_index,\nconst Eigen::Vector3d & torque,\nbool local=false\n) 
"},{"location":"api/classrobot__dart_1_1Robot/#function-adjacent_colliding","title":"function adjacent_colliding","text":"
bool robot_dart::Robot::adjacent_colliding () const\n
"},{"location":"api/classrobot__dart_1_1Robot/#function-aug_mass_matrix","title":"function aug_mass_matrix","text":"
Eigen::MatrixXd robot_dart::Robot::aug_mass_matrix (\nconst std::vector< std::string > & dof_names={}\n) const\n
"},{"location":"api/classrobot__dart_1_1Robot/#function-base_pose","title":"function base_pose","text":"
Eigen::Isometry3d robot_dart::Robot::base_pose () const\n
"},{"location":"api/classrobot__dart_1_1Robot/#function-base_pose_vec","title":"function base_pose_vec","text":"
Eigen::Vector6d robot_dart::Robot::base_pose_vec () const\n
"},{"location":"api/classrobot__dart_1_1Robot/#function-body_acceleration-12","title":"function body_acceleration [\u00bd]","text":"
Eigen::Vector6d robot_dart::Robot::body_acceleration (\nconst std::string & body_name\n) const\n
"},{"location":"api/classrobot__dart_1_1Robot/#function-body_acceleration-22","title":"function body_acceleration [2/2]","text":"
Eigen::Vector6d robot_dart::Robot::body_acceleration (\nsize_t body_index\n) const\n
"},{"location":"api/classrobot__dart_1_1Robot/#function-body_index","title":"function body_index","text":"
size_t robot_dart::Robot::body_index (\nconst std::string & body_name\n) const\n
"},{"location":"api/classrobot__dart_1_1Robot/#function-body_mass-12","title":"function body_mass [\u00bd]","text":"
double robot_dart::Robot::body_mass (\nconst std::string & body_name\n) const\n
"},{"location":"api/classrobot__dart_1_1Robot/#function-body_mass-22","title":"function body_mass [2/2]","text":"
double robot_dart::Robot::body_mass (\nsize_t body_index\n) const\n
"},{"location":"api/classrobot__dart_1_1Robot/#function-body_name","title":"function body_name","text":"
std::string robot_dart::Robot::body_name (\nsize_t body_index\n) const\n
"},{"location":"api/classrobot__dart_1_1Robot/#function-body_names","title":"function body_names","text":"
std::vector< std::string > robot_dart::Robot::body_names () const\n
"},{"location":"api/classrobot__dart_1_1Robot/#function-body_node-12","title":"function body_node [\u00bd]","text":"
dart::dynamics::BodyNode * robot_dart::Robot::body_node (\nconst std::string & body_name\n) 
"},{"location":"api/classrobot__dart_1_1Robot/#function-body_node-22","title":"function body_node [2/2]","text":"
dart::dynamics::BodyNode * robot_dart::Robot::body_node (\nsize_t body_index\n) 
"},{"location":"api/classrobot__dart_1_1Robot/#function-body_pose-12","title":"function body_pose [\u00bd]","text":"
Eigen::Isometry3d robot_dart::Robot::body_pose (\nconst std::string & body_name\n) const\n
"},{"location":"api/classrobot__dart_1_1Robot/#function-body_pose-22","title":"function body_pose [2/2]","text":"
Eigen::Isometry3d robot_dart::Robot::body_pose (\nsize_t body_index\n) const\n
"},{"location":"api/classrobot__dart_1_1Robot/#function-body_pose_vec-12","title":"function body_pose_vec [\u00bd]","text":"
Eigen::Vector6d robot_dart::Robot::body_pose_vec (\nconst std::string & body_name\n) const\n
"},{"location":"api/classrobot__dart_1_1Robot/#function-body_pose_vec-22","title":"function body_pose_vec [2/2]","text":"
Eigen::Vector6d robot_dart::Robot::body_pose_vec (\nsize_t body_index\n) const\n
"},{"location":"api/classrobot__dart_1_1Robot/#function-body_velocity-12","title":"function body_velocity [\u00bd]","text":"
Eigen::Vector6d robot_dart::Robot::body_velocity (\nconst std::string & body_name\n) const\n
"},{"location":"api/classrobot__dart_1_1Robot/#function-body_velocity-22","title":"function body_velocity [2/2]","text":"
Eigen::Vector6d robot_dart::Robot::body_velocity (\nsize_t body_index\n) const\n
"},{"location":"api/classrobot__dart_1_1Robot/#function-cast_shadows","title":"function cast_shadows","text":"
bool robot_dart::Robot::cast_shadows () const\n
"},{"location":"api/classrobot__dart_1_1Robot/#function-clear_controllers","title":"function clear_controllers","text":"
void robot_dart::Robot::clear_controllers () 
"},{"location":"api/classrobot__dart_1_1Robot/#function-clear_external_forces","title":"function clear_external_forces","text":"
void robot_dart::Robot::clear_external_forces () 
"},{"location":"api/classrobot__dart_1_1Robot/#function-clear_internal_forces","title":"function clear_internal_forces","text":"
void robot_dart::Robot::clear_internal_forces () 
"},{"location":"api/classrobot__dart_1_1Robot/#function-clone","title":"function clone","text":"
std::shared_ptr< Robot > robot_dart::Robot::clone () const\n
"},{"location":"api/classrobot__dart_1_1Robot/#function-clone_ghost","title":"function clone_ghost","text":"
std::shared_ptr< Robot > robot_dart::Robot::clone_ghost (\nconst std::string & ghost_name=\"ghost\",\nconst Eigen::Vector4d & ghost_color={0.3, 0.3, 0.3, 0.7}\n) const\n
"},{"location":"api/classrobot__dart_1_1Robot/#function-com","title":"function com","text":"
Eigen::Vector3d robot_dart::Robot::com () const\n
"},{"location":"api/classrobot__dart_1_1Robot/#function-com_acceleration","title":"function com_acceleration","text":"
Eigen::Vector6d robot_dart::Robot::com_acceleration () const\n
"},{"location":"api/classrobot__dart_1_1Robot/#function-com_jacobian","title":"function com_jacobian","text":"
Eigen::MatrixXd robot_dart::Robot::com_jacobian (\nconst std::vector< std::string > & dof_names={}\n) const\n
"},{"location":"api/classrobot__dart_1_1Robot/#function-com_jacobian_deriv","title":"function com_jacobian_deriv","text":"
Eigen::MatrixXd robot_dart::Robot::com_jacobian_deriv (\nconst std::vector< std::string > & dof_names={}\n) const\n
"},{"location":"api/classrobot__dart_1_1Robot/#function-com_velocity","title":"function com_velocity","text":"
Eigen::Vector6d robot_dart::Robot::com_velocity () const\n
"},{"location":"api/classrobot__dart_1_1Robot/#function-commands","title":"function commands","text":"
Eigen::VectorXd robot_dart::Robot::commands (\nconst std::vector< std::string > & dof_names={}\n) const\n
"},{"location":"api/classrobot__dart_1_1Robot/#function-constraint_forces","title":"function constraint_forces","text":"
Eigen::VectorXd robot_dart::Robot::constraint_forces (\nconst std::vector< std::string > & dof_names={}\n) const\n
"},{"location":"api/classrobot__dart_1_1Robot/#function-controller","title":"function controller","text":"
std::shared_ptr< control::RobotControl > robot_dart::Robot::controller (\nsize_t index\n) const\n
"},{"location":"api/classrobot__dart_1_1Robot/#function-controllers","title":"function controllers","text":"
std::vector< std::shared_ptr< control::RobotControl > > robot_dart::Robot::controllers () const\n
"},{"location":"api/classrobot__dart_1_1Robot/#function-coriolis_forces","title":"function coriolis_forces","text":"
Eigen::VectorXd robot_dart::Robot::coriolis_forces (\nconst std::vector< std::string > & dof_names={}\n) const\n
"},{"location":"api/classrobot__dart_1_1Robot/#function-coriolis_gravity_forces","title":"function coriolis_gravity_forces","text":"
Eigen::VectorXd robot_dart::Robot::coriolis_gravity_forces (\nconst std::vector< std::string > & dof_names={}\n) const\n
"},{"location":"api/classrobot__dart_1_1Robot/#function-coulomb_coeffs","title":"function coulomb_coeffs","text":"
std::vector< double > robot_dart::Robot::coulomb_coeffs (\nconst std::vector< std::string > & dof_names={}\n) const\n
"},{"location":"api/classrobot__dart_1_1Robot/#function-damping_coeffs","title":"function damping_coeffs","text":"
std::vector< double > robot_dart::Robot::damping_coeffs (\nconst std::vector< std::string > & dof_names={}\n) const\n
"},{"location":"api/classrobot__dart_1_1Robot/#function-dof-12","title":"function dof [\u00bd]","text":"
dart::dynamics::DegreeOfFreedom * robot_dart::Robot::dof (\nconst std::string & dof_name\n) 
"},{"location":"api/classrobot__dart_1_1Robot/#function-dof-22","title":"function dof [2/2]","text":"
dart::dynamics::DegreeOfFreedom * robot_dart::Robot::dof (\nsize_t dof_index\n) 
"},{"location":"api/classrobot__dart_1_1Robot/#function-dof_index","title":"function dof_index","text":"
size_t robot_dart::Robot::dof_index (\nconst std::string & dof_name\n) const\n
"},{"location":"api/classrobot__dart_1_1Robot/#function-dof_map","title":"function dof_map","text":"
const std::unordered_map< std::string, size_t > & robot_dart::Robot::dof_map () const\n
"},{"location":"api/classrobot__dart_1_1Robot/#function-dof_name","title":"function dof_name","text":"
std::string robot_dart::Robot::dof_name (\nsize_t dof_index\n) const\n
"},{"location":"api/classrobot__dart_1_1Robot/#function-dof_names","title":"function dof_names","text":"
std::vector< std::string > robot_dart::Robot::dof_names (\nbool filter_mimics=false,\nbool filter_locked=false,\nbool filter_passive=false\n) const\n
"},{"location":"api/classrobot__dart_1_1Robot/#function-drawing_axes","title":"function drawing_axes","text":"
const std::vector< std::pair< dart::dynamics::BodyNode *, double > > & robot_dart::Robot::drawing_axes () const\n
"},{"location":"api/classrobot__dart_1_1Robot/#function-external_forces-12","title":"function external_forces [\u00bd]","text":"
Eigen::Vector6d robot_dart::Robot::external_forces (\nconst std::string & body_name\n) const\n
"},{"location":"api/classrobot__dart_1_1Robot/#function-external_forces-22","title":"function external_forces [2/2]","text":"
Eigen::Vector6d robot_dart::Robot::external_forces (\nsize_t body_index\n) const\n
"},{"location":"api/classrobot__dart_1_1Robot/#function-fix_to_world","title":"function fix_to_world","text":"
void robot_dart::Robot::fix_to_world () 
"},{"location":"api/classrobot__dart_1_1Robot/#function-fixed","title":"function fixed","text":"
bool robot_dart::Robot::fixed () const\n
"},{"location":"api/classrobot__dart_1_1Robot/#function-force_lower_limits","title":"function force_lower_limits","text":"
Eigen::VectorXd robot_dart::Robot::force_lower_limits (\nconst std::vector< std::string > & dof_names={}\n) const\n
"},{"location":"api/classrobot__dart_1_1Robot/#function-force_position_bounds","title":"function force_position_bounds","text":"
void robot_dart::Robot::force_position_bounds () 
"},{"location":"api/classrobot__dart_1_1Robot/#function-force_torque","title":"function force_torque","text":"
std::pair< Eigen::Vector6d, Eigen::Vector6d > robot_dart::Robot::force_torque (\nsize_t joint_index\n) const\n
"},{"location":"api/classrobot__dart_1_1Robot/#function-force_upper_limits","title":"function force_upper_limits","text":"
Eigen::VectorXd robot_dart::Robot::force_upper_limits (\nconst std::vector< std::string > & dof_names={}\n) const\n
"},{"location":"api/classrobot__dart_1_1Robot/#function-forces","title":"function forces","text":"
Eigen::VectorXd robot_dart::Robot::forces (\nconst std::vector< std::string > & dof_names={}\n) const\n
"},{"location":"api/classrobot__dart_1_1Robot/#function-free","title":"function free","text":"
bool robot_dart::Robot::free () const\n
"},{"location":"api/classrobot__dart_1_1Robot/#function-free_from_world","title":"function free_from_world","text":"
void robot_dart::Robot::free_from_world (\nconst Eigen::Vector6d & pose=Eigen::Vector6d::Zero()\n) 
"},{"location":"api/classrobot__dart_1_1Robot/#function-friction_coeff-12","title":"function friction_coeff [\u00bd]","text":"
double robot_dart::Robot::friction_coeff (\nconst std::string & body_name\n) 
"},{"location":"api/classrobot__dart_1_1Robot/#function-friction_coeff-22","title":"function friction_coeff [2/2]","text":"
double robot_dart::Robot::friction_coeff (\nsize_t body_index\n) 
"},{"location":"api/classrobot__dart_1_1Robot/#function-friction_dir-12","title":"function friction_dir [\u00bd]","text":"
Eigen::Vector3d robot_dart::Robot::friction_dir (\nconst std::string & body_name\n) 
"},{"location":"api/classrobot__dart_1_1Robot/#function-friction_dir-22","title":"function friction_dir [2/2]","text":"
Eigen::Vector3d robot_dart::Robot::friction_dir (\nsize_t body_index\n) 
"},{"location":"api/classrobot__dart_1_1Robot/#function-ghost","title":"function ghost","text":"
bool robot_dart::Robot::ghost () const\n
"},{"location":"api/classrobot__dart_1_1Robot/#function-gravity_forces","title":"function gravity_forces","text":"
Eigen::VectorXd robot_dart::Robot::gravity_forces (\nconst std::vector< std::string > & dof_names={}\n) const\n
"},{"location":"api/classrobot__dart_1_1Robot/#function-inv_aug_mass_matrix","title":"function inv_aug_mass_matrix","text":"
Eigen::MatrixXd robot_dart::Robot::inv_aug_mass_matrix (\nconst std::vector< std::string > & dof_names={}\n) const\n
"},{"location":"api/classrobot__dart_1_1Robot/#function-inv_mass_matrix","title":"function inv_mass_matrix","text":"
Eigen::MatrixXd robot_dart::Robot::inv_mass_matrix (\nconst std::vector< std::string > & dof_names={}\n) const\n
"},{"location":"api/classrobot__dart_1_1Robot/#function-jacobian","title":"function jacobian","text":"
Eigen::MatrixXd robot_dart::Robot::jacobian (\nconst std::string & body_name,\nconst std::vector< std::string > & dof_names={}\n) const\n
"},{"location":"api/classrobot__dart_1_1Robot/#function-jacobian_deriv","title":"function jacobian_deriv","text":"
Eigen::MatrixXd robot_dart::Robot::jacobian_deriv (\nconst std::string & body_name,\nconst std::vector< std::string > & dof_names={}\n) const\n
"},{"location":"api/classrobot__dart_1_1Robot/#function-joint-12","title":"function joint [\u00bd]","text":"
dart::dynamics::Joint * robot_dart::Robot::joint (\nconst std::string & joint_name\n) 
"},{"location":"api/classrobot__dart_1_1Robot/#function-joint-22","title":"function joint [2/2]","text":"
dart::dynamics::Joint * robot_dart::Robot::joint (\nsize_t joint_index\n) 
"},{"location":"api/classrobot__dart_1_1Robot/#function-joint_index","title":"function joint_index","text":"
size_t robot_dart::Robot::joint_index (\nconst std::string & joint_name\n) const\n
"},{"location":"api/classrobot__dart_1_1Robot/#function-joint_map","title":"function joint_map","text":"
const std::unordered_map< std::string, size_t > & robot_dart::Robot::joint_map () const\n
"},{"location":"api/classrobot__dart_1_1Robot/#function-joint_name","title":"function joint_name","text":"
std::string robot_dart::Robot::joint_name (\nsize_t joint_index\n) const\n
"},{"location":"api/classrobot__dart_1_1Robot/#function-joint_names","title":"function joint_names","text":"
std::vector< std::string > robot_dart::Robot::joint_names () const\n
"},{"location":"api/classrobot__dart_1_1Robot/#function-locked_dof_names","title":"function locked_dof_names","text":"
std::vector< std::string > robot_dart::Robot::locked_dof_names () const\n
"},{"location":"api/classrobot__dart_1_1Robot/#function-mass_matrix","title":"function mass_matrix","text":"
Eigen::MatrixXd robot_dart::Robot::mass_matrix (\nconst std::vector< std::string > & dof_names={}\n) const\n
"},{"location":"api/classrobot__dart_1_1Robot/#function-mimic_dof_names","title":"function mimic_dof_names","text":"
std::vector< std::string > robot_dart::Robot::mimic_dof_names () const\n
"},{"location":"api/classrobot__dart_1_1Robot/#function-model_filename","title":"function model_filename","text":"
inline const std::string & robot_dart::Robot::model_filename () const\n
"},{"location":"api/classrobot__dart_1_1Robot/#function-model_packages","title":"function model_packages","text":"
inline const std::vector< std::pair< std::string, std::string > > & robot_dart::Robot::model_packages () const\n
"},{"location":"api/classrobot__dart_1_1Robot/#function-name","title":"function name","text":"
const std::string & robot_dart::Robot::name () const\n
"},{"location":"api/classrobot__dart_1_1Robot/#function-num_bodies","title":"function num_bodies","text":"
size_t robot_dart::Robot::num_bodies () const\n
"},{"location":"api/classrobot__dart_1_1Robot/#function-num_controllers","title":"function num_controllers","text":"
size_t robot_dart::Robot::num_controllers () const\n
"},{"location":"api/classrobot__dart_1_1Robot/#function-num_dofs","title":"function num_dofs","text":"
size_t robot_dart::Robot::num_dofs () const\n
"},{"location":"api/classrobot__dart_1_1Robot/#function-num_joints","title":"function num_joints","text":"
size_t robot_dart::Robot::num_joints () const\n
"},{"location":"api/classrobot__dart_1_1Robot/#function-passive_dof_names","title":"function passive_dof_names","text":"
std::vector< std::string > robot_dart::Robot::passive_dof_names () const\n
"},{"location":"api/classrobot__dart_1_1Robot/#function-position_enforced","title":"function position_enforced","text":"
std::vector< bool > robot_dart::Robot::position_enforced (\nconst std::vector< std::string > & dof_names={}\n) const\n
"},{"location":"api/classrobot__dart_1_1Robot/#function-position_lower_limits","title":"function position_lower_limits","text":"
Eigen::VectorXd robot_dart::Robot::position_lower_limits (\nconst std::vector< std::string > & dof_names={}\n) const\n
"},{"location":"api/classrobot__dart_1_1Robot/#function-position_upper_limits","title":"function position_upper_limits","text":"
Eigen::VectorXd robot_dart::Robot::position_upper_limits (\nconst std::vector< std::string > & dof_names={}\n) const\n
"},{"location":"api/classrobot__dart_1_1Robot/#function-positions","title":"function positions","text":"
Eigen::VectorXd robot_dart::Robot::positions (\nconst std::vector< std::string > & dof_names={}\n) const\n
"},{"location":"api/classrobot__dart_1_1Robot/#function-reinit_controllers","title":"function reinit_controllers","text":"
void robot_dart::Robot::reinit_controllers () 
"},{"location":"api/classrobot__dart_1_1Robot/#function-remove_all_drawing_axis","title":"function remove_all_drawing_axis","text":"
void robot_dart::Robot::remove_all_drawing_axis () 
"},{"location":"api/classrobot__dart_1_1Robot/#function-remove_controller-12","title":"function remove_controller [\u00bd]","text":"
void robot_dart::Robot::remove_controller (\nconst std::shared_ptr< control::RobotControl > & controller\n) 
"},{"location":"api/classrobot__dart_1_1Robot/#function-remove_controller-22","title":"function remove_controller [2/2]","text":"
void robot_dart::Robot::remove_controller (\nsize_t index\n) 
"},{"location":"api/classrobot__dart_1_1Robot/#function-reset","title":"function reset","text":"
virtual void robot_dart::Robot::reset () 
"},{"location":"api/classrobot__dart_1_1Robot/#function-reset_commands","title":"function reset_commands","text":"
void robot_dart::Robot::reset_commands () 
"},{"location":"api/classrobot__dart_1_1Robot/#function-restitution_coeff-12","title":"function restitution_coeff [\u00bd]","text":"
double robot_dart::Robot::restitution_coeff (\nconst std::string & body_name\n) 
"},{"location":"api/classrobot__dart_1_1Robot/#function-restitution_coeff-22","title":"function restitution_coeff [2/2]","text":"
double robot_dart::Robot::restitution_coeff (\nsize_t body_index\n) 
"},{"location":"api/classrobot__dart_1_1Robot/#function-secondary_friction_coeff-12","title":"function secondary_friction_coeff [\u00bd]","text":"
double robot_dart::Robot::secondary_friction_coeff (\nconst std::string & body_name\n) 
"},{"location":"api/classrobot__dart_1_1Robot/#function-secondary_friction_coeff-22","title":"function secondary_friction_coeff [2/2]","text":"
double robot_dart::Robot::secondary_friction_coeff (\nsize_t body_index\n) 
"},{"location":"api/classrobot__dart_1_1Robot/#function-self_colliding","title":"function self_colliding","text":"
bool robot_dart::Robot::self_colliding () const\n
"},{"location":"api/classrobot__dart_1_1Robot/#function-set_acceleration_lower_limits","title":"function set_acceleration_lower_limits","text":"
void robot_dart::Robot::set_acceleration_lower_limits (\nconst Eigen::VectorXd & accelerations,\nconst std::vector< std::string > & dof_names={}\n) 
"},{"location":"api/classrobot__dart_1_1Robot/#function-set_acceleration_upper_limits","title":"function set_acceleration_upper_limits","text":"
void robot_dart::Robot::set_acceleration_upper_limits (\nconst Eigen::VectorXd & accelerations,\nconst std::vector< std::string > & dof_names={}\n) 
"},{"location":"api/classrobot__dart_1_1Robot/#function-set_accelerations","title":"function set_accelerations","text":"
void robot_dart::Robot::set_accelerations (\nconst Eigen::VectorXd & accelerations,\nconst std::vector< std::string > & dof_names={}\n) 
"},{"location":"api/classrobot__dart_1_1Robot/#function-set_actuator_type","title":"function set_actuator_type","text":"
void robot_dart::Robot::set_actuator_type (\nconst std::string & type,\nconst std::string & joint_name,\nbool override_mimic=false,\nbool override_base=false\n) 
"},{"location":"api/classrobot__dart_1_1Robot/#function-set_actuator_types","title":"function set_actuator_types","text":"
void robot_dart::Robot::set_actuator_types (\nconst std::string & type,\nconst std::vector< std::string > & joint_names={},\nbool override_mimic=false,\nbool override_base=false\n) 
"},{"location":"api/classrobot__dart_1_1Robot/#function-set_base_pose-12","title":"function set_base_pose [\u00bd]","text":"
void robot_dart::Robot::set_base_pose (\nconst Eigen::Isometry3d & tf\n) 
"},{"location":"api/classrobot__dart_1_1Robot/#function-set_base_pose-22","title":"function set_base_pose [2/2]","text":"
void robot_dart::Robot::set_base_pose (\nconst Eigen::Vector6d & pose\n) 
"},{"location":"api/classrobot__dart_1_1Robot/#function-set_body_mass-12","title":"function set_body_mass [\u00bd]","text":"
void robot_dart::Robot::set_body_mass (\nconst std::string & body_name,\ndouble mass\n) 
"},{"location":"api/classrobot__dart_1_1Robot/#function-set_body_mass-22","title":"function set_body_mass [2/2]","text":"
void robot_dart::Robot::set_body_mass (\nsize_t body_index,\ndouble mass\n) 
"},{"location":"api/classrobot__dart_1_1Robot/#function-set_body_name","title":"function set_body_name","text":"
void robot_dart::Robot::set_body_name (\nsize_t body_index,\nconst std::string & body_name\n) 
"},{"location":"api/classrobot__dart_1_1Robot/#function-set_cast_shadows","title":"function set_cast_shadows","text":"
void robot_dart::Robot::set_cast_shadows (\nbool cast_shadows=true\n) 
"},{"location":"api/classrobot__dart_1_1Robot/#function-set_color_mode-12","title":"function set_color_mode [\u00bd]","text":"
void robot_dart::Robot::set_color_mode (\nconst std::string & color_mode\n) 
"},{"location":"api/classrobot__dart_1_1Robot/#function-set_color_mode-22","title":"function set_color_mode [2/2]","text":"
void robot_dart::Robot::set_color_mode (\nconst std::string & color_mode,\nconst std::string & body_name\n) 
"},{"location":"api/classrobot__dart_1_1Robot/#function-set_commands","title":"function set_commands","text":"
void robot_dart::Robot::set_commands (\nconst Eigen::VectorXd & commands,\nconst std::vector< std::string > & dof_names={}\n) 
"},{"location":"api/classrobot__dart_1_1Robot/#function-set_coulomb_coeffs-12","title":"function set_coulomb_coeffs [\u00bd]","text":"
void robot_dart::Robot::set_coulomb_coeffs (\nconst std::vector< double > & cfrictions,\nconst std::vector< std::string > & dof_names={}\n) 
"},{"location":"api/classrobot__dart_1_1Robot/#function-set_coulomb_coeffs-22","title":"function set_coulomb_coeffs [2/2]","text":"
void robot_dart::Robot::set_coulomb_coeffs (\ndouble cfriction,\nconst std::vector< std::string > & dof_names={}\n) 
"},{"location":"api/classrobot__dart_1_1Robot/#function-set_damping_coeffs-12","title":"function set_damping_coeffs [\u00bd]","text":"
void robot_dart::Robot::set_damping_coeffs (\nconst std::vector< double > & damps,\nconst std::vector< std::string > & dof_names={}\n) 
"},{"location":"api/classrobot__dart_1_1Robot/#function-set_damping_coeffs-22","title":"function set_damping_coeffs [2/2]","text":"
void robot_dart::Robot::set_damping_coeffs (\ndouble damp,\nconst std::vector< std::string > & dof_names={}\n) 
"},{"location":"api/classrobot__dart_1_1Robot/#function-set_draw_axis","title":"function set_draw_axis","text":"
void robot_dart::Robot::set_draw_axis (\nconst std::string & body_name,\ndouble size=0.25\n) 
"},{"location":"api/classrobot__dart_1_1Robot/#function-set_external_force-12","title":"function set_external_force [\u00bd]","text":"
void robot_dart::Robot::set_external_force (\nconst std::string & body_name,\nconst Eigen::Vector3d & force,\nconst Eigen::Vector3d & offset=Eigen::Vector3d::Zero(),\nbool force_local=false,\nbool offset_local=true\n) 
"},{"location":"api/classrobot__dart_1_1Robot/#function-set_external_force-22","title":"function set_external_force [2/2]","text":"
void robot_dart::Robot::set_external_force (\nsize_t body_index,\nconst Eigen::Vector3d & force,\nconst Eigen::Vector3d & offset=Eigen::Vector3d::Zero(),\nbool force_local=false,\nbool offset_local=true\n) 
"},{"location":"api/classrobot__dart_1_1Robot/#function-set_external_torque-12","title":"function set_external_torque [\u00bd]","text":"
void robot_dart::Robot::set_external_torque (\nconst std::string & body_name,\nconst Eigen::Vector3d & torque,\nbool local=false\n) 
"},{"location":"api/classrobot__dart_1_1Robot/#function-set_external_torque-22","title":"function set_external_torque [2/2]","text":"
void robot_dart::Robot::set_external_torque (\nsize_t body_index,\nconst Eigen::Vector3d & torque,\nbool local=false\n) 
"},{"location":"api/classrobot__dart_1_1Robot/#function-set_force_lower_limits","title":"function set_force_lower_limits","text":"
void robot_dart::Robot::set_force_lower_limits (\nconst Eigen::VectorXd & forces,\nconst std::vector< std::string > & dof_names={}\n) 
"},{"location":"api/classrobot__dart_1_1Robot/#function-set_force_upper_limits","title":"function set_force_upper_limits","text":"
void robot_dart::Robot::set_force_upper_limits (\nconst Eigen::VectorXd & forces,\nconst std::vector< std::string > & dof_names={}\n) 
"},{"location":"api/classrobot__dart_1_1Robot/#function-set_forces","title":"function set_forces","text":"
void robot_dart::Robot::set_forces (\nconst Eigen::VectorXd & forces,\nconst std::vector< std::string > & dof_names={}\n) 
"},{"location":"api/classrobot__dart_1_1Robot/#function-set_friction_coeff-12","title":"function set_friction_coeff [\u00bd]","text":"
void robot_dart::Robot::set_friction_coeff (\nconst std::string & body_name,\ndouble value\n) 
"},{"location":"api/classrobot__dart_1_1Robot/#function-set_friction_coeff-22","title":"function set_friction_coeff [2/2]","text":"
void robot_dart::Robot::set_friction_coeff (\nsize_t body_index,\ndouble value\n) 
"},{"location":"api/classrobot__dart_1_1Robot/#function-set_friction_coeffs","title":"function set_friction_coeffs","text":"
void robot_dart::Robot::set_friction_coeffs (\ndouble value\n) 
"},{"location":"api/classrobot__dart_1_1Robot/#function-set_friction_dir-12","title":"function set_friction_dir [\u00bd]","text":"
void robot_dart::Robot::set_friction_dir (\nconst std::string & body_name,\nconst Eigen::Vector3d & direction\n) 
"},{"location":"api/classrobot__dart_1_1Robot/#function-set_friction_dir-22","title":"function set_friction_dir [2/2]","text":"
void robot_dart::Robot::set_friction_dir (\nsize_t body_index,\nconst Eigen::Vector3d & direction\n) 
"},{"location":"api/classrobot__dart_1_1Robot/#function-set_ghost","title":"function set_ghost","text":"
void robot_dart::Robot::set_ghost (\nbool ghost=true\n) 
"},{"location":"api/classrobot__dart_1_1Robot/#function-set_joint_name","title":"function set_joint_name","text":"
void robot_dart::Robot::set_joint_name (\nsize_t joint_index,\nconst std::string & joint_name\n) 
"},{"location":"api/classrobot__dart_1_1Robot/#function-set_mimic","title":"function set_mimic","text":"
void robot_dart::Robot::set_mimic (\nconst std::string & joint_name,\nconst std::string & mimic_joint_name,\ndouble multiplier=1.,\ndouble offset=0.\n) 
"},{"location":"api/classrobot__dart_1_1Robot/#function-set_position_enforced-12","title":"function set_position_enforced [\u00bd]","text":"
void robot_dart::Robot::set_position_enforced (\nconst std::vector< bool > & enforced,\nconst std::vector< std::string > & dof_names={}\n) 
"},{"location":"api/classrobot__dart_1_1Robot/#function-set_position_enforced-22","title":"function set_position_enforced [2/2]","text":"
void robot_dart::Robot::set_position_enforced (\nbool enforced,\nconst std::vector< std::string > & dof_names={}\n) 
"},{"location":"api/classrobot__dart_1_1Robot/#function-set_position_lower_limits","title":"function set_position_lower_limits","text":"
void robot_dart::Robot::set_position_lower_limits (\nconst Eigen::VectorXd & positions,\nconst std::vector< std::string > & dof_names={}\n) 
"},{"location":"api/classrobot__dart_1_1Robot/#function-set_position_upper_limits","title":"function set_position_upper_limits","text":"
void robot_dart::Robot::set_position_upper_limits (\nconst Eigen::VectorXd & positions,\nconst std::vector< std::string > & dof_names={}\n) 
"},{"location":"api/classrobot__dart_1_1Robot/#function-set_positions","title":"function set_positions","text":"
void robot_dart::Robot::set_positions (\nconst Eigen::VectorXd & positions,\nconst std::vector< std::string > & dof_names={}\n) 
"},{"location":"api/classrobot__dart_1_1Robot/#function-set_restitution_coeff-12","title":"function set_restitution_coeff [\u00bd]","text":"
void robot_dart::Robot::set_restitution_coeff (\nconst std::string & body_name,\ndouble value\n) 
"},{"location":"api/classrobot__dart_1_1Robot/#function-set_restitution_coeff-22","title":"function set_restitution_coeff [2/2]","text":"
void robot_dart::Robot::set_restitution_coeff (\nsize_t body_index,\ndouble value\n) 
"},{"location":"api/classrobot__dart_1_1Robot/#function-set_restitution_coeffs","title":"function set_restitution_coeffs","text":"
void robot_dart::Robot::set_restitution_coeffs (\ndouble value\n) 
"},{"location":"api/classrobot__dart_1_1Robot/#function-set_secondary_friction_coeff-12","title":"function set_secondary_friction_coeff [\u00bd]","text":"
void robot_dart::Robot::set_secondary_friction_coeff (\nconst std::string & body_name,\ndouble value\n) 
"},{"location":"api/classrobot__dart_1_1Robot/#function-set_secondary_friction_coeff-22","title":"function set_secondary_friction_coeff [2/2]","text":"
void robot_dart::Robot::set_secondary_friction_coeff (\nsize_t body_index,\ndouble value\n) 
"},{"location":"api/classrobot__dart_1_1Robot/#function-set_secondary_friction_coeffs","title":"function set_secondary_friction_coeffs","text":"
void robot_dart::Robot::set_secondary_friction_coeffs (\ndouble value\n) 
"},{"location":"api/classrobot__dart_1_1Robot/#function-set_self_collision","title":"function set_self_collision","text":"
void robot_dart::Robot::set_self_collision (\nbool enable_self_collisions=true,\nbool enable_adjacent_collisions=false\n) 
"},{"location":"api/classrobot__dart_1_1Robot/#function-set_spring_stiffnesses-12","title":"function set_spring_stiffnesses [\u00bd]","text":"
void robot_dart::Robot::set_spring_stiffnesses (\nconst std::vector< double > & stiffnesses,\nconst std::vector< std::string > & dof_names={}\n) 
"},{"location":"api/classrobot__dart_1_1Robot/#function-set_spring_stiffnesses-22","title":"function set_spring_stiffnesses [2/2]","text":"
void robot_dart::Robot::set_spring_stiffnesses (\ndouble stiffness,\nconst std::vector< std::string > & dof_names={}\n) 
"},{"location":"api/classrobot__dart_1_1Robot/#function-set_velocities","title":"function set_velocities","text":"
void robot_dart::Robot::set_velocities (\nconst Eigen::VectorXd & velocities,\nconst std::vector< std::string > & dof_names={}\n) 
"},{"location":"api/classrobot__dart_1_1Robot/#function-set_velocity_lower_limits","title":"function set_velocity_lower_limits","text":"
void robot_dart::Robot::set_velocity_lower_limits (\nconst Eigen::VectorXd & velocities,\nconst std::vector< std::string > & dof_names={}\n) 
"},{"location":"api/classrobot__dart_1_1Robot/#function-set_velocity_upper_limits","title":"function set_velocity_upper_limits","text":"
void robot_dart::Robot::set_velocity_upper_limits (\nconst Eigen::VectorXd & velocities,\nconst std::vector< std::string > & dof_names={}\n) 
"},{"location":"api/classrobot__dart_1_1Robot/#function-skeleton","title":"function skeleton","text":"
dart::dynamics::SkeletonPtr robot_dart::Robot::skeleton () 
"},{"location":"api/classrobot__dart_1_1Robot/#function-spring_stiffnesses","title":"function spring_stiffnesses","text":"
std::vector< double > robot_dart::Robot::spring_stiffnesses (\nconst std::vector< std::string > & dof_names={}\n) const\n
"},{"location":"api/classrobot__dart_1_1Robot/#function-update","title":"function update","text":"
void robot_dart::Robot::update (\ndouble t\n) 
"},{"location":"api/classrobot__dart_1_1Robot/#function-update_joint_dof_maps","title":"function update_joint_dof_maps","text":"
void robot_dart::Robot::update_joint_dof_maps () 
"},{"location":"api/classrobot__dart_1_1Robot/#function-vec_dof","title":"function vec_dof","text":"
Eigen::VectorXd robot_dart::Robot::vec_dof (\nconst Eigen::VectorXd & vec,\nconst std::vector< std::string > & dof_names\n) const\n
"},{"location":"api/classrobot__dart_1_1Robot/#function-velocities","title":"function velocities","text":"
Eigen::VectorXd robot_dart::Robot::velocities (\nconst std::vector< std::string > & dof_names={}\n) const\n
"},{"location":"api/classrobot__dart_1_1Robot/#function-velocity_lower_limits","title":"function velocity_lower_limits","text":"
Eigen::VectorXd robot_dart::Robot::velocity_lower_limits (\nconst std::vector< std::string > & dof_names={}\n) const\n
"},{"location":"api/classrobot__dart_1_1Robot/#function-velocity_upper_limits","title":"function velocity_upper_limits","text":"
Eigen::VectorXd robot_dart::Robot::velocity_upper_limits (\nconst std::vector< std::string > & dof_names={}\n) const\n
"},{"location":"api/classrobot__dart_1_1Robot/#function-robot","title":"function ~Robot","text":"
inline virtual robot_dart::Robot::~Robot () 
"},{"location":"api/classrobot__dart_1_1Robot/#public-static-functions-documentation","title":"Public Static Functions Documentation","text":""},{"location":"api/classrobot__dart_1_1Robot/#function-create_box-12","title":"function create_box [\u00bd]","text":"
static std::shared_ptr< Robot > robot_dart::Robot::create_box (\nconst Eigen::Vector3d & dims,\nconst Eigen::Isometry3d & tf,\nconst std::string & type=\"free\",\ndouble mass=1.0,\nconst Eigen::Vector4d & color=dart::Color::Red(1.0),\nconst std::string & box_name=\"box\"\n) 
"},{"location":"api/classrobot__dart_1_1Robot/#function-create_box-22","title":"function create_box [2/2]","text":"
static std::shared_ptr< Robot > robot_dart::Robot::create_box (\nconst Eigen::Vector3d & dims,\nconst Eigen::Vector6d & pose=Eigen::Vector6d::Zero(),\nconst std::string & type=\"free\",\ndouble mass=1.0,\nconst Eigen::Vector4d & color=dart::Color::Red(1.0),\nconst std::string & box_name=\"box\"\n) 
"},{"location":"api/classrobot__dart_1_1Robot/#function-create_ellipsoid-12","title":"function create_ellipsoid [\u00bd]","text":"
static std::shared_ptr< Robot > robot_dart::Robot::create_ellipsoid (\nconst Eigen::Vector3d & dims,\nconst Eigen::Isometry3d & tf,\nconst std::string & type=\"free\",\ndouble mass=1.0,\nconst Eigen::Vector4d & color=dart::Color::Red(1.0),\nconst std::string & ellipsoid_name=\"ellipsoid\"\n) 
"},{"location":"api/classrobot__dart_1_1Robot/#function-create_ellipsoid-22","title":"function create_ellipsoid [2/2]","text":"
static std::shared_ptr< Robot > robot_dart::Robot::create_ellipsoid (\nconst Eigen::Vector3d & dims,\nconst Eigen::Vector6d & pose=Eigen::Vector6d::Zero(),\nconst std::string & type=\"free\",\ndouble mass=1.0,\nconst Eigen::Vector4d & color=dart::Color::Red(1.0),\nconst std::string & ellipsoid_name=\"ellipsoid\"\n) 
"},{"location":"api/classrobot__dart_1_1Robot/#protected-attributes-documentation","title":"Protected Attributes Documentation","text":""},{"location":"api/classrobot__dart_1_1Robot/#variable-_axis_shapes","title":"variable _axis_shapes","text":"
std::vector<std::pair<dart::dynamics::BodyNode*, double> > robot_dart::Robot::_axis_shapes;\n
"},{"location":"api/classrobot__dart_1_1Robot/#variable-_cast_shadows","title":"variable _cast_shadows","text":"
bool robot_dart::Robot::_cast_shadows;\n
"},{"location":"api/classrobot__dart_1_1Robot/#variable-_controllers","title":"variable _controllers","text":"
std::vector<std::shared_ptr<control::RobotControl> > robot_dart::Robot::_controllers;\n
"},{"location":"api/classrobot__dart_1_1Robot/#variable-_dof_map","title":"variable _dof_map","text":"
std::unordered_map<std::string, size_t> robot_dart::Robot::_dof_map;\n
"},{"location":"api/classrobot__dart_1_1Robot/#variable-_is_ghost","title":"variable _is_ghost","text":"
bool robot_dart::Robot::_is_ghost;\n
"},{"location":"api/classrobot__dart_1_1Robot/#variable-_joint_map","title":"variable _joint_map","text":"
std::unordered_map<std::string, size_t> robot_dart::Robot::_joint_map;\n
"},{"location":"api/classrobot__dart_1_1Robot/#variable-_model_filename","title":"variable _model_filename","text":"
std::string robot_dart::Robot::_model_filename;\n
"},{"location":"api/classrobot__dart_1_1Robot/#variable-_packages","title":"variable _packages","text":"
std::vector<std::pair<std::string, std::string> > robot_dart::Robot::_packages;\n
"},{"location":"api/classrobot__dart_1_1Robot/#variable-_robot_name","title":"variable _robot_name","text":"
std::string robot_dart::Robot::_robot_name;\n
"},{"location":"api/classrobot__dart_1_1Robot/#variable-_skeleton","title":"variable _skeleton","text":"
dart::dynamics::SkeletonPtr robot_dart::Robot::_skeleton;\n
"},{"location":"api/classrobot__dart_1_1Robot/#protected-functions-documentation","title":"Protected Functions Documentation","text":""},{"location":"api/classrobot__dart_1_1Robot/#function-_actuator_type","title":"function _actuator_type","text":"
dart::dynamics::Joint::ActuatorType robot_dart::Robot::_actuator_type (\nsize_t joint_index\n) const\n
"},{"location":"api/classrobot__dart_1_1Robot/#function-_actuator_types","title":"function _actuator_types","text":"
std::vector< dart::dynamics::Joint::ActuatorType > robot_dart::Robot::_actuator_types () const\n
"},{"location":"api/classrobot__dart_1_1Robot/#function-_get_path","title":"function _get_path","text":"
std::string robot_dart::Robot::_get_path (\nconst std::string & filename\n) const\n
"},{"location":"api/classrobot__dart_1_1Robot/#function-_jacobian","title":"function _jacobian","text":"
Eigen::MatrixXd robot_dart::Robot::_jacobian (\nconst Eigen::MatrixXd & full_jacobian,\nconst std::vector< std::string > & dof_names\n) const\n
"},{"location":"api/classrobot__dart_1_1Robot/#function-_load_model","title":"function _load_model","text":"
dart::dynamics::SkeletonPtr robot_dart::Robot::_load_model (\nconst std::string & filename,\nconst std::vector< std::pair< std::string, std::string > > & packages=std::vector< std::pair< std::string, std::string > >(),\nbool is_urdf_string=false\n) 
"},{"location":"api/classrobot__dart_1_1Robot/#function-_mass_matrix","title":"function _mass_matrix","text":"
Eigen::MatrixXd robot_dart::Robot::_mass_matrix (\nconst Eigen::MatrixXd & full_mass_matrix,\nconst std::vector< std::string > & dof_names\n) const\n
"},{"location":"api/classrobot__dart_1_1Robot/#function-_post_addition","title":"function _post_addition","text":"
inline virtual void robot_dart::Robot::_post_addition (\nRobotDARTSimu *\n) 
"},{"location":"api/classrobot__dart_1_1Robot/#function-_post_removal","title":"function _post_removal","text":"
inline virtual void robot_dart::Robot::_post_removal (\nRobotDARTSimu *\n) 
"},{"location":"api/classrobot__dart_1_1Robot/#function-_set_actuator_type","title":"function _set_actuator_type","text":"
void robot_dart::Robot::_set_actuator_type (\nsize_t joint_index,\ndart::dynamics::Joint::ActuatorType type,\nbool override_mimic=false,\nbool override_base=false\n) 
"},{"location":"api/classrobot__dart_1_1Robot/#function-_set_actuator_types-12","title":"function _set_actuator_types [\u00bd]","text":"
void robot_dart::Robot::_set_actuator_types (\nconst std::vector< dart::dynamics::Joint::ActuatorType > & types,\nbool override_mimic=false,\nbool override_base=false\n) 
"},{"location":"api/classrobot__dart_1_1Robot/#function-_set_actuator_types-22","title":"function _set_actuator_types [2/2]","text":"
void robot_dart::Robot::_set_actuator_types (\ndart::dynamics::Joint::ActuatorType type,\nbool override_mimic=false,\nbool override_base=false\n) 
"},{"location":"api/classrobot__dart_1_1Robot/#function-_set_color_mode-12","title":"function _set_color_mode [\u00bd]","text":"
void robot_dart::Robot::_set_color_mode (\ndart::dynamics::MeshShape::ColorMode color_mode,\ndart::dynamics::SkeletonPtr skel\n) 
"},{"location":"api/classrobot__dart_1_1Robot/#function-_set_color_mode-22","title":"function _set_color_mode [2/2]","text":"
void robot_dart::Robot::_set_color_mode (\ndart::dynamics::MeshShape::ColorMode color_mode,\ndart::dynamics::ShapeNode * sn\n) 

The documentation for this class was generated from the following file robot_dart/robot.hpp

"},{"location":"api/classrobot__dart_1_1RobotDARTSimu/","title":"Class robot_dart::RobotDARTSimu","text":"

ClassList > robot_dart > RobotDARTSimu

"},{"location":"api/classrobot__dart_1_1RobotDARTSimu/#public-types","title":"Public Types","text":"Type Name typedef std::shared_ptr< Robot > robot_t"},{"location":"api/classrobot__dart_1_1RobotDARTSimu/#public-functions","title":"Public Functions","text":"Type Name RobotDARTSimu (double timestep=0.015) std::shared_ptr< Robot > add_checkerboard_floor (double floor_width=10.0, double floor_height=0.1, double size=1., const Eigen::Isometry3d & tf=Eigen::Isometry3d::Identity(), const std::string & floor_name=\"checkerboard_floor\", const Eigen::Vector4d & first_color=dart::Color::White(1.), const Eigen::Vector4d & second_color=dart::Color::Gray(1.)) std::shared_ptr< Robot > add_floor (double floor_width=10.0, double floor_height=0.1, const Eigen::Isometry3d & tf=Eigen::Isometry3d::Identity(), const std::string & floor_name=\"floor\") void add_robot (const robot_t & robot) std::shared_ptr< T > add_sensor (Args &&... args) void add_sensor (const std::shared_ptr< sensor::Sensor > & sensor) std::shared_ptr< simu::TextData > add_text (const std::string & text, const Eigen::Affine2d & tf=Eigen::Affine2d::Identity(), Eigen::Vector4d color=Eigen::Vector4d(1, 1, 1, 1), std::uint8_t alignment=(1|3<< 3), bool draw_bg=false, Eigen::Vector4d bg_color=Eigen::Vector4d(0, 0, 0, 0.75), double font_size=28) void add_visual_robot (const robot_t & robot) void clear_robots () void clear_sensors () uint32_t collision_category (size_t robot_index, const std::string & body_name) uint32_t collision_category (size_t robot_index, size_t body_index) const std::string & collision_detector () const uint32_t collision_mask (size_t robot_index, const std::string & body_name) uint32_t collision_mask (size_t robot_index, size_t body_index) std::pair< uint32_t, uint32_t > collision_masks (size_t robot_index, const std::string & body_name) std::pair< uint32_t, uint32_t > collision_masks (size_t robot_index, size_t body_index) int control_freq () const void enable_status_bar (bool enable=true, double font_size=-1) void enable_text_panel (bool enable=true, double font_size=-1) std::shared_ptr< gui::Base > graphics () const int graphics_freq () const Eigen::Vector3d gravity () const simu::GUIData * gui_data () bool halted_sim () const size_t num_robots () const int physics_freq () const void remove_all_collision_masks () void remove_collision_masks (size_t robot_index) void remove_collision_masks (size_t robot_index, const std::string & body_name) void remove_collision_masks (size_t robot_index, size_t body_index) void remove_robot (const robot_t & robot) void remove_robot (size_t index) void remove_sensor (const std::shared_ptr< sensor::Sensor > & sensor) void remove_sensor (size_t index) void remove_sensors (const std::string & type) robot_t robot (size_t index) const int robot_index (const robot_t & robot) const const std::vector< robot_t > & robots () const void run (double max_duration=5.0, bool reset_commands=false, bool force_position_bounds=true) bool schedule (int freq) Scheduler & scheduler () const Scheduler & scheduler () const std::shared_ptr< sensor::Sensor > sensor (size_t index) const std::vector< std::shared_ptr< sensor::Sensor > > sensors () const void set_collision_detector (const std::string & collision_detector) void set_collision_masks (size_t robot_index, uint32_t category_mask, uint32_t collision_mask) void set_collision_masks (size_t robot_index, const std::string & body_name, uint32_t category_mask, uint32_t collision_mask) void set_collision_masks (size_t robot_index, size_t body_index, uint32_t category_mask, uint32_t collision_mask) void set_control_freq (int frequency) void set_graphics (const std::shared_ptr< gui::Base > & graphics) void set_graphics_freq (int frequency) void set_gravity (const Eigen::Vector3d & gravity) void set_text_panel (const std::string & str) void set_timestep (double timestep, bool update_control_freq=true) std::string status_bar_text () const bool step (bool reset_commands=false, bool force_position_bounds=true) bool step_world (bool reset_commands=false, bool force_position_bounds=true) void stop_sim (bool disable=true) std::string text_panel_text () const double timestep () const dart::simulation::WorldPtr world () ~RobotDARTSimu ()"},{"location":"api/classrobot__dart_1_1RobotDARTSimu/#protected-attributes","title":"Protected Attributes","text":"Type Name bool _break int _control_freq = = -1 std::shared_ptr< gui::Base > _graphics int _graphics_freq = = 40 std::unique_ptr< simu::GUIData > _gui_data size_t _old_index int _physics_freq = = -1 std::vector< robot_t > _robots Scheduler _scheduler std::vector< std::shared_ptr< sensor::Sensor > > _sensors std::shared_ptr< simu::TextData > _status_bar = = nullptr std::shared_ptr< simu::TextData > _text_panel = = nullptr dart::simulation::WorldPtr _world"},{"location":"api/classrobot__dart_1_1RobotDARTSimu/#protected-functions","title":"Protected Functions","text":"Type Name void _enable (std::shared_ptr< simu::TextData > & text, bool enable, double font_size)"},{"location":"api/classrobot__dart_1_1RobotDARTSimu/#public-types-documentation","title":"Public Types Documentation","text":""},{"location":"api/classrobot__dart_1_1RobotDARTSimu/#typedef-robot_t","title":"typedef robot_t","text":"
using robot_dart::RobotDARTSimu::robot_t =  std::shared_ptr<Robot>;\n
"},{"location":"api/classrobot__dart_1_1RobotDARTSimu/#public-functions-documentation","title":"Public Functions Documentation","text":""},{"location":"api/classrobot__dart_1_1RobotDARTSimu/#function-robotdartsimu","title":"function RobotDARTSimu","text":"
robot_dart::RobotDARTSimu::RobotDARTSimu (\ndouble timestep=0.015\n) 
"},{"location":"api/classrobot__dart_1_1RobotDARTSimu/#function-add_checkerboard_floor","title":"function add_checkerboard_floor","text":"
std::shared_ptr< Robot > robot_dart::RobotDARTSimu::add_checkerboard_floor (\ndouble floor_width=10.0,\ndouble floor_height=0.1,\ndouble size=1.,\nconst Eigen::Isometry3d & tf=Eigen::Isometry3d::Identity(),\nconst std::string & floor_name=\"checkerboard_floor\",\nconst Eigen::Vector4d & first_color=dart::Color::White(1.),\nconst Eigen::Vector4d & second_color=dart::Color::Gray(1.)\n) 
"},{"location":"api/classrobot__dart_1_1RobotDARTSimu/#function-add_floor","title":"function add_floor","text":"
std::shared_ptr< Robot > robot_dart::RobotDARTSimu::add_floor (\ndouble floor_width=10.0,\ndouble floor_height=0.1,\nconst Eigen::Isometry3d & tf=Eigen::Isometry3d::Identity(),\nconst std::string & floor_name=\"floor\"\n) 
"},{"location":"api/classrobot__dart_1_1RobotDARTSimu/#function-add_robot","title":"function add_robot","text":"
void robot_dart::RobotDARTSimu::add_robot (\nconst robot_t & robot\n) 
"},{"location":"api/classrobot__dart_1_1RobotDARTSimu/#function-add_sensor-12","title":"function add_sensor [\u00bd]","text":"
template<typename T typename T, typename... Args>\ninline std::shared_ptr< T > robot_dart::RobotDARTSimu::add_sensor (\nArgs &&... args\n) 
"},{"location":"api/classrobot__dart_1_1RobotDARTSimu/#function-add_sensor-22","title":"function add_sensor [2/2]","text":"
void robot_dart::RobotDARTSimu::add_sensor (\nconst std::shared_ptr< sensor::Sensor > & sensor\n) 
"},{"location":"api/classrobot__dart_1_1RobotDARTSimu/#function-add_text","title":"function add_text","text":"
std::shared_ptr< simu::TextData > robot_dart::RobotDARTSimu::add_text (\nconst std::string & text,\nconst Eigen::Affine2d & tf=Eigen::Affine2d::Identity(),\nEigen::Vector4d color=Eigen::Vector4d(1, 1, 1, 1),\nstd::uint8_t alignment=(1|3<< 3),\nbool draw_bg=false,\nEigen::Vector4d bg_color=Eigen::Vector4d(0, 0, 0, 0.75),\ndouble font_size=28\n) 
"},{"location":"api/classrobot__dart_1_1RobotDARTSimu/#function-add_visual_robot","title":"function add_visual_robot","text":"
void robot_dart::RobotDARTSimu::add_visual_robot (\nconst robot_t & robot\n) 
"},{"location":"api/classrobot__dart_1_1RobotDARTSimu/#function-clear_robots","title":"function clear_robots","text":"
void robot_dart::RobotDARTSimu::clear_robots () 
"},{"location":"api/classrobot__dart_1_1RobotDARTSimu/#function-clear_sensors","title":"function clear_sensors","text":"
void robot_dart::RobotDARTSimu::clear_sensors () 
"},{"location":"api/classrobot__dart_1_1RobotDARTSimu/#function-collision_category-12","title":"function collision_category [\u00bd]","text":"
uint32_t robot_dart::RobotDARTSimu::collision_category (\nsize_t robot_index,\nconst std::string & body_name\n) 
"},{"location":"api/classrobot__dart_1_1RobotDARTSimu/#function-collision_category-22","title":"function collision_category [2/2]","text":"
uint32_t robot_dart::RobotDARTSimu::collision_category (\nsize_t robot_index,\nsize_t body_index\n) 
"},{"location":"api/classrobot__dart_1_1RobotDARTSimu/#function-collision_detector","title":"function collision_detector","text":"
const std::string & robot_dart::RobotDARTSimu::collision_detector () const\n
"},{"location":"api/classrobot__dart_1_1RobotDARTSimu/#function-collision_mask-12","title":"function collision_mask [\u00bd]","text":"
uint32_t robot_dart::RobotDARTSimu::collision_mask (\nsize_t robot_index,\nconst std::string & body_name\n) 
"},{"location":"api/classrobot__dart_1_1RobotDARTSimu/#function-collision_mask-22","title":"function collision_mask [2/2]","text":"
uint32_t robot_dart::RobotDARTSimu::collision_mask (\nsize_t robot_index,\nsize_t body_index\n) 
"},{"location":"api/classrobot__dart_1_1RobotDARTSimu/#function-collision_masks-12","title":"function collision_masks [\u00bd]","text":"
std::pair< uint32_t, uint32_t > robot_dart::RobotDARTSimu::collision_masks (\nsize_t robot_index,\nconst std::string & body_name\n) 
"},{"location":"api/classrobot__dart_1_1RobotDARTSimu/#function-collision_masks-22","title":"function collision_masks [2/2]","text":"
std::pair< uint32_t, uint32_t > robot_dart::RobotDARTSimu::collision_masks (\nsize_t robot_index,\nsize_t body_index\n) 
"},{"location":"api/classrobot__dart_1_1RobotDARTSimu/#function-control_freq","title":"function control_freq","text":"
inline int robot_dart::RobotDARTSimu::control_freq () const\n
"},{"location":"api/classrobot__dart_1_1RobotDARTSimu/#function-enable_status_bar","title":"function enable_status_bar","text":"
void robot_dart::RobotDARTSimu::enable_status_bar (\nbool enable=true,\ndouble font_size=-1\n) 
"},{"location":"api/classrobot__dart_1_1RobotDARTSimu/#function-enable_text_panel","title":"function enable_text_panel","text":"
void robot_dart::RobotDARTSimu::enable_text_panel (\nbool enable=true,\ndouble font_size=-1\n) 
"},{"location":"api/classrobot__dart_1_1RobotDARTSimu/#function-graphics","title":"function graphics","text":"
std::shared_ptr< gui::Base > robot_dart::RobotDARTSimu::graphics () const\n
"},{"location":"api/classrobot__dart_1_1RobotDARTSimu/#function-graphics_freq","title":"function graphics_freq","text":"
inline int robot_dart::RobotDARTSimu::graphics_freq () const\n
"},{"location":"api/classrobot__dart_1_1RobotDARTSimu/#function-gravity","title":"function gravity","text":"
Eigen::Vector3d robot_dart::RobotDARTSimu::gravity () const\n
"},{"location":"api/classrobot__dart_1_1RobotDARTSimu/#function-gui_data","title":"function gui_data","text":"
simu::GUIData * robot_dart::RobotDARTSimu::gui_data () 
"},{"location":"api/classrobot__dart_1_1RobotDARTSimu/#function-halted_sim","title":"function halted_sim","text":"
bool robot_dart::RobotDARTSimu::halted_sim () const\n
"},{"location":"api/classrobot__dart_1_1RobotDARTSimu/#function-num_robots","title":"function num_robots","text":"
size_t robot_dart::RobotDARTSimu::num_robots () const\n
"},{"location":"api/classrobot__dart_1_1RobotDARTSimu/#function-physics_freq","title":"function physics_freq","text":"
inline int robot_dart::RobotDARTSimu::physics_freq () const\n
"},{"location":"api/classrobot__dart_1_1RobotDARTSimu/#function-remove_all_collision_masks","title":"function remove_all_collision_masks","text":"
void robot_dart::RobotDARTSimu::remove_all_collision_masks () 
"},{"location":"api/classrobot__dart_1_1RobotDARTSimu/#function-remove_collision_masks-13","title":"function remove_collision_masks [\u2153]","text":"
void robot_dart::RobotDARTSimu::remove_collision_masks (\nsize_t robot_index\n) 
"},{"location":"api/classrobot__dart_1_1RobotDARTSimu/#function-remove_collision_masks-23","title":"function remove_collision_masks [\u2154]","text":"
void robot_dart::RobotDARTSimu::remove_collision_masks (\nsize_t robot_index,\nconst std::string & body_name\n) 
"},{"location":"api/classrobot__dart_1_1RobotDARTSimu/#function-remove_collision_masks-33","title":"function remove_collision_masks [3/3]","text":"
void robot_dart::RobotDARTSimu::remove_collision_masks (\nsize_t robot_index,\nsize_t body_index\n) 
"},{"location":"api/classrobot__dart_1_1RobotDARTSimu/#function-remove_robot-12","title":"function remove_robot [\u00bd]","text":"
void robot_dart::RobotDARTSimu::remove_robot (\nconst robot_t & robot\n) 
"},{"location":"api/classrobot__dart_1_1RobotDARTSimu/#function-remove_robot-22","title":"function remove_robot [2/2]","text":"
void robot_dart::RobotDARTSimu::remove_robot (\nsize_t index\n) 
"},{"location":"api/classrobot__dart_1_1RobotDARTSimu/#function-remove_sensor-12","title":"function remove_sensor [\u00bd]","text":"
void robot_dart::RobotDARTSimu::remove_sensor (\nconst std::shared_ptr< sensor::Sensor > & sensor\n) 
"},{"location":"api/classrobot__dart_1_1RobotDARTSimu/#function-remove_sensor-22","title":"function remove_sensor [2/2]","text":"
void robot_dart::RobotDARTSimu::remove_sensor (\nsize_t index\n) 
"},{"location":"api/classrobot__dart_1_1RobotDARTSimu/#function-remove_sensors","title":"function remove_sensors","text":"
void robot_dart::RobotDARTSimu::remove_sensors (\nconst std::string & type\n) 
"},{"location":"api/classrobot__dart_1_1RobotDARTSimu/#function-robot","title":"function robot","text":"
robot_t robot_dart::RobotDARTSimu::robot (\nsize_t index\n) const\n
"},{"location":"api/classrobot__dart_1_1RobotDARTSimu/#function-robot_index","title":"function robot_index","text":"
int robot_dart::RobotDARTSimu::robot_index (\nconst robot_t & robot\n) const\n
"},{"location":"api/classrobot__dart_1_1RobotDARTSimu/#function-robots","title":"function robots","text":"
const std::vector< robot_t > & robot_dart::RobotDARTSimu::robots () const\n
"},{"location":"api/classrobot__dart_1_1RobotDARTSimu/#function-run","title":"function run","text":"
void robot_dart::RobotDARTSimu::run (\ndouble max_duration=5.0,\nbool reset_commands=false,\nbool force_position_bounds=true\n) 
"},{"location":"api/classrobot__dart_1_1RobotDARTSimu/#function-schedule","title":"function schedule","text":"
inline bool robot_dart::RobotDARTSimu::schedule (\nint freq\n) 
"},{"location":"api/classrobot__dart_1_1RobotDARTSimu/#function-scheduler-12","title":"function scheduler [\u00bd]","text":"
inline Scheduler & robot_dart::RobotDARTSimu::scheduler () 
"},{"location":"api/classrobot__dart_1_1RobotDARTSimu/#function-scheduler-22","title":"function scheduler [2/2]","text":"
inline const Scheduler & robot_dart::RobotDARTSimu::scheduler () const\n
"},{"location":"api/classrobot__dart_1_1RobotDARTSimu/#function-sensor","title":"function sensor","text":"
std::shared_ptr< sensor::Sensor > robot_dart::RobotDARTSimu::sensor (\nsize_t index\n) const\n
"},{"location":"api/classrobot__dart_1_1RobotDARTSimu/#function-sensors","title":"function sensors","text":"
std::vector< std::shared_ptr< sensor::Sensor > > robot_dart::RobotDARTSimu::sensors () const\n
"},{"location":"api/classrobot__dart_1_1RobotDARTSimu/#function-set_collision_detector","title":"function set_collision_detector","text":"
void robot_dart::RobotDARTSimu::set_collision_detector (\nconst std::string & collision_detector\n) 
"},{"location":"api/classrobot__dart_1_1RobotDARTSimu/#function-set_collision_masks-13","title":"function set_collision_masks [\u2153]","text":"
void robot_dart::RobotDARTSimu::set_collision_masks (\nsize_t robot_index,\nuint32_t category_mask,\nuint32_t collision_mask\n) 
"},{"location":"api/classrobot__dart_1_1RobotDARTSimu/#function-set_collision_masks-23","title":"function set_collision_masks [\u2154]","text":"
void robot_dart::RobotDARTSimu::set_collision_masks (\nsize_t robot_index,\nconst std::string & body_name,\nuint32_t category_mask,\nuint32_t collision_mask\n) 
"},{"location":"api/classrobot__dart_1_1RobotDARTSimu/#function-set_collision_masks-33","title":"function set_collision_masks [3/3]","text":"
void robot_dart::RobotDARTSimu::set_collision_masks (\nsize_t robot_index,\nsize_t body_index,\nuint32_t category_mask,\nuint32_t collision_mask\n) 
"},{"location":"api/classrobot__dart_1_1RobotDARTSimu/#function-set_control_freq","title":"function set_control_freq","text":"
inline void robot_dart::RobotDARTSimu::set_control_freq (\nint frequency\n) 
"},{"location":"api/classrobot__dart_1_1RobotDARTSimu/#function-set_graphics","title":"function set_graphics","text":"
void robot_dart::RobotDARTSimu::set_graphics (\nconst std::shared_ptr< gui::Base > & graphics\n) 
"},{"location":"api/classrobot__dart_1_1RobotDARTSimu/#function-set_graphics_freq","title":"function set_graphics_freq","text":"
inline void robot_dart::RobotDARTSimu::set_graphics_freq (\nint frequency\n) 
"},{"location":"api/classrobot__dart_1_1RobotDARTSimu/#function-set_gravity","title":"function set_gravity","text":"
void robot_dart::RobotDARTSimu::set_gravity (\nconst Eigen::Vector3d & gravity\n) 
"},{"location":"api/classrobot__dart_1_1RobotDARTSimu/#function-set_text_panel","title":"function set_text_panel","text":"
void robot_dart::RobotDARTSimu::set_text_panel (\nconst std::string & str\n) 
"},{"location":"api/classrobot__dart_1_1RobotDARTSimu/#function-set_timestep","title":"function set_timestep","text":"
void robot_dart::RobotDARTSimu::set_timestep (\ndouble timestep,\nbool update_control_freq=true\n) 
"},{"location":"api/classrobot__dart_1_1RobotDARTSimu/#function-status_bar_text","title":"function status_bar_text","text":"
std::string robot_dart::RobotDARTSimu::status_bar_text () const\n
"},{"location":"api/classrobot__dart_1_1RobotDARTSimu/#function-step","title":"function step","text":"
bool robot_dart::RobotDARTSimu::step (\nbool reset_commands=false,\nbool force_position_bounds=true\n) 
"},{"location":"api/classrobot__dart_1_1RobotDARTSimu/#function-step_world","title":"function step_world","text":"
bool robot_dart::RobotDARTSimu::step_world (\nbool reset_commands=false,\nbool force_position_bounds=true\n) 
"},{"location":"api/classrobot__dart_1_1RobotDARTSimu/#function-stop_sim","title":"function stop_sim","text":"
void robot_dart::RobotDARTSimu::stop_sim (\nbool disable=true\n) 
"},{"location":"api/classrobot__dart_1_1RobotDARTSimu/#function-text_panel_text","title":"function text_panel_text","text":"
std::string robot_dart::RobotDARTSimu::text_panel_text () const\n
"},{"location":"api/classrobot__dart_1_1RobotDARTSimu/#function-timestep","title":"function timestep","text":"
double robot_dart::RobotDARTSimu::timestep () const\n
"},{"location":"api/classrobot__dart_1_1RobotDARTSimu/#function-world","title":"function world","text":"
dart::simulation::WorldPtr robot_dart::RobotDARTSimu::world () 
"},{"location":"api/classrobot__dart_1_1RobotDARTSimu/#function-robotdartsimu_1","title":"function ~RobotDARTSimu","text":"
robot_dart::RobotDARTSimu::~RobotDARTSimu () 
"},{"location":"api/classrobot__dart_1_1RobotDARTSimu/#protected-attributes-documentation","title":"Protected Attributes Documentation","text":""},{"location":"api/classrobot__dart_1_1RobotDARTSimu/#variable-_break","title":"variable _break","text":"
bool robot_dart::RobotDARTSimu::_break;\n
"},{"location":"api/classrobot__dart_1_1RobotDARTSimu/#variable-_control_freq","title":"variable _control_freq","text":"
int robot_dart::RobotDARTSimu::_control_freq;\n
"},{"location":"api/classrobot__dart_1_1RobotDARTSimu/#variable-_graphics","title":"variable _graphics","text":"
std::shared_ptr<gui::Base> robot_dart::RobotDARTSimu::_graphics;\n
"},{"location":"api/classrobot__dart_1_1RobotDARTSimu/#variable-_graphics_freq","title":"variable _graphics_freq","text":"
int robot_dart::RobotDARTSimu::_graphics_freq;\n
"},{"location":"api/classrobot__dart_1_1RobotDARTSimu/#variable-_gui_data","title":"variable _gui_data","text":"
std::unique_ptr<simu::GUIData> robot_dart::RobotDARTSimu::_gui_data;\n
"},{"location":"api/classrobot__dart_1_1RobotDARTSimu/#variable-_old_index","title":"variable _old_index","text":"
size_t robot_dart::RobotDARTSimu::_old_index;\n
"},{"location":"api/classrobot__dart_1_1RobotDARTSimu/#variable-_physics_freq","title":"variable _physics_freq","text":"
int robot_dart::RobotDARTSimu::_physics_freq;\n
"},{"location":"api/classrobot__dart_1_1RobotDARTSimu/#variable-_robots","title":"variable _robots","text":"
std::vector<robot_t> robot_dart::RobotDARTSimu::_robots;\n
"},{"location":"api/classrobot__dart_1_1RobotDARTSimu/#variable-_scheduler","title":"variable _scheduler","text":"
Scheduler robot_dart::RobotDARTSimu::_scheduler;\n
"},{"location":"api/classrobot__dart_1_1RobotDARTSimu/#variable-_sensors","title":"variable _sensors","text":"
std::vector<std::shared_ptr<sensor::Sensor> > robot_dart::RobotDARTSimu::_sensors;\n
"},{"location":"api/classrobot__dart_1_1RobotDARTSimu/#variable-_status_bar","title":"variable _status_bar","text":"
std::shared_ptr<simu::TextData> robot_dart::RobotDARTSimu::_status_bar;\n
"},{"location":"api/classrobot__dart_1_1RobotDARTSimu/#variable-_text_panel","title":"variable _text_panel","text":"
std::shared_ptr<simu::TextData> robot_dart::RobotDARTSimu::_text_panel;\n
"},{"location":"api/classrobot__dart_1_1RobotDARTSimu/#variable-_world","title":"variable _world","text":"
dart::simulation::WorldPtr robot_dart::RobotDARTSimu::_world;\n
"},{"location":"api/classrobot__dart_1_1RobotDARTSimu/#protected-functions-documentation","title":"Protected Functions Documentation","text":""},{"location":"api/classrobot__dart_1_1RobotDARTSimu/#function-_enable","title":"function _enable","text":"
void robot_dart::RobotDARTSimu::_enable (\nstd::shared_ptr< simu::TextData > & text,\nbool enable,\ndouble font_size\n) 

The documentation for this class was generated from the following file robot_dart/robot_dart_simu.hpp

"},{"location":"api/classrobot__dart_1_1RobotPool/","title":"Class robot_dart::RobotPool","text":"

ClassList > robot_dart > RobotPool

"},{"location":"api/classrobot__dart_1_1RobotPool/#public-types","title":"Public Types","text":"Type Name typedef std::function< std::shared_ptr< Robot >()> robot_creator_t"},{"location":"api/classrobot__dart_1_1RobotPool/#public-functions","title":"Public Functions","text":"Type Name RobotPool (const robot_creator_t & robot_creator, size_t pool_size=32, bool verbose=true) RobotPool (const RobotPool &) = delete virtual void free_robot (const std::shared_ptr< Robot > & robot) virtual std::shared_ptr< Robot > get_robot (const std::string & name=\"robot\") const std::string & model_filename () const void operator= (const RobotPool &) = delete virtual ~RobotPool ()"},{"location":"api/classrobot__dart_1_1RobotPool/#protected-attributes","title":"Protected Attributes","text":"Type Name std::vector< bool > _free std::string _model_filename size_t _pool_size robot_creator_t _robot_creator std::mutex _skeleton_mutex std::vector< dart::dynamics::SkeletonPtr > _skeletons bool _verbose"},{"location":"api/classrobot__dart_1_1RobotPool/#protected-functions","title":"Protected Functions","text":"Type Name virtual void _reset_robot (const std::shared_ptr< Robot > & robot)"},{"location":"api/classrobot__dart_1_1RobotPool/#public-types-documentation","title":"Public Types Documentation","text":""},{"location":"api/classrobot__dart_1_1RobotPool/#typedef-robot_creator_t","title":"typedef robot_creator_t","text":"
using robot_dart::RobotPool::robot_creator_t =  std::function<std::shared_ptr<Robot>()>;\n
"},{"location":"api/classrobot__dart_1_1RobotPool/#public-functions-documentation","title":"Public Functions Documentation","text":""},{"location":"api/classrobot__dart_1_1RobotPool/#function-robotpool-12","title":"function RobotPool [\u00bd]","text":"
robot_dart::RobotPool::RobotPool (\nconst robot_creator_t & robot_creator,\nsize_t pool_size=32,\nbool verbose=true\n) 
"},{"location":"api/classrobot__dart_1_1RobotPool/#function-robotpool-22","title":"function RobotPool [2/2]","text":"
robot_dart::RobotPool::RobotPool (\nconst RobotPool &\n) = delete\n
"},{"location":"api/classrobot__dart_1_1RobotPool/#function-free_robot","title":"function free_robot","text":"
virtual void robot_dart::RobotPool::free_robot (\nconst std::shared_ptr< Robot > & robot\n) 
"},{"location":"api/classrobot__dart_1_1RobotPool/#function-get_robot","title":"function get_robot","text":"
virtual std::shared_ptr< Robot > robot_dart::RobotPool::get_robot (\nconst std::string & name=\"robot\"\n) 
"},{"location":"api/classrobot__dart_1_1RobotPool/#function-model_filename","title":"function model_filename","text":"
inline const std::string & robot_dart::RobotPool::model_filename () const\n
"},{"location":"api/classrobot__dart_1_1RobotPool/#function-operator","title":"function operator=","text":"
void robot_dart::RobotPool::operator= (\nconst RobotPool &\n) = delete\n
"},{"location":"api/classrobot__dart_1_1RobotPool/#function-robotpool","title":"function ~RobotPool","text":"
inline virtual robot_dart::RobotPool::~RobotPool () 
"},{"location":"api/classrobot__dart_1_1RobotPool/#protected-attributes-documentation","title":"Protected Attributes Documentation","text":""},{"location":"api/classrobot__dart_1_1RobotPool/#variable-_free","title":"variable _free","text":"
std::vector<bool> robot_dart::RobotPool::_free;\n
"},{"location":"api/classrobot__dart_1_1RobotPool/#variable-_model_filename","title":"variable _model_filename","text":"
std::string robot_dart::RobotPool::_model_filename;\n
"},{"location":"api/classrobot__dart_1_1RobotPool/#variable-_pool_size","title":"variable _pool_size","text":"
size_t robot_dart::RobotPool::_pool_size;\n
"},{"location":"api/classrobot__dart_1_1RobotPool/#variable-_robot_creator","title":"variable _robot_creator","text":"
robot_creator_t robot_dart::RobotPool::_robot_creator;\n
"},{"location":"api/classrobot__dart_1_1RobotPool/#variable-_skeleton_mutex","title":"variable _skeleton_mutex","text":"
std::mutex robot_dart::RobotPool::_skeleton_mutex;\n
"},{"location":"api/classrobot__dart_1_1RobotPool/#variable-_skeletons","title":"variable _skeletons","text":"
std::vector<dart::dynamics::SkeletonPtr> robot_dart::RobotPool::_skeletons;\n
"},{"location":"api/classrobot__dart_1_1RobotPool/#variable-_verbose","title":"variable _verbose","text":"
bool robot_dart::RobotPool::_verbose;\n
"},{"location":"api/classrobot__dart_1_1RobotPool/#protected-functions-documentation","title":"Protected Functions Documentation","text":""},{"location":"api/classrobot__dart_1_1RobotPool/#function-_reset_robot","title":"function _reset_robot","text":"
virtual void robot_dart::RobotPool::_reset_robot (\nconst std::shared_ptr< Robot > & robot\n) 

The documentation for this class was generated from the following file robot_dart/robot_pool.hpp

"},{"location":"api/classrobot__dart_1_1Scheduler/","title":"Class robot_dart::Scheduler","text":"

ClassList > robot_dart > Scheduler

"},{"location":"api/classrobot__dart_1_1Scheduler/#public-functions","title":"Public Functions","text":"Type Name Scheduler (double dt, bool sync=false) double current_time () constcurrent time according to the simulation (simulation clock) double dt () constdt used by the simulation (simulation clock) double it_duration () const double last_it_duration () const double next_time () constnext time according to the simulation (simulation clock) bool operator() (int frequency) double real_time () consttime according to the clock's computer (wall clock) double real_time_factor () const void reset (double dt, bool sync=false, double current_time=0., double real_time=0.) bool schedule (int frequency) void set_sync (bool enable) double step () bool sync () const"},{"location":"api/classrobot__dart_1_1Scheduler/#protected-types","title":"Protected Types","text":"Type Name typedef std::chrono::high_resolution_clock clock_t"},{"location":"api/classrobot__dart_1_1Scheduler/#protected-attributes","title":"Protected Attributes","text":"Type Name double _average_it_duration = = 0. int _current_step = = 0 double _current_time = = 0. double _dt double _it_duration = = 0. clock_t::time_point _last_iteration_time int _max_frequency = = -1 double _real_start_time = = 0. double _real_time = = 0. double _simu_start_time = = 0. clock_t::time_point _start_time bool _sync"},{"location":"api/classrobot__dart_1_1Scheduler/#public-functions-documentation","title":"Public Functions Documentation","text":""},{"location":"api/classrobot__dart_1_1Scheduler/#function-scheduler","title":"function Scheduler","text":"
inline robot_dart::Scheduler::Scheduler (\ndouble dt,\nbool sync=false\n) 
"},{"location":"api/classrobot__dart_1_1Scheduler/#function-current_time","title":"function current_time","text":"
inline double robot_dart::Scheduler::current_time () const\n
"},{"location":"api/classrobot__dart_1_1Scheduler/#function-dt","title":"function dt","text":"
inline double robot_dart::Scheduler::dt () const\n
"},{"location":"api/classrobot__dart_1_1Scheduler/#function-it_duration","title":"function it_duration","text":"
inline double robot_dart::Scheduler::it_duration () const\n
"},{"location":"api/classrobot__dart_1_1Scheduler/#function-last_it_duration","title":"function last_it_duration","text":"
inline double robot_dart::Scheduler::last_it_duration () const\n
"},{"location":"api/classrobot__dart_1_1Scheduler/#function-next_time","title":"function next_time","text":"
inline double robot_dart::Scheduler::next_time () const\n
"},{"location":"api/classrobot__dart_1_1Scheduler/#function-operator","title":"function operator()","text":"
inline bool robot_dart::Scheduler::operator() (\nint frequency\n) 
"},{"location":"api/classrobot__dart_1_1Scheduler/#function-real_time","title":"function real_time","text":"
inline double robot_dart::Scheduler::real_time () const\n
"},{"location":"api/classrobot__dart_1_1Scheduler/#function-real_time_factor","title":"function real_time_factor","text":"
inline double robot_dart::Scheduler::real_time_factor () const\n
"},{"location":"api/classrobot__dart_1_1Scheduler/#function-reset","title":"function reset","text":"
void robot_dart::Scheduler::reset (\ndouble dt,\nbool sync=false,\ndouble current_time=0.,\ndouble real_time=0.\n) 
"},{"location":"api/classrobot__dart_1_1Scheduler/#function-schedule","title":"function schedule","text":"
bool robot_dart::Scheduler::schedule (\nint frequency\n) 
"},{"location":"api/classrobot__dart_1_1Scheduler/#function-set_sync","title":"function set_sync","text":"
inline void robot_dart::Scheduler::set_sync (\nbool enable\n) 

synchronize the simulation clock with the wall clock (when possible, i.e. when the simulation is faster than real time)

"},{"location":"api/classrobot__dart_1_1Scheduler/#function-step","title":"function step","text":"
double robot_dart::Scheduler::step () 

call this at the end of the loop (see examples) this will synchronize with real time if requested and increase the counter; returns the real-time (in seconds)

"},{"location":"api/classrobot__dart_1_1Scheduler/#function-sync","title":"function sync","text":"
inline bool robot_dart::Scheduler::sync () const\n
"},{"location":"api/classrobot__dart_1_1Scheduler/#protected-types-documentation","title":"Protected Types Documentation","text":""},{"location":"api/classrobot__dart_1_1Scheduler/#typedef-clock_t","title":"typedef clock_t","text":"
using robot_dart::Scheduler::clock_t =  std::chrono::high_resolution_clock;\n
"},{"location":"api/classrobot__dart_1_1Scheduler/#protected-attributes-documentation","title":"Protected Attributes Documentation","text":""},{"location":"api/classrobot__dart_1_1Scheduler/#variable-_average_it_duration","title":"variable _average_it_duration","text":"
double robot_dart::Scheduler::_average_it_duration;\n
"},{"location":"api/classrobot__dart_1_1Scheduler/#variable-_current_step","title":"variable _current_step","text":"
int robot_dart::Scheduler::_current_step;\n
"},{"location":"api/classrobot__dart_1_1Scheduler/#variable-_current_time","title":"variable _current_time","text":"
double robot_dart::Scheduler::_current_time;\n
"},{"location":"api/classrobot__dart_1_1Scheduler/#variable-_dt","title":"variable _dt","text":"
double robot_dart::Scheduler::_dt;\n
"},{"location":"api/classrobot__dart_1_1Scheduler/#variable-_it_duration","title":"variable _it_duration","text":"
double robot_dart::Scheduler::_it_duration;\n
"},{"location":"api/classrobot__dart_1_1Scheduler/#variable-_last_iteration_time","title":"variable _last_iteration_time","text":"
clock_t::time_point robot_dart::Scheduler::_last_iteration_time;\n
"},{"location":"api/classrobot__dart_1_1Scheduler/#variable-_max_frequency","title":"variable _max_frequency","text":"
int robot_dart::Scheduler::_max_frequency;\n
"},{"location":"api/classrobot__dart_1_1Scheduler/#variable-_real_start_time","title":"variable _real_start_time","text":"
double robot_dart::Scheduler::_real_start_time;\n
"},{"location":"api/classrobot__dart_1_1Scheduler/#variable-_real_time","title":"variable _real_time","text":"
double robot_dart::Scheduler::_real_time;\n
"},{"location":"api/classrobot__dart_1_1Scheduler/#variable-_simu_start_time","title":"variable _simu_start_time","text":"
double robot_dart::Scheduler::_simu_start_time;\n
"},{"location":"api/classrobot__dart_1_1Scheduler/#variable-_start_time","title":"variable _start_time","text":"
clock_t::time_point robot_dart::Scheduler::_start_time;\n
"},{"location":"api/classrobot__dart_1_1Scheduler/#variable-_sync","title":"variable _sync","text":"
bool robot_dart::Scheduler::_sync;\n

The documentation for this class was generated from the following file robot_dart/scheduler.hpp

"},{"location":"api/namespacerobot__dart_1_1collision__filter/","title":"Namespace robot_dart::collision_filter","text":"

Namespace List > robot_dart > collision_filter

"},{"location":"api/namespacerobot__dart_1_1collision__filter/#classes","title":"Classes","text":"Type Name class BitmaskContactFilter

The documentation for this class was generated from the following file robot_dart/robot_dart_simu.cpp

"},{"location":"api/classrobot__dart_1_1collision__filter_1_1BitmaskContactFilter/","title":"Class robot_dart::collision_filter::BitmaskContactFilter","text":"

ClassList > robot_dart > collision_filter > BitmaskContactFilter

Inherits the following classes: dart::collision::BodyNodeCollisionFilter

"},{"location":"api/classrobot__dart_1_1collision__filter_1_1BitmaskContactFilter/#classes","title":"Classes","text":"Type Name struct Masks"},{"location":"api/classrobot__dart_1_1collision__filter_1_1BitmaskContactFilter/#public-types","title":"Public Types","text":"Type Name typedef const dart::collision::CollisionObject * DartCollisionConstPtr typedef const dart::dynamics::ShapeNode * DartShapeConstPtr"},{"location":"api/classrobot__dart_1_1collision__filter_1_1BitmaskContactFilter/#public-functions","title":"Public Functions","text":"Type Name void add_to_map (DartShapeConstPtr shape, uint32_t col_mask, uint32_t cat_mask) void add_to_map (dart::dynamics::SkeletonPtr skel, uint32_t col_mask, uint32_t cat_mask) void clear_all () bool ignoresCollision (DartCollisionConstPtr object1, DartCollisionConstPtr object2) override const Masks mask (DartShapeConstPtr shape) const void remove_from_map (DartShapeConstPtr shape) void remove_from_map (dart::dynamics::SkeletonPtr skel) virtual ~BitmaskContactFilter () = default"},{"location":"api/classrobot__dart_1_1collision__filter_1_1BitmaskContactFilter/#public-types-documentation","title":"Public Types Documentation","text":""},{"location":"api/classrobot__dart_1_1collision__filter_1_1BitmaskContactFilter/#typedef-dartcollisionconstptr","title":"typedef DartCollisionConstPtr","text":"
using robot_dart::collision_filter::BitmaskContactFilter::DartCollisionConstPtr =  const dart::collision::CollisionObject*;\n
"},{"location":"api/classrobot__dart_1_1collision__filter_1_1BitmaskContactFilter/#typedef-dartshapeconstptr","title":"typedef DartShapeConstPtr","text":"
using robot_dart::collision_filter::BitmaskContactFilter::DartShapeConstPtr =  const dart::dynamics::ShapeNode*;\n
"},{"location":"api/classrobot__dart_1_1collision__filter_1_1BitmaskContactFilter/#public-functions-documentation","title":"Public Functions Documentation","text":""},{"location":"api/classrobot__dart_1_1collision__filter_1_1BitmaskContactFilter/#function-add_to_map-12","title":"function add_to_map [\u00bd]","text":"
inline void robot_dart::collision_filter::BitmaskContactFilter::add_to_map (\nDartShapeConstPtr shape,\nuint32_t col_mask,\nuint32_t cat_mask\n) 
"},{"location":"api/classrobot__dart_1_1collision__filter_1_1BitmaskContactFilter/#function-add_to_map-22","title":"function add_to_map [2/2]","text":"
inline void robot_dart::collision_filter::BitmaskContactFilter::add_to_map (\ndart::dynamics::SkeletonPtr skel,\nuint32_t col_mask,\nuint32_t cat_mask\n) 
"},{"location":"api/classrobot__dart_1_1collision__filter_1_1BitmaskContactFilter/#function-clear_all","title":"function clear_all","text":"
inline void robot_dart::collision_filter::BitmaskContactFilter::clear_all () 
"},{"location":"api/classrobot__dart_1_1collision__filter_1_1BitmaskContactFilter/#function-ignorescollision","title":"function ignoresCollision","text":"
inline bool robot_dart::collision_filter::BitmaskContactFilter::ignoresCollision (\nDartCollisionConstPtr object1,\nDartCollisionConstPtr object2\n) override const\n
"},{"location":"api/classrobot__dart_1_1collision__filter_1_1BitmaskContactFilter/#function-mask","title":"function mask","text":"
inline Masks robot_dart::collision_filter::BitmaskContactFilter::mask (\nDartShapeConstPtr shape\n) const\n
"},{"location":"api/classrobot__dart_1_1collision__filter_1_1BitmaskContactFilter/#function-remove_from_map-12","title":"function remove_from_map [\u00bd]","text":"
inline void robot_dart::collision_filter::BitmaskContactFilter::remove_from_map (\nDartShapeConstPtr shape\n) 
"},{"location":"api/classrobot__dart_1_1collision__filter_1_1BitmaskContactFilter/#function-remove_from_map-22","title":"function remove_from_map [2/2]","text":"
inline void robot_dart::collision_filter::BitmaskContactFilter::remove_from_map (\ndart::dynamics::SkeletonPtr skel\n) 
"},{"location":"api/classrobot__dart_1_1collision__filter_1_1BitmaskContactFilter/#function-bitmaskcontactfilter","title":"function ~BitmaskContactFilter","text":"
virtual robot_dart::collision_filter::BitmaskContactFilter::~BitmaskContactFilter () = default\n

The documentation for this class was generated from the following file robot_dart/robot_dart_simu.cpp

"},{"location":"api/structrobot__dart_1_1collision__filter_1_1BitmaskContactFilter_1_1Masks/","title":"Struct robot_dart::collision_filter::BitmaskContactFilter::Masks","text":"

ClassList > robot_dart > collision_filter > BitmaskContactFilter > Masks

"},{"location":"api/structrobot__dart_1_1collision__filter_1_1BitmaskContactFilter_1_1Masks/#public-attributes","title":"Public Attributes","text":"Type Name uint32_t category_mask = = 0xffffffff uint32_t collision_mask = = 0xffffffff"},{"location":"api/structrobot__dart_1_1collision__filter_1_1BitmaskContactFilter_1_1Masks/#public-attributes-documentation","title":"Public Attributes Documentation","text":""},{"location":"api/structrobot__dart_1_1collision__filter_1_1BitmaskContactFilter_1_1Masks/#variable-category_mask","title":"variable category_mask","text":"
uint32_t robot_dart::collision_filter::BitmaskContactFilter::Masks::category_mask;\n
"},{"location":"api/structrobot__dart_1_1collision__filter_1_1BitmaskContactFilter_1_1Masks/#variable-collision_mask","title":"variable collision_mask","text":"
uint32_t robot_dart::collision_filter::BitmaskContactFilter::Masks::collision_mask;\n

The documentation for this class was generated from the following file robot_dart/robot_dart_simu.cpp

"},{"location":"api/namespacerobot__dart_1_1control/","title":"Namespace robot_dart::control","text":"

Namespace List > robot_dart > control

"},{"location":"api/namespacerobot__dart_1_1control/#classes","title":"Classes","text":"Type Name class PDControl class PolicyControl <typename Policy> class RobotControl class SimpleControl

The documentation for this class was generated from the following file robot_dart/control/pd_control.cpp

"},{"location":"api/classrobot__dart_1_1control_1_1PDControl/","title":"Class robot_dart::control::PDControl","text":"

ClassList > robot_dart > control > PDControl

Inherits the following classes: robot_dart::control::RobotControl

"},{"location":"api/classrobot__dart_1_1control_1_1PDControl/#public-functions","title":"Public Functions","text":"Type Name PDControl () PDControl (const Eigen::VectorXd & ctrl, bool full_control=false, bool use_angular_errors=true) PDControl (const Eigen::VectorXd & ctrl, const std::vector< std::string > & controllable_dofs, bool use_angular_errors=true) virtual Eigen::VectorXd calculate (double) override virtual std::shared_ptr< RobotControl > clone () override const virtual void configure () override std::pair< Eigen::VectorXd, Eigen::VectorXd > pd () const void set_pd (double p, double d) void set_pd (const Eigen::VectorXd & p, const Eigen::VectorXd & d) void set_use_angular_errors (bool enable=true) bool using_angular_errors () const"},{"location":"api/classrobot__dart_1_1control_1_1PDControl/#public-functions-inherited-from-robot_dartcontrolrobotcontrol","title":"Public Functions inherited from robot_dart::control::RobotControl","text":"

See robot_dart::control::RobotControl

Type Name RobotControl () RobotControl (const Eigen::VectorXd & ctrl, bool full_control=false) RobotControl (const Eigen::VectorXd & ctrl, const std::vector< std::string > & controllable_dofs) void activate (bool enable=true) bool active () const virtual Eigen::VectorXd calculate (double t) = 0 virtual std::shared_ptr< RobotControl > clone () const = 0 virtual void configure () = 0 const std::vector< std::string > & controllable_dofs () const void init () const Eigen::VectorXd & parameters () const std::shared_ptr< Robot > robot () const void set_parameters (const Eigen::VectorXd & ctrl) void set_robot (const std::shared_ptr< Robot > & robot) void set_weight (double weight) double weight () const virtual ~RobotControl ()"},{"location":"api/classrobot__dart_1_1control_1_1PDControl/#protected-attributes","title":"Protected Attributes","text":"Type Name Eigen::VectorXd _Kd Eigen::VectorXd _Kp bool _use_angular_errors"},{"location":"api/classrobot__dart_1_1control_1_1PDControl/#protected-attributes-inherited-from-robot_dartcontrolrobotcontrol","title":"Protected Attributes inherited from robot_dart::control::RobotControl","text":"

See robot_dart::control::RobotControl

Type Name bool _active bool _check_free = = false int _control_dof std::vector< std::string > _controllable_dofs Eigen::VectorXd _ctrl int _dof std::weak_ptr< Robot > _robot double _weight"},{"location":"api/classrobot__dart_1_1control_1_1PDControl/#protected-static-functions","title":"Protected Static Functions","text":"Type Name double _angle_dist (double target, double current)"},{"location":"api/classrobot__dart_1_1control_1_1PDControl/#public-functions-documentation","title":"Public Functions Documentation","text":""},{"location":"api/classrobot__dart_1_1control_1_1PDControl/#function-pdcontrol-13","title":"function PDControl [\u2153]","text":"
robot_dart::control::PDControl::PDControl () 
"},{"location":"api/classrobot__dart_1_1control_1_1PDControl/#function-pdcontrol-23","title":"function PDControl [\u2154]","text":"
robot_dart::control::PDControl::PDControl (\nconst Eigen::VectorXd & ctrl,\nbool full_control=false,\nbool use_angular_errors=true\n) 
"},{"location":"api/classrobot__dart_1_1control_1_1PDControl/#function-pdcontrol-33","title":"function PDControl [3/3]","text":"
robot_dart::control::PDControl::PDControl (\nconst Eigen::VectorXd & ctrl,\nconst std::vector< std::string > & controllable_dofs,\nbool use_angular_errors=true\n) 
"},{"location":"api/classrobot__dart_1_1control_1_1PDControl/#function-calculate","title":"function calculate","text":"
virtual Eigen::VectorXd robot_dart::control::PDControl::calculate (\ndouble\n) override\n

Implements robot_dart::control::RobotControl::calculate

"},{"location":"api/classrobot__dart_1_1control_1_1PDControl/#function-clone","title":"function clone","text":"
virtual std::shared_ptr< RobotControl > robot_dart::control::PDControl::clone () override const\n

Implements robot_dart::control::RobotControl::clone

"},{"location":"api/classrobot__dart_1_1control_1_1PDControl/#function-configure","title":"function configure","text":"
virtual void robot_dart::control::PDControl::configure () override\n

Implements robot_dart::control::RobotControl::configure

"},{"location":"api/classrobot__dart_1_1control_1_1PDControl/#function-pd","title":"function pd","text":"
std::pair< Eigen::VectorXd, Eigen::VectorXd > robot_dart::control::PDControl::pd () const\n
"},{"location":"api/classrobot__dart_1_1control_1_1PDControl/#function-set_pd-12","title":"function set_pd [\u00bd]","text":"
void robot_dart::control::PDControl::set_pd (\ndouble p,\ndouble d\n) 
"},{"location":"api/classrobot__dart_1_1control_1_1PDControl/#function-set_pd-22","title":"function set_pd [2/2]","text":"
void robot_dart::control::PDControl::set_pd (\nconst Eigen::VectorXd & p,\nconst Eigen::VectorXd & d\n) 
"},{"location":"api/classrobot__dart_1_1control_1_1PDControl/#function-set_use_angular_errors","title":"function set_use_angular_errors","text":"
void robot_dart::control::PDControl::set_use_angular_errors (\nbool enable=true\n) 
"},{"location":"api/classrobot__dart_1_1control_1_1PDControl/#function-using_angular_errors","title":"function using_angular_errors","text":"
bool robot_dart::control::PDControl::using_angular_errors () const\n
"},{"location":"api/classrobot__dart_1_1control_1_1PDControl/#protected-attributes-documentation","title":"Protected Attributes Documentation","text":""},{"location":"api/classrobot__dart_1_1control_1_1PDControl/#variable-_kd","title":"variable _Kd","text":"
Eigen::VectorXd robot_dart::control::PDControl::_Kd;\n
"},{"location":"api/classrobot__dart_1_1control_1_1PDControl/#variable-_kp","title":"variable _Kp","text":"
Eigen::VectorXd robot_dart::control::PDControl::_Kp;\n
"},{"location":"api/classrobot__dart_1_1control_1_1PDControl/#variable-_use_angular_errors","title":"variable _use_angular_errors","text":"
bool robot_dart::control::PDControl::_use_angular_errors;\n
"},{"location":"api/classrobot__dart_1_1control_1_1PDControl/#protected-static-functions-documentation","title":"Protected Static Functions Documentation","text":""},{"location":"api/classrobot__dart_1_1control_1_1PDControl/#function-_angle_dist","title":"function _angle_dist","text":"
static double robot_dart::control::PDControl::_angle_dist (\ndouble target,\ndouble current\n) 

The documentation for this class was generated from the following file robot_dart/control/pd_control.hpp

"},{"location":"api/classrobot__dart_1_1control_1_1PolicyControl/","title":"Class robot_dart::control::PolicyControl","text":"

template <typename Policy typename Policy>

ClassList > robot_dart > control > PolicyControl

Inherits the following classes: robot_dart::control::RobotControl

"},{"location":"api/classrobot__dart_1_1control_1_1PolicyControl/#public-functions","title":"Public Functions","text":"Type Name PolicyControl () PolicyControl (double dt, const Eigen::VectorXd & ctrl, bool full_control=false) PolicyControl (const Eigen::VectorXd & ctrl, bool full_control=false) PolicyControl (double dt, const Eigen::VectorXd & ctrl, const std::vector< std::string > & controllable_dofs) PolicyControl (const Eigen::VectorXd & ctrl, const std::vector< std::string > & controllable_dofs) virtual Eigen::VectorXd calculate (double t) override virtual std::shared_ptr< RobotControl > clone () override const virtual void configure () override Eigen::VectorXd h_params () const void set_h_params (const Eigen::VectorXd & h_params)"},{"location":"api/classrobot__dart_1_1control_1_1PolicyControl/#public-functions-inherited-from-robot_dartcontrolrobotcontrol","title":"Public Functions inherited from robot_dart::control::RobotControl","text":"

See robot_dart::control::RobotControl

Type Name RobotControl () RobotControl (const Eigen::VectorXd & ctrl, bool full_control=false) RobotControl (const Eigen::VectorXd & ctrl, const std::vector< std::string > & controllable_dofs) void activate (bool enable=true) bool active () const virtual Eigen::VectorXd calculate (double t) = 0 virtual std::shared_ptr< RobotControl > clone () const = 0 virtual void configure () = 0 const std::vector< std::string > & controllable_dofs () const void init () const Eigen::VectorXd & parameters () const std::shared_ptr< Robot > robot () const void set_parameters (const Eigen::VectorXd & ctrl) void set_robot (const std::shared_ptr< Robot > & robot) void set_weight (double weight) double weight () const virtual ~RobotControl ()"},{"location":"api/classrobot__dart_1_1control_1_1PolicyControl/#protected-attributes","title":"Protected Attributes","text":"Type Name double _dt bool _first bool _full_dt int _i Policy _policy Eigen::VectorXd _prev_commands double _prev_time double _threshold"},{"location":"api/classrobot__dart_1_1control_1_1PolicyControl/#protected-attributes-inherited-from-robot_dartcontrolrobotcontrol","title":"Protected Attributes inherited from robot_dart::control::RobotControl","text":"

See robot_dart::control::RobotControl

Type Name bool _active bool _check_free = = false int _control_dof std::vector< std::string > _controllable_dofs Eigen::VectorXd _ctrl int _dof std::weak_ptr< Robot > _robot double _weight"},{"location":"api/classrobot__dart_1_1control_1_1PolicyControl/#public-functions-documentation","title":"Public Functions Documentation","text":""},{"location":"api/classrobot__dart_1_1control_1_1PolicyControl/#function-policycontrol-15","title":"function PolicyControl [\u2155]","text":"
inline robot_dart::control::PolicyControl::PolicyControl () 
"},{"location":"api/classrobot__dart_1_1control_1_1PolicyControl/#function-policycontrol-25","title":"function PolicyControl [\u2156]","text":"
inline robot_dart::control::PolicyControl::PolicyControl (\ndouble dt,\nconst Eigen::VectorXd & ctrl,\nbool full_control=false\n) 
"},{"location":"api/classrobot__dart_1_1control_1_1PolicyControl/#function-policycontrol-35","title":"function PolicyControl [\u2157]","text":"
inline robot_dart::control::PolicyControl::PolicyControl (\nconst Eigen::VectorXd & ctrl,\nbool full_control=false\n) 
"},{"location":"api/classrobot__dart_1_1control_1_1PolicyControl/#function-policycontrol-45","title":"function PolicyControl [\u2158]","text":"
inline robot_dart::control::PolicyControl::PolicyControl (\ndouble dt,\nconst Eigen::VectorXd & ctrl,\nconst std::vector< std::string > & controllable_dofs\n) 
"},{"location":"api/classrobot__dart_1_1control_1_1PolicyControl/#function-policycontrol-55","title":"function PolicyControl [5/5]","text":"
inline robot_dart::control::PolicyControl::PolicyControl (\nconst Eigen::VectorXd & ctrl,\nconst std::vector< std::string > & controllable_dofs\n) 
"},{"location":"api/classrobot__dart_1_1control_1_1PolicyControl/#function-calculate","title":"function calculate","text":"
inline virtual Eigen::VectorXd robot_dart::control::PolicyControl::calculate (\ndouble t\n) override\n

Implements robot_dart::control::RobotControl::calculate

"},{"location":"api/classrobot__dart_1_1control_1_1PolicyControl/#function-clone","title":"function clone","text":"
inline virtual std::shared_ptr< RobotControl > robot_dart::control::PolicyControl::clone () override const\n

Implements robot_dart::control::RobotControl::clone

"},{"location":"api/classrobot__dart_1_1control_1_1PolicyControl/#function-configure","title":"function configure","text":"
inline virtual void robot_dart::control::PolicyControl::configure () override\n

Implements robot_dart::control::RobotControl::configure

"},{"location":"api/classrobot__dart_1_1control_1_1PolicyControl/#function-h_params","title":"function h_params","text":"
inline Eigen::VectorXd robot_dart::control::PolicyControl::h_params () const\n
"},{"location":"api/classrobot__dart_1_1control_1_1PolicyControl/#function-set_h_params","title":"function set_h_params","text":"
inline void robot_dart::control::PolicyControl::set_h_params (\nconst Eigen::VectorXd & h_params\n) 
"},{"location":"api/classrobot__dart_1_1control_1_1PolicyControl/#protected-attributes-documentation","title":"Protected Attributes Documentation","text":""},{"location":"api/classrobot__dart_1_1control_1_1PolicyControl/#variable-_dt","title":"variable _dt","text":"
double robot_dart::control::PolicyControl< Policy >::_dt;\n
"},{"location":"api/classrobot__dart_1_1control_1_1PolicyControl/#variable-_first","title":"variable _first","text":"
bool robot_dart::control::PolicyControl< Policy >::_first;\n
"},{"location":"api/classrobot__dart_1_1control_1_1PolicyControl/#variable-_full_dt","title":"variable _full_dt","text":"
bool robot_dart::control::PolicyControl< Policy >::_full_dt;\n
"},{"location":"api/classrobot__dart_1_1control_1_1PolicyControl/#variable-_i","title":"variable _i","text":"
int robot_dart::control::PolicyControl< Policy >::_i;\n
"},{"location":"api/classrobot__dart_1_1control_1_1PolicyControl/#variable-_policy","title":"variable _policy","text":"
Policy robot_dart::control::PolicyControl< Policy >::_policy;\n
"},{"location":"api/classrobot__dart_1_1control_1_1PolicyControl/#variable-_prev_commands","title":"variable _prev_commands","text":"
Eigen::VectorXd robot_dart::control::PolicyControl< Policy >::_prev_commands;\n
"},{"location":"api/classrobot__dart_1_1control_1_1PolicyControl/#variable-_prev_time","title":"variable _prev_time","text":"
double robot_dart::control::PolicyControl< Policy >::_prev_time;\n
"},{"location":"api/classrobot__dart_1_1control_1_1PolicyControl/#variable-_threshold","title":"variable _threshold","text":"
double robot_dart::control::PolicyControl< Policy >::_threshold;\n

The documentation for this class was generated from the following file robot_dart/control/policy_control.hpp

"},{"location":"api/classrobot__dart_1_1control_1_1RobotControl/","title":"Class robot_dart::control::RobotControl","text":"

ClassList > robot_dart > control > RobotControl

Inherited by the following classes: robot_dart::control::PDControl, robot_dart::control::PolicyControl, robot_dart::control::SimpleControl

"},{"location":"api/classrobot__dart_1_1control_1_1RobotControl/#public-functions","title":"Public Functions","text":"Type Name RobotControl () RobotControl (const Eigen::VectorXd & ctrl, bool full_control=false) RobotControl (const Eigen::VectorXd & ctrl, const std::vector< std::string > & controllable_dofs) void activate (bool enable=true) bool active () const virtual Eigen::VectorXd calculate (double t) = 0 virtual std::shared_ptr< RobotControl > clone () const = 0 virtual void configure () = 0 const std::vector< std::string > & controllable_dofs () const void init () const Eigen::VectorXd & parameters () const std::shared_ptr< Robot > robot () const void set_parameters (const Eigen::VectorXd & ctrl) void set_robot (const std::shared_ptr< Robot > & robot) void set_weight (double weight) double weight () const virtual ~RobotControl ()"},{"location":"api/classrobot__dart_1_1control_1_1RobotControl/#protected-attributes","title":"Protected Attributes","text":"Type Name bool _active bool _check_free = = false int _control_dof std::vector< std::string > _controllable_dofs Eigen::VectorXd _ctrl int _dof std::weak_ptr< Robot > _robot double _weight"},{"location":"api/classrobot__dart_1_1control_1_1RobotControl/#public-functions-documentation","title":"Public Functions Documentation","text":""},{"location":"api/classrobot__dart_1_1control_1_1RobotControl/#function-robotcontrol-13","title":"function RobotControl [\u2153]","text":"
robot_dart::control::RobotControl::RobotControl () 
"},{"location":"api/classrobot__dart_1_1control_1_1RobotControl/#function-robotcontrol-23","title":"function RobotControl [\u2154]","text":"
robot_dart::control::RobotControl::RobotControl (\nconst Eigen::VectorXd & ctrl,\nbool full_control=false\n) 
"},{"location":"api/classrobot__dart_1_1control_1_1RobotControl/#function-robotcontrol-33","title":"function RobotControl [3/3]","text":"
robot_dart::control::RobotControl::RobotControl (\nconst Eigen::VectorXd & ctrl,\nconst std::vector< std::string > & controllable_dofs\n) 
"},{"location":"api/classrobot__dart_1_1control_1_1RobotControl/#function-activate","title":"function activate","text":"
void robot_dart::control::RobotControl::activate (\nbool enable=true\n) 
"},{"location":"api/classrobot__dart_1_1control_1_1RobotControl/#function-active","title":"function active","text":"
bool robot_dart::control::RobotControl::active () const\n
"},{"location":"api/classrobot__dart_1_1control_1_1RobotControl/#function-calculate","title":"function calculate","text":"
virtual Eigen::VectorXd robot_dart::control::RobotControl::calculate (\ndouble t\n) = 0\n
"},{"location":"api/classrobot__dart_1_1control_1_1RobotControl/#function-clone","title":"function clone","text":"
virtual std::shared_ptr< RobotControl > robot_dart::control::RobotControl::clone () const = 0\n
"},{"location":"api/classrobot__dart_1_1control_1_1RobotControl/#function-configure","title":"function configure","text":"
virtual void robot_dart::control::RobotControl::configure () = 0\n
"},{"location":"api/classrobot__dart_1_1control_1_1RobotControl/#function-controllable_dofs","title":"function controllable_dofs","text":"
const std::vector< std::string > & robot_dart::control::RobotControl::controllable_dofs () const\n
"},{"location":"api/classrobot__dart_1_1control_1_1RobotControl/#function-init","title":"function init","text":"
void robot_dart::control::RobotControl::init () 
"},{"location":"api/classrobot__dart_1_1control_1_1RobotControl/#function-parameters","title":"function parameters","text":"
const Eigen::VectorXd & robot_dart::control::RobotControl::parameters () const\n
"},{"location":"api/classrobot__dart_1_1control_1_1RobotControl/#function-robot","title":"function robot","text":"
std::shared_ptr< Robot > robot_dart::control::RobotControl::robot () const\n
"},{"location":"api/classrobot__dart_1_1control_1_1RobotControl/#function-set_parameters","title":"function set_parameters","text":"
void robot_dart::control::RobotControl::set_parameters (\nconst Eigen::VectorXd & ctrl\n) 
"},{"location":"api/classrobot__dart_1_1control_1_1RobotControl/#function-set_robot","title":"function set_robot","text":"
void robot_dart::control::RobotControl::set_robot (\nconst std::shared_ptr< Robot > & robot\n) 
"},{"location":"api/classrobot__dart_1_1control_1_1RobotControl/#function-set_weight","title":"function set_weight","text":"
void robot_dart::control::RobotControl::set_weight (\ndouble weight\n) 
"},{"location":"api/classrobot__dart_1_1control_1_1RobotControl/#function-weight","title":"function weight","text":"
double robot_dart::control::RobotControl::weight () const\n
"},{"location":"api/classrobot__dart_1_1control_1_1RobotControl/#function-robotcontrol","title":"function ~RobotControl","text":"
inline virtual robot_dart::control::RobotControl::~RobotControl () 
"},{"location":"api/classrobot__dart_1_1control_1_1RobotControl/#protected-attributes-documentation","title":"Protected Attributes Documentation","text":""},{"location":"api/classrobot__dart_1_1control_1_1RobotControl/#variable-_active","title":"variable _active","text":"
bool robot_dart::control::RobotControl::_active;\n
"},{"location":"api/classrobot__dart_1_1control_1_1RobotControl/#variable-_check_free","title":"variable _check_free","text":"
bool robot_dart::control::RobotControl::_check_free;\n
"},{"location":"api/classrobot__dart_1_1control_1_1RobotControl/#variable-_control_dof","title":"variable _control_dof","text":"
int robot_dart::control::RobotControl::_control_dof;\n
"},{"location":"api/classrobot__dart_1_1control_1_1RobotControl/#variable-_controllable_dofs","title":"variable _controllable_dofs","text":"
std::vector<std::string> robot_dart::control::RobotControl::_controllable_dofs;\n
"},{"location":"api/classrobot__dart_1_1control_1_1RobotControl/#variable-_ctrl","title":"variable _ctrl","text":"
Eigen::VectorXd robot_dart::control::RobotControl::_ctrl;\n
"},{"location":"api/classrobot__dart_1_1control_1_1RobotControl/#variable-_dof","title":"variable _dof","text":"
int robot_dart::control::RobotControl::_dof;\n
"},{"location":"api/classrobot__dart_1_1control_1_1RobotControl/#variable-_robot","title":"variable _robot","text":"
std::weak_ptr<Robot> robot_dart::control::RobotControl::_robot;\n
"},{"location":"api/classrobot__dart_1_1control_1_1RobotControl/#variable-_weight","title":"variable _weight","text":"
double robot_dart::control::RobotControl::_weight;\n

The documentation for this class was generated from the following file robot_dart/control/robot_control.hpp

"},{"location":"api/classrobot__dart_1_1control_1_1SimpleControl/","title":"Class robot_dart::control::SimpleControl","text":"

ClassList > robot_dart > control > SimpleControl

Inherits the following classes: robot_dart::control::RobotControl

"},{"location":"api/classrobot__dart_1_1control_1_1SimpleControl/#public-functions","title":"Public Functions","text":"Type Name SimpleControl () SimpleControl (const Eigen::VectorXd & ctrl, bool full_control=false) SimpleControl (const Eigen::VectorXd & ctrl, const std::vector< std::string > & controllable_dofs) virtual Eigen::VectorXd calculate (double) override virtual std::shared_ptr< RobotControl > clone () override const virtual void configure () override"},{"location":"api/classrobot__dart_1_1control_1_1SimpleControl/#public-functions-inherited-from-robot_dartcontrolrobotcontrol","title":"Public Functions inherited from robot_dart::control::RobotControl","text":"

See robot_dart::control::RobotControl

Type Name RobotControl () RobotControl (const Eigen::VectorXd & ctrl, bool full_control=false) RobotControl (const Eigen::VectorXd & ctrl, const std::vector< std::string > & controllable_dofs) void activate (bool enable=true) bool active () const virtual Eigen::VectorXd calculate (double t) = 0 virtual std::shared_ptr< RobotControl > clone () const = 0 virtual void configure () = 0 const std::vector< std::string > & controllable_dofs () const void init () const Eigen::VectorXd & parameters () const std::shared_ptr< Robot > robot () const void set_parameters (const Eigen::VectorXd & ctrl) void set_robot (const std::shared_ptr< Robot > & robot) void set_weight (double weight) double weight () const virtual ~RobotControl ()"},{"location":"api/classrobot__dart_1_1control_1_1SimpleControl/#protected-attributes-inherited-from-robot_dartcontrolrobotcontrol","title":"Protected Attributes inherited from robot_dart::control::RobotControl","text":"

See robot_dart::control::RobotControl

Type Name bool _active bool _check_free = = false int _control_dof std::vector< std::string > _controllable_dofs Eigen::VectorXd _ctrl int _dof std::weak_ptr< Robot > _robot double _weight"},{"location":"api/classrobot__dart_1_1control_1_1SimpleControl/#public-functions-documentation","title":"Public Functions Documentation","text":""},{"location":"api/classrobot__dart_1_1control_1_1SimpleControl/#function-simplecontrol-13","title":"function SimpleControl [\u2153]","text":"
robot_dart::control::SimpleControl::SimpleControl () 
"},{"location":"api/classrobot__dart_1_1control_1_1SimpleControl/#function-simplecontrol-23","title":"function SimpleControl [\u2154]","text":"
robot_dart::control::SimpleControl::SimpleControl (\nconst Eigen::VectorXd & ctrl,\nbool full_control=false\n) 
"},{"location":"api/classrobot__dart_1_1control_1_1SimpleControl/#function-simplecontrol-33","title":"function SimpleControl [3/3]","text":"
robot_dart::control::SimpleControl::SimpleControl (\nconst Eigen::VectorXd & ctrl,\nconst std::vector< std::string > & controllable_dofs\n) 
"},{"location":"api/classrobot__dart_1_1control_1_1SimpleControl/#function-calculate","title":"function calculate","text":"
virtual Eigen::VectorXd robot_dart::control::SimpleControl::calculate (\ndouble\n) override\n

Implements robot_dart::control::RobotControl::calculate

"},{"location":"api/classrobot__dart_1_1control_1_1SimpleControl/#function-clone","title":"function clone","text":"
virtual std::shared_ptr< RobotControl > robot_dart::control::SimpleControl::clone () override const\n

Implements robot_dart::control::RobotControl::clone

"},{"location":"api/classrobot__dart_1_1control_1_1SimpleControl/#function-configure","title":"function configure","text":"
virtual void robot_dart::control::SimpleControl::configure () override\n

Implements robot_dart::control::RobotControl::configure

The documentation for this class was generated from the following file robot_dart/control/simple_control.hpp

"},{"location":"api/namespacerobot__dart_1_1detail/","title":"Namespace robot_dart::detail","text":"

Namespace List > robot_dart > detail

"},{"location":"api/namespacerobot__dart_1_1detail/#public-functions","title":"Public Functions","text":"Type Name void add_dof_data (const Eigen::VectorXd & data, dart::dynamics::SkeletonPtr skeleton, const std::vector< std::string > & dof_names, const std::unordered_map< std::string, size_t > & dof_map) Eigen::VectorXd dof_data (dart::dynamics::SkeletonPtr skeleton, const std::vector< std::string > & dof_names, const std::unordered_map< std::string, size_t > & dof_map) void set_dof_data (const Eigen::VectorXd & data, dart::dynamics::SkeletonPtr skeleton, const std::vector< std::string > & dof_names, const std::unordered_map< std::string, size_t > & dof_map)"},{"location":"api/namespacerobot__dart_1_1detail/#public-functions-documentation","title":"Public Functions Documentation","text":""},{"location":"api/namespacerobot__dart_1_1detail/#function-add_dof_data","title":"function add_dof_data","text":"
template<int content>\nvoid robot_dart::detail::add_dof_data (\nconst Eigen::VectorXd & data,\ndart::dynamics::SkeletonPtr skeleton,\nconst std::vector< std::string > & dof_names,\nconst std::unordered_map< std::string, size_t > & dof_map\n) 
"},{"location":"api/namespacerobot__dart_1_1detail/#function-dof_data","title":"function dof_data","text":"
template<int content>\nEigen::VectorXd robot_dart::detail::dof_data (\ndart::dynamics::SkeletonPtr skeleton,\nconst std::vector< std::string > & dof_names,\nconst std::unordered_map< std::string, size_t > & dof_map\n) 
"},{"location":"api/namespacerobot__dart_1_1detail/#function-set_dof_data","title":"function set_dof_data","text":"
template<int content>\nvoid robot_dart::detail::set_dof_data (\nconst Eigen::VectorXd & data,\ndart::dynamics::SkeletonPtr skeleton,\nconst std::vector< std::string > & dof_names,\nconst std::unordered_map< std::string, size_t > & dof_map\n) 

The documentation for this class was generated from the following file robot_dart/robot.cpp

"},{"location":"api/namespacerobot__dart_1_1gui/","title":"Namespace robot_dart::gui","text":"

Namespace List > robot_dart > gui

"},{"location":"api/namespacerobot__dart_1_1gui/#namespaces","title":"Namespaces","text":"Type Name namespace magnum"},{"location":"api/namespacerobot__dart_1_1gui/#classes","title":"Classes","text":"Type Name class Base struct DepthImage struct GrayscaleImage struct Image"},{"location":"api/namespacerobot__dart_1_1gui/#public-functions","title":"Public Functions","text":"Type Name GrayscaleImage convert_rgb_to_grayscale (const Image & rgb) std::vector< Eigen::Vector3d > point_cloud_from_depth_array (const DepthImage & depth_image, const Eigen::Matrix3d & intrinsic_matrix, const Eigen::Matrix4d & tf, double far_plane) void save_png_image (const std::string & filename, const Image & rgb) void save_png_image (const std::string & filename, const GrayscaleImage & gray)"},{"location":"api/namespacerobot__dart_1_1gui/#public-functions-documentation","title":"Public Functions Documentation","text":""},{"location":"api/namespacerobot__dart_1_1gui/#function-convert_rgb_to_grayscale","title":"function convert_rgb_to_grayscale","text":"
GrayscaleImage robot_dart::gui::convert_rgb_to_grayscale (\nconst Image & rgb\n) 
"},{"location":"api/namespacerobot__dart_1_1gui/#function-point_cloud_from_depth_array","title":"function point_cloud_from_depth_array","text":"
std::vector< Eigen::Vector3d > robot_dart::gui::point_cloud_from_depth_array (\nconst DepthImage & depth_image,\nconst Eigen::Matrix3d & intrinsic_matrix,\nconst Eigen::Matrix4d & tf,\ndouble far_plane\n) 
"},{"location":"api/namespacerobot__dart_1_1gui/#function-save_png_image","title":"function save_png_image","text":"
void robot_dart::gui::save_png_image (\nconst std::string & filename,\nconst Image & rgb\n) 
"},{"location":"api/namespacerobot__dart_1_1gui/#function-save_png_image_1","title":"function save_png_image","text":"
void robot_dart::gui::save_png_image (\nconst std::string & filename,\nconst GrayscaleImage & gray\n) 

The documentation for this class was generated from the following file robot_dart/gui/base.hpp

"},{"location":"api/classrobot__dart_1_1gui_1_1Base/","title":"Class robot_dart::gui::Base","text":"

ClassList > robot_dart > gui > Base

Inherited by the following classes: robot_dart::gui::magnum::BaseGraphics, robot_dart::gui::magnum::BaseGraphics, robot_dart::gui::magnum::BaseGraphics

"},{"location":"api/classrobot__dart_1_1gui_1_1Base/#public-functions","title":"Public Functions","text":"Type Name Base () virtual DepthImage depth_array () virtual GrayscaleImage depth_image () virtual bool done () const virtual size_t height () const virtual Image image () virtual GrayscaleImage raw_depth_image () virtual void refresh () virtual void set_enable (bool) virtual void set_fps (int) virtual void set_render_period (double) virtual void set_simu (RobotDARTSimu * simu) const RobotDARTSimu * simu () const virtual size_t width () const virtual ~Base ()"},{"location":"api/classrobot__dart_1_1gui_1_1Base/#protected-attributes","title":"Protected Attributes","text":"Type Name RobotDARTSimu * _simu = = nullptr"},{"location":"api/classrobot__dart_1_1gui_1_1Base/#public-functions-documentation","title":"Public Functions Documentation","text":""},{"location":"api/classrobot__dart_1_1gui_1_1Base/#function-base","title":"function Base","text":"
inline robot_dart::gui::Base::Base () 
"},{"location":"api/classrobot__dart_1_1gui_1_1Base/#function-depth_array","title":"function depth_array","text":"
inline virtual DepthImage robot_dart::gui::Base::depth_array () 
"},{"location":"api/classrobot__dart_1_1gui_1_1Base/#function-depth_image","title":"function depth_image","text":"
inline virtual GrayscaleImage robot_dart::gui::Base::depth_image () 
"},{"location":"api/classrobot__dart_1_1gui_1_1Base/#function-done","title":"function done","text":"
inline virtual bool robot_dart::gui::Base::done () const\n
"},{"location":"api/classrobot__dart_1_1gui_1_1Base/#function-height","title":"function height","text":"
inline virtual size_t robot_dart::gui::Base::height () const\n
"},{"location":"api/classrobot__dart_1_1gui_1_1Base/#function-image","title":"function image","text":"
inline virtual Image robot_dart::gui::Base::image () 
"},{"location":"api/classrobot__dart_1_1gui_1_1Base/#function-raw_depth_image","title":"function raw_depth_image","text":"
inline virtual GrayscaleImage robot_dart::gui::Base::raw_depth_image () 
"},{"location":"api/classrobot__dart_1_1gui_1_1Base/#function-refresh","title":"function refresh","text":"
inline virtual void robot_dart::gui::Base::refresh () 
"},{"location":"api/classrobot__dart_1_1gui_1_1Base/#function-set_enable","title":"function set_enable","text":"
inline virtual void robot_dart::gui::Base::set_enable (\nbool\n) 
"},{"location":"api/classrobot__dart_1_1gui_1_1Base/#function-set_fps","title":"function set_fps","text":"
inline virtual void robot_dart::gui::Base::set_fps (\nint\n) 
"},{"location":"api/classrobot__dart_1_1gui_1_1Base/#function-set_render_period","title":"function set_render_period","text":"
inline virtual void robot_dart::gui::Base::set_render_period (\ndouble\n) 
"},{"location":"api/classrobot__dart_1_1gui_1_1Base/#function-set_simu","title":"function set_simu","text":"
inline virtual void robot_dart::gui::Base::set_simu (\nRobotDARTSimu * simu\n) 
"},{"location":"api/classrobot__dart_1_1gui_1_1Base/#function-simu","title":"function simu","text":"
inline const RobotDARTSimu * robot_dart::gui::Base::simu () const\n
"},{"location":"api/classrobot__dart_1_1gui_1_1Base/#function-width","title":"function width","text":"
inline virtual size_t robot_dart::gui::Base::width () const\n
"},{"location":"api/classrobot__dart_1_1gui_1_1Base/#function-base_1","title":"function ~Base","text":"
inline virtual robot_dart::gui::Base::~Base () 
"},{"location":"api/classrobot__dart_1_1gui_1_1Base/#protected-attributes-documentation","title":"Protected Attributes Documentation","text":""},{"location":"api/classrobot__dart_1_1gui_1_1Base/#variable-_simu","title":"variable _simu","text":"
RobotDARTSimu* robot_dart::gui::Base::_simu;\n

The documentation for this class was generated from the following file robot_dart/gui/base.hpp

"},{"location":"api/structrobot__dart_1_1gui_1_1DepthImage/","title":"Struct robot_dart::gui::DepthImage","text":"

ClassList > robot_dart > gui > DepthImage

"},{"location":"api/structrobot__dart_1_1gui_1_1DepthImage/#public-attributes","title":"Public Attributes","text":"Type Name std::vector< double > data size_t height = = 0 size_t width = = 0"},{"location":"api/structrobot__dart_1_1gui_1_1DepthImage/#public-attributes-documentation","title":"Public Attributes Documentation","text":""},{"location":"api/structrobot__dart_1_1gui_1_1DepthImage/#variable-data","title":"variable data","text":"
std::vector<double> robot_dart::gui::DepthImage::data;\n
"},{"location":"api/structrobot__dart_1_1gui_1_1DepthImage/#variable-height","title":"variable height","text":"
size_t robot_dart::gui::DepthImage::height;\n
"},{"location":"api/structrobot__dart_1_1gui_1_1DepthImage/#variable-width","title":"variable width","text":"
size_t robot_dart::gui::DepthImage::width;\n

The documentation for this class was generated from the following file robot_dart/gui/helper.hpp

"},{"location":"api/structrobot__dart_1_1gui_1_1GrayscaleImage/","title":"Struct robot_dart::gui::GrayscaleImage","text":"

ClassList > robot_dart > gui > GrayscaleImage

"},{"location":"api/structrobot__dart_1_1gui_1_1GrayscaleImage/#public-attributes","title":"Public Attributes","text":"Type Name std::vector< uint8_t > data size_t height = = 0 size_t width = = 0"},{"location":"api/structrobot__dart_1_1gui_1_1GrayscaleImage/#public-attributes-documentation","title":"Public Attributes Documentation","text":""},{"location":"api/structrobot__dart_1_1gui_1_1GrayscaleImage/#variable-data","title":"variable data","text":"
std::vector<uint8_t> robot_dart::gui::GrayscaleImage::data;\n
"},{"location":"api/structrobot__dart_1_1gui_1_1GrayscaleImage/#variable-height","title":"variable height","text":"
size_t robot_dart::gui::GrayscaleImage::height;\n
"},{"location":"api/structrobot__dart_1_1gui_1_1GrayscaleImage/#variable-width","title":"variable width","text":"
size_t robot_dart::gui::GrayscaleImage::width;\n

The documentation for this class was generated from the following file robot_dart/gui/helper.hpp

"},{"location":"api/structrobot__dart_1_1gui_1_1Image/","title":"Struct robot_dart::gui::Image","text":"

ClassList > robot_dart > gui > Image

"},{"location":"api/structrobot__dart_1_1gui_1_1Image/#public-attributes","title":"Public Attributes","text":"Type Name size_t channels = = 3 std::vector< uint8_t > data size_t height = = 0 size_t width = = 0"},{"location":"api/structrobot__dart_1_1gui_1_1Image/#public-attributes-documentation","title":"Public Attributes Documentation","text":""},{"location":"api/structrobot__dart_1_1gui_1_1Image/#variable-channels","title":"variable channels","text":"
size_t robot_dart::gui::Image::channels;\n
"},{"location":"api/structrobot__dart_1_1gui_1_1Image/#variable-data","title":"variable data","text":"
std::vector<uint8_t> robot_dart::gui::Image::data;\n
"},{"location":"api/structrobot__dart_1_1gui_1_1Image/#variable-height","title":"variable height","text":"
size_t robot_dart::gui::Image::height;\n
"},{"location":"api/structrobot__dart_1_1gui_1_1Image/#variable-width","title":"variable width","text":"
size_t robot_dart::gui::Image::width;\n

The documentation for this class was generated from the following file robot_dart/gui/helper.hpp

"},{"location":"api/namespacerobot__dart_1_1gui_1_1magnum/","title":"Namespace robot_dart::gui::magnum","text":"

Namespace List > robot_dart > gui > magnum

"},{"location":"api/namespacerobot__dart_1_1gui_1_1magnum/#namespaces","title":"Namespaces","text":"Type Name namespace gs namespace sensor"},{"location":"api/namespacerobot__dart_1_1gui_1_1magnum/#classes","title":"Classes","text":"Type Name class BaseApplication class BaseGraphics <typename T> class CubeMapShadowedColorObject class CubeMapShadowedObject struct DebugDrawData class DrawableObject class GlfwApplication struct GlobalData class Graphics struct GraphicsConfiguration struct ObjectStruct struct ShadowData class ShadowedColorObject class ShadowedObject class WindowlessGLApplication class WindowlessGraphics"},{"location":"api/namespacerobot__dart_1_1gui_1_1magnum/#public-types","title":"Public Types","text":"Type Name typedef Magnum::SceneGraph::Camera3D Camera3D typedef Magnum::SceneGraph::Object< Magnum::SceneGraph::MatrixTransformation3D > Object3D typedef Magnum::SceneGraph::Scene< Magnum::SceneGraph::MatrixTransformation3D > Scene3D"},{"location":"api/namespacerobot__dart_1_1gui_1_1magnum/#public-functions","title":"Public Functions","text":"Type Name BaseApplication * make_application (RobotDARTSimu * simu, const GraphicsConfiguration & configuration=GraphicsConfiguration())"},{"location":"api/namespacerobot__dart_1_1gui_1_1magnum/#public-types-documentation","title":"Public Types Documentation","text":""},{"location":"api/namespacerobot__dart_1_1gui_1_1magnum/#typedef-camera3d","title":"typedef Camera3D","text":"
using robot_dart::gui::magnum::Camera3D = typedef Magnum::SceneGraph::Camera3D;\n
"},{"location":"api/namespacerobot__dart_1_1gui_1_1magnum/#typedef-object3d","title":"typedef Object3D","text":"
using robot_dart::gui::magnum::Object3D = typedef Magnum::SceneGraph::Object<Magnum::SceneGraph::MatrixTransformation3D>;\n
"},{"location":"api/namespacerobot__dart_1_1gui_1_1magnum/#typedef-scene3d","title":"typedef Scene3D","text":"
using robot_dart::gui::magnum::Scene3D = typedef Magnum::SceneGraph::Scene<Magnum::SceneGraph::MatrixTransformation3D>;\n
"},{"location":"api/namespacerobot__dart_1_1gui_1_1magnum/#public-functions-documentation","title":"Public Functions Documentation","text":""},{"location":"api/namespacerobot__dart_1_1gui_1_1magnum/#function-make_application","title":"function make_application","text":"
template<typename T typename T>\ninline BaseApplication * robot_dart::gui::magnum::make_application (\nRobotDARTSimu * simu,\nconst GraphicsConfiguration & configuration=GraphicsConfiguration ()\n) 

The documentation for this class was generated from the following file robot_dart/gui/magnum/base_application.cpp

"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1BaseApplication/","title":"Class robot_dart::gui::magnum::BaseApplication","text":"

ClassList > robot_dart > gui > magnum > BaseApplication

Inherited by the following classes: robot_dart::gui::magnum::GlfwApplication, robot_dart::gui::magnum::WindowlessGLApplication

"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1BaseApplication/#public-functions","title":"Public Functions","text":"Type Name BaseApplication (const GraphicsConfiguration & configuration=GraphicsConfiguration()) void add_light (const gs::Light & light) bool attach_camera (gs::Camera & camera, dart::dynamics::BodyNode * body) gs::Camera & camera () const gs::Camera & camera () const void clear_lights () DebugDrawData debug_draw_data () DepthImage depth_array () GrayscaleImage depth_image () bool done () const Magnum::SceneGraph::DrawableGroup3D & drawables () void enable_shadows (bool enable=true, bool drawTransparentShadows=false) Corrade::Containers::Optional< Magnum::Image2D > & image () void init (RobotDARTSimu * simu, const GraphicsConfiguration & configuration) gs::Light & light (size_t i) std::vector< gs::Light > & lights () void look_at (const Eigen::Vector3d & camera_pos, const Eigen::Vector3d & look_at, const Eigen::Vector3d & up) size_t num_lights () const GrayscaleImage raw_depth_image () void record_video (const std::string & video_fname, int fps) virtual void render () void render_shadows () Scene3D & scene () bool shadowed () const bool transparent_shadows () const void update_graphics () void update_lights (const gs::Camera & camera) virtual ~BaseApplication ()"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1BaseApplication/#protected-attributes","title":"Protected Attributes","text":"Type Name std::unique_ptr< Magnum::GL::Mesh > _3D_axis_mesh std::unique_ptr< Magnum::Shaders::VertexColorGL3D > _3D_axis_shader std::unique_ptr< Magnum::GL::Mesh > _background_mesh std::unique_ptr< Magnum::Shaders::FlatGL2D > _background_shader std::unique_ptr< gs::Camera > _camera std::unique_ptr< gs::PhongMultiLight > _color_shader GraphicsConfiguration _configuration Magnum::SceneGraph::DrawableGroup3D _cubemap_color_drawables std::unique_ptr< gs::CubeMapColor > _cubemap_color_shader Magnum::SceneGraph::DrawableGroup3D _cubemap_drawables std::unique_ptr< gs::CubeMap > _cubemap_shader std::unique_ptr< gs::CubeMapColor > _cubemap_texture_color_shader std::unique_ptr< gs::CubeMap > _cubemap_texture_shader std::unique_ptr< Magnum::DartIntegration::World > _dart_world bool _done = = false std::unordered_map< Magnum::DartIntegration::Object *, ObjectStruct * > _drawable_objects Magnum::SceneGraph::DrawableGroup3D _drawables Corrade::Containers::Pointer< Magnum::Text::AbstractFont > _font Corrade::PluginManager::Manager< Magnum::Text::AbstractFont > _font_manager Corrade::Containers::Pointer< Magnum::Text::DistanceFieldGlyphCache > _glyph_cache Corrade::PluginManager::Manager< Magnum::Trade::AbstractImporter > _importer_manager std::vector< gs::Light > _lights int _max_lights = = 5 Scene3D _scene std::unique_ptr< Camera3D > _shadow_camera Object3D * _shadow_camera_object std::unique_ptr< Magnum::GL::CubeMapTextureArray > _shadow_color_cube_map std::unique_ptr< gs::ShadowMapColor > _shadow_color_shader std::unique_ptr< Magnum::GL::Texture2DArray > _shadow_color_texture std::unique_ptr< Magnum::GL::CubeMapTextureArray > _shadow_cube_map std::vector< ShadowData > _shadow_data int _shadow_map_size = = 512 std::unique_ptr< gs::ShadowMap > _shadow_shader std::unique_ptr< Magnum::GL::Texture2DArray > _shadow_texture std::unique_ptr< gs::ShadowMapColor > _shadow_texture_color_shader std::unique_ptr< gs::ShadowMap > _shadow_texture_shader bool _shadowed = = true Magnum::SceneGraph::DrawableGroup3D _shadowed_color_drawables Magnum::SceneGraph::DrawableGroup3D _shadowed_drawables RobotDARTSimu * _simu Corrade::Containers::Pointer< Magnum::GL::Buffer > _text_indices std::unique_ptr< Magnum::Shaders::DistanceFieldVectorGL2D > _text_shader Corrade::Containers::Pointer< Magnum::GL::Buffer > _text_vertices std::unique_ptr< gs::PhongMultiLight > _texture_shader int _transparentSize = = 0 bool _transparent_shadows = = false"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1BaseApplication/#protected-functions","title":"Protected Functions","text":"Type Name void _gl_clean_up () void _prepare_shadows ()"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1BaseApplication/#public-functions-documentation","title":"Public Functions Documentation","text":""},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1BaseApplication/#function-baseapplication","title":"function BaseApplication","text":"
robot_dart::gui::magnum::BaseApplication::BaseApplication (\nconst GraphicsConfiguration & configuration=GraphicsConfiguration ()\n) 
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1BaseApplication/#function-add_light","title":"function add_light","text":"
void robot_dart::gui::magnum::BaseApplication::add_light (\nconst gs::Light & light\n) 
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1BaseApplication/#function-attach_camera","title":"function attach_camera","text":"
bool robot_dart::gui::magnum::BaseApplication::attach_camera (\ngs::Camera & camera,\ndart::dynamics::BodyNode * body\n) 
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1BaseApplication/#function-camera-12","title":"function camera [\u00bd]","text":"
inline gs::Camera & robot_dart::gui::magnum::BaseApplication::camera () 
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1BaseApplication/#function-camera-22","title":"function camera [2/2]","text":"
inline const gs::Camera & robot_dart::gui::magnum::BaseApplication::camera () const\n
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1BaseApplication/#function-clear_lights","title":"function clear_lights","text":"
void robot_dart::gui::magnum::BaseApplication::clear_lights () 
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1BaseApplication/#function-debug_draw_data","title":"function debug_draw_data","text":"
inline DebugDrawData robot_dart::gui::magnum::BaseApplication::debug_draw_data () 
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1BaseApplication/#function-depth_array","title":"function depth_array","text":"
DepthImage robot_dart::gui::magnum::BaseApplication::depth_array () 
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1BaseApplication/#function-depth_image","title":"function depth_image","text":"
GrayscaleImage robot_dart::gui::magnum::BaseApplication::depth_image () 
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1BaseApplication/#function-done","title":"function done","text":"
bool robot_dart::gui::magnum::BaseApplication::done () const\n
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1BaseApplication/#function-drawables","title":"function drawables","text":"
inline Magnum::SceneGraph::DrawableGroup3D & robot_dart::gui::magnum::BaseApplication::drawables () 
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1BaseApplication/#function-enable_shadows","title":"function enable_shadows","text":"
void robot_dart::gui::magnum::BaseApplication::enable_shadows (\nbool enable=true,\nbool drawTransparentShadows=false\n) 
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1BaseApplication/#function-image","title":"function image","text":"
inline Corrade::Containers::Optional< Magnum::Image2D > & robot_dart::gui::magnum::BaseApplication::image () 
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1BaseApplication/#function-init","title":"function init","text":"
void robot_dart::gui::magnum::BaseApplication::init (\nRobotDARTSimu * simu,\nconst GraphicsConfiguration & configuration\n) 
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1BaseApplication/#function-light","title":"function light","text":"
gs::Light & robot_dart::gui::magnum::BaseApplication::light (\nsize_t i\n) 
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1BaseApplication/#function-lights","title":"function lights","text":"
std::vector< gs::Light > & robot_dart::gui::magnum::BaseApplication::lights () 
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1BaseApplication/#function-look_at","title":"function look_at","text":"
void robot_dart::gui::magnum::BaseApplication::look_at (\nconst Eigen::Vector3d & camera_pos,\nconst Eigen::Vector3d & look_at,\nconst Eigen::Vector3d & up\n) 
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1BaseApplication/#function-num_lights","title":"function num_lights","text":"
size_t robot_dart::gui::magnum::BaseApplication::num_lights () const\n
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1BaseApplication/#function-raw_depth_image","title":"function raw_depth_image","text":"
GrayscaleImage robot_dart::gui::magnum::BaseApplication::raw_depth_image () 
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1BaseApplication/#function-record_video","title":"function record_video","text":"
inline void robot_dart::gui::magnum::BaseApplication::record_video (\nconst std::string & video_fname,\nint fps\n) 
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1BaseApplication/#function-render","title":"function render","text":"
inline virtual void robot_dart::gui::magnum::BaseApplication::render () 
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1BaseApplication/#function-render_shadows","title":"function render_shadows","text":"
void robot_dart::gui::magnum::BaseApplication::render_shadows () 
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1BaseApplication/#function-scene","title":"function scene","text":"
inline Scene3D & robot_dart::gui::magnum::BaseApplication::scene () 
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1BaseApplication/#function-shadowed","title":"function shadowed","text":"
inline bool robot_dart::gui::magnum::BaseApplication::shadowed () const\n
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1BaseApplication/#function-transparent_shadows","title":"function transparent_shadows","text":"
inline bool robot_dart::gui::magnum::BaseApplication::transparent_shadows () const\n
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1BaseApplication/#function-update_graphics","title":"function update_graphics","text":"
void robot_dart::gui::magnum::BaseApplication::update_graphics () 
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1BaseApplication/#function-update_lights","title":"function update_lights","text":"
void robot_dart::gui::magnum::BaseApplication::update_lights (\nconst gs::Camera & camera\n) 
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1BaseApplication/#function-baseapplication_1","title":"function ~BaseApplication","text":"
inline virtual robot_dart::gui::magnum::BaseApplication::~BaseApplication () 
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1BaseApplication/#protected-attributes-documentation","title":"Protected Attributes Documentation","text":""},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1BaseApplication/#variable-_3d_axis_mesh","title":"variable _3D_axis_mesh","text":"
std::unique_ptr<Magnum::GL::Mesh> robot_dart::gui::magnum::BaseApplication::_3D_axis_mesh;\n
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1BaseApplication/#variable-_3d_axis_shader","title":"variable _3D_axis_shader","text":"
std::unique_ptr<Magnum::Shaders::VertexColorGL3D> robot_dart::gui::magnum::BaseApplication::_3D_axis_shader;\n
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1BaseApplication/#variable-_background_mesh","title":"variable _background_mesh","text":"
std::unique_ptr<Magnum::GL::Mesh> robot_dart::gui::magnum::BaseApplication::_background_mesh;\n
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1BaseApplication/#variable-_background_shader","title":"variable _background_shader","text":"
std::unique_ptr<Magnum::Shaders::FlatGL2D> robot_dart::gui::magnum::BaseApplication::_background_shader;\n
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1BaseApplication/#variable-_camera","title":"variable _camera","text":"
std::unique_ptr<gs::Camera> robot_dart::gui::magnum::BaseApplication::_camera;\n
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1BaseApplication/#variable-_color_shader","title":"variable _color_shader","text":"
std::unique_ptr<gs::PhongMultiLight> robot_dart::gui::magnum::BaseApplication::_color_shader;\n
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1BaseApplication/#variable-_configuration","title":"variable _configuration","text":"
GraphicsConfiguration robot_dart::gui::magnum::BaseApplication::_configuration;\n
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1BaseApplication/#variable-_cubemap_color_drawables","title":"variable _cubemap_color_drawables","text":"
Magnum::SceneGraph::DrawableGroup3D robot_dart::gui::magnum::BaseApplication::_cubemap_color_drawables;\n
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1BaseApplication/#variable-_cubemap_color_shader","title":"variable _cubemap_color_shader","text":"
std::unique_ptr<gs::CubeMapColor> robot_dart::gui::magnum::BaseApplication::_cubemap_color_shader;\n
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1BaseApplication/#variable-_cubemap_drawables","title":"variable _cubemap_drawables","text":"
Magnum::SceneGraph::DrawableGroup3D robot_dart::gui::magnum::BaseApplication::_cubemap_drawables;\n
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1BaseApplication/#variable-_cubemap_shader","title":"variable _cubemap_shader","text":"
std::unique_ptr<gs::CubeMap> robot_dart::gui::magnum::BaseApplication::_cubemap_shader;\n
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1BaseApplication/#variable-_cubemap_texture_color_shader","title":"variable _cubemap_texture_color_shader","text":"
std::unique_ptr<gs::CubeMapColor> robot_dart::gui::magnum::BaseApplication::_cubemap_texture_color_shader;\n
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1BaseApplication/#variable-_cubemap_texture_shader","title":"variable _cubemap_texture_shader","text":"
std::unique_ptr<gs::CubeMap> robot_dart::gui::magnum::BaseApplication::_cubemap_texture_shader;\n
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1BaseApplication/#variable-_dart_world","title":"variable _dart_world","text":"
std::unique_ptr<Magnum::DartIntegration::World> robot_dart::gui::magnum::BaseApplication::_dart_world;\n
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1BaseApplication/#variable-_done","title":"variable _done","text":"
bool robot_dart::gui::magnum::BaseApplication::_done;\n
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1BaseApplication/#variable-_drawable_objects","title":"variable _drawable_objects","text":"
std::unordered_map<Magnum::DartIntegration::Object*, ObjectStruct*> robot_dart::gui::magnum::BaseApplication::_drawable_objects;\n
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1BaseApplication/#variable-_drawables","title":"variable _drawables","text":"
Magnum::SceneGraph::DrawableGroup3D robot_dart::gui::magnum::BaseApplication::_drawables;\n
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1BaseApplication/#variable-_font","title":"variable _font","text":"
Corrade::Containers::Pointer<Magnum::Text::AbstractFont> robot_dart::gui::magnum::BaseApplication::_font;\n
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1BaseApplication/#variable-_font_manager","title":"variable _font_manager","text":"
Corrade::PluginManager::Manager<Magnum::Text::AbstractFont> robot_dart::gui::magnum::BaseApplication::_font_manager;\n
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1BaseApplication/#variable-_glyph_cache","title":"variable _glyph_cache","text":"
Corrade::Containers::Pointer<Magnum::Text::DistanceFieldGlyphCache> robot_dart::gui::magnum::BaseApplication::_glyph_cache;\n
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1BaseApplication/#variable-_importer_manager","title":"variable _importer_manager","text":"
Corrade::PluginManager::Manager<Magnum::Trade::AbstractImporter> robot_dart::gui::magnum::BaseApplication::_importer_manager;\n
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1BaseApplication/#variable-_lights","title":"variable _lights","text":"
std::vector<gs::Light> robot_dart::gui::magnum::BaseApplication::_lights;\n
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1BaseApplication/#variable-_max_lights","title":"variable _max_lights","text":"
int robot_dart::gui::magnum::BaseApplication::_max_lights;\n
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1BaseApplication/#variable-_scene","title":"variable _scene","text":"
Scene3D robot_dart::gui::magnum::BaseApplication::_scene;\n
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1BaseApplication/#variable-_shadow_camera","title":"variable _shadow_camera","text":"
std::unique_ptr<Camera3D> robot_dart::gui::magnum::BaseApplication::_shadow_camera;\n
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1BaseApplication/#variable-_shadow_camera_object","title":"variable _shadow_camera_object","text":"
Object3D* robot_dart::gui::magnum::BaseApplication::_shadow_camera_object;\n
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1BaseApplication/#variable-_shadow_color_cube_map","title":"variable _shadow_color_cube_map","text":"
std::unique_ptr<Magnum::GL::CubeMapTextureArray> robot_dart::gui::magnum::BaseApplication::_shadow_color_cube_map;\n
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1BaseApplication/#variable-_shadow_color_shader","title":"variable _shadow_color_shader","text":"
std::unique_ptr<gs::ShadowMapColor> robot_dart::gui::magnum::BaseApplication::_shadow_color_shader;\n
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1BaseApplication/#variable-_shadow_color_texture","title":"variable _shadow_color_texture","text":"
std::unique_ptr<Magnum::GL::Texture2DArray> robot_dart::gui::magnum::BaseApplication::_shadow_color_texture;\n
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1BaseApplication/#variable-_shadow_cube_map","title":"variable _shadow_cube_map","text":"
std::unique_ptr<Magnum::GL::CubeMapTextureArray> robot_dart::gui::magnum::BaseApplication::_shadow_cube_map;\n
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1BaseApplication/#variable-_shadow_data","title":"variable _shadow_data","text":"
std::vector<ShadowData> robot_dart::gui::magnum::BaseApplication::_shadow_data;\n
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1BaseApplication/#variable-_shadow_map_size","title":"variable _shadow_map_size","text":"
int robot_dart::gui::magnum::BaseApplication::_shadow_map_size;\n
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1BaseApplication/#variable-_shadow_shader","title":"variable _shadow_shader","text":"
std::unique_ptr<gs::ShadowMap> robot_dart::gui::magnum::BaseApplication::_shadow_shader;\n
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1BaseApplication/#variable-_shadow_texture","title":"variable _shadow_texture","text":"
std::unique_ptr<Magnum::GL::Texture2DArray> robot_dart::gui::magnum::BaseApplication::_shadow_texture;\n
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1BaseApplication/#variable-_shadow_texture_color_shader","title":"variable _shadow_texture_color_shader","text":"
std::unique_ptr<gs::ShadowMapColor> robot_dart::gui::magnum::BaseApplication::_shadow_texture_color_shader;\n
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1BaseApplication/#variable-_shadow_texture_shader","title":"variable _shadow_texture_shader","text":"
std::unique_ptr<gs::ShadowMap> robot_dart::gui::magnum::BaseApplication::_shadow_texture_shader;\n
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1BaseApplication/#variable-_shadowed","title":"variable _shadowed","text":"
bool robot_dart::gui::magnum::BaseApplication::_shadowed;\n
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1BaseApplication/#variable-_shadowed_color_drawables","title":"variable _shadowed_color_drawables","text":"
Magnum::SceneGraph::DrawableGroup3D robot_dart::gui::magnum::BaseApplication::_shadowed_color_drawables;\n
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1BaseApplication/#variable-_shadowed_drawables","title":"variable _shadowed_drawables","text":"
Magnum::SceneGraph::DrawableGroup3D robot_dart::gui::magnum::BaseApplication::_shadowed_drawables;\n
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1BaseApplication/#variable-_simu","title":"variable _simu","text":"
RobotDARTSimu* robot_dart::gui::magnum::BaseApplication::_simu;\n
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1BaseApplication/#variable-_text_indices","title":"variable _text_indices","text":"
Corrade::Containers::Pointer<Magnum::GL::Buffer> robot_dart::gui::magnum::BaseApplication::_text_indices;\n
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1BaseApplication/#variable-_text_shader","title":"variable _text_shader","text":"
std::unique_ptr<Magnum::Shaders::DistanceFieldVectorGL2D> robot_dart::gui::magnum::BaseApplication::_text_shader;\n
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1BaseApplication/#variable-_text_vertices","title":"variable _text_vertices","text":"
Corrade::Containers::Pointer<Magnum::GL::Buffer> robot_dart::gui::magnum::BaseApplication::_text_vertices;\n
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1BaseApplication/#variable-_texture_shader","title":"variable _texture_shader","text":"
std::unique_ptr<gs::PhongMultiLight> robot_dart::gui::magnum::BaseApplication::_texture_shader;\n
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1BaseApplication/#variable-_transparentsize","title":"variable _transparentSize","text":"
int robot_dart::gui::magnum::BaseApplication::_transparentSize;\n
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1BaseApplication/#variable-_transparent_shadows","title":"variable _transparent_shadows","text":"
bool robot_dart::gui::magnum::BaseApplication::_transparent_shadows;\n
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1BaseApplication/#protected-functions-documentation","title":"Protected Functions Documentation","text":""},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1BaseApplication/#function-_gl_clean_up","title":"function _gl_clean_up","text":"
void robot_dart::gui::magnum::BaseApplication::_gl_clean_up () 
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1BaseApplication/#function-_prepare_shadows","title":"function _prepare_shadows","text":"
void robot_dart::gui::magnum::BaseApplication::_prepare_shadows () 

The documentation for this class was generated from the following file robot_dart/gui/magnum/base_application.hpp

"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1BaseGraphics/","title":"Class robot_dart::gui::magnum::BaseGraphics","text":"

template <typename T typename T>

ClassList > robot_dart > gui > magnum > BaseGraphics

Inherits the following classes: robot_dart::gui::Base

"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1BaseGraphics/#public-functions","title":"Public Functions","text":"Type Name BaseGraphics (const GraphicsConfiguration & configuration=GraphicsConfiguration()) void add_light (const magnum::Light & light) gs::Camera & camera () const gs::Camera & camera () const Eigen::Matrix4d camera_extrinsic_matrix () const Eigen::Matrix3d camera_intrinsic_matrix () const void clear_lights () virtual DepthImage depth_array () override virtual GrayscaleImage depth_image () override virtual bool done () override const void enable_shadows (bool enable=true, bool transparent=true) virtual size_t height () override const virtual Image image () override magnum::Light & light (size_t i) std::vector< gs::Light > & lights () void look_at (const Eigen::Vector3d & camera_pos, const Eigen::Vector3d & look_at=Eigen::Vector3d(0, 0, 0), const Eigen::Vector3d & up=Eigen::Vector3d(0, 0, 1)) BaseApplication * magnum_app () const BaseApplication * magnum_app () const Magnum::Image2D * magnum_image () size_t num_lights () const virtual GrayscaleImage raw_depth_image () override void record_video (const std::string & video_fname, int fps=-1) virtual void refresh () override virtual void set_enable (bool enable) override virtual void set_fps (int fps) override virtual void set_simu (RobotDARTSimu * simu) override bool shadowed () const bool transparent_shadows () const virtual size_t width () override const virtual ~BaseGraphics ()"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1BaseGraphics/#public-functions-inherited-from-robot_dartguibase","title":"Public Functions inherited from robot_dart::gui::Base","text":"

See robot_dart::gui::Base

Type Name Base () virtual DepthImage depth_array () virtual GrayscaleImage depth_image () virtual bool done () const virtual size_t height () const virtual Image image () virtual GrayscaleImage raw_depth_image () virtual void refresh () virtual void set_enable (bool) virtual void set_fps (int) virtual void set_render_period (double) virtual void set_simu (RobotDARTSimu * simu) const RobotDARTSimu * simu () const virtual size_t width () const virtual ~Base ()"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1BaseGraphics/#protected-attributes","title":"Protected Attributes","text":"Type Name GraphicsConfiguration _configuration bool _enabled int _fps std::unique_ptr< BaseApplication > _magnum_app Corrade::Utility::Debug _magnum_silence_output = {nullptr}"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1BaseGraphics/#protected-attributes-inherited-from-robot_dartguibase","title":"Protected Attributes inherited from robot_dart::gui::Base","text":"

See robot_dart::gui::Base

Type Name RobotDARTSimu * _simu = = nullptr"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1BaseGraphics/#public-functions-documentation","title":"Public Functions Documentation","text":""},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1BaseGraphics/#function-basegraphics","title":"function BaseGraphics","text":"
inline robot_dart::gui::magnum::BaseGraphics::BaseGraphics (\nconst GraphicsConfiguration & configuration=GraphicsConfiguration ()\n) 
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1BaseGraphics/#function-add_light","title":"function add_light","text":"
inline void robot_dart::gui::magnum::BaseGraphics::add_light (\nconst magnum::gs::Light & light\n) 
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1BaseGraphics/#function-camera-12","title":"function camera [\u00bd]","text":"
inline gs::Camera & robot_dart::gui::magnum::BaseGraphics::camera () 
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1BaseGraphics/#function-camera-22","title":"function camera [2/2]","text":"
inline const gs::Camera & robot_dart::gui::magnum::BaseGraphics::camera () const\n
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1BaseGraphics/#function-camera_extrinsic_matrix","title":"function camera_extrinsic_matrix","text":"
inline Eigen::Matrix4d robot_dart::gui::magnum::BaseGraphics::camera_extrinsic_matrix () const\n
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1BaseGraphics/#function-camera_intrinsic_matrix","title":"function camera_intrinsic_matrix","text":"
inline Eigen::Matrix3d robot_dart::gui::magnum::BaseGraphics::camera_intrinsic_matrix () const\n
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1BaseGraphics/#function-clear_lights","title":"function clear_lights","text":"
inline void robot_dart::gui::magnum::BaseGraphics::clear_lights () 
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1BaseGraphics/#function-depth_array","title":"function depth_array","text":"
inline virtual DepthImage robot_dart::gui::magnum::BaseGraphics::depth_array () override\n

Implements robot_dart::gui::Base::depth_array

"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1BaseGraphics/#function-depth_image","title":"function depth_image","text":"
inline virtual GrayscaleImage robot_dart::gui::magnum::BaseGraphics::depth_image () override\n

Implements robot_dart::gui::Base::depth_image

"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1BaseGraphics/#function-done","title":"function done","text":"
inline virtual bool robot_dart::gui::magnum::BaseGraphics::done () override const\n

Implements robot_dart::gui::Base::done

"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1BaseGraphics/#function-enable_shadows","title":"function enable_shadows","text":"
inline void robot_dart::gui::magnum::BaseGraphics::enable_shadows (\nbool enable=true,\nbool transparent=true\n) 
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1BaseGraphics/#function-height","title":"function height","text":"
inline virtual size_t robot_dart::gui::magnum::BaseGraphics::height () override const\n

Implements robot_dart::gui::Base::height

"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1BaseGraphics/#function-image","title":"function image","text":"
inline virtual Image robot_dart::gui::magnum::BaseGraphics::image () override\n

Implements robot_dart::gui::Base::image

"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1BaseGraphics/#function-light","title":"function light","text":"
inline magnum::gs::Light & robot_dart::gui::magnum::BaseGraphics::light (\nsize_t i\n) 
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1BaseGraphics/#function-lights","title":"function lights","text":"
inline std::vector< gs::Light > & robot_dart::gui::magnum::BaseGraphics::lights () 
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1BaseGraphics/#function-look_at","title":"function look_at","text":"
inline void robot_dart::gui::magnum::BaseGraphics::look_at (\nconst Eigen::Vector3d & camera_pos,\nconst Eigen::Vector3d & look_at=Eigen::Vector3d(0, 0, 0),\nconst Eigen::Vector3d & up=Eigen::Vector3d(0, 0, 1)\n) 
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1BaseGraphics/#function-magnum_app-12","title":"function magnum_app [\u00bd]","text":"
inline BaseApplication * robot_dart::gui::magnum::BaseGraphics::magnum_app () 
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1BaseGraphics/#function-magnum_app-22","title":"function magnum_app [2/2]","text":"
inline const BaseApplication * robot_dart::gui::magnum::BaseGraphics::magnum_app () const\n
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1BaseGraphics/#function-magnum_image","title":"function magnum_image","text":"
inline Magnum::Image2D * robot_dart::gui::magnum::BaseGraphics::magnum_image () 
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1BaseGraphics/#function-num_lights","title":"function num_lights","text":"
inline size_t robot_dart::gui::magnum::BaseGraphics::num_lights () const\n
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1BaseGraphics/#function-raw_depth_image","title":"function raw_depth_image","text":"
inline virtual GrayscaleImage robot_dart::gui::magnum::BaseGraphics::raw_depth_image () override\n

Implements robot_dart::gui::Base::raw_depth_image

"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1BaseGraphics/#function-record_video","title":"function record_video","text":"
inline void robot_dart::gui::magnum::BaseGraphics::record_video (\nconst std::string & video_fname,\nint fps=-1\n) 
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1BaseGraphics/#function-refresh","title":"function refresh","text":"
inline virtual void robot_dart::gui::magnum::BaseGraphics::refresh () override\n

Implements robot_dart::gui::Base::refresh

"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1BaseGraphics/#function-set_enable","title":"function set_enable","text":"
inline virtual void robot_dart::gui::magnum::BaseGraphics::set_enable (\nbool enable\n) override\n

Implements robot_dart::gui::Base::set_enable

"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1BaseGraphics/#function-set_fps","title":"function set_fps","text":"
inline virtual void robot_dart::gui::magnum::BaseGraphics::set_fps (\nint fps\n) override\n

Implements robot_dart::gui::Base::set_fps

"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1BaseGraphics/#function-set_simu","title":"function set_simu","text":"
inline virtual void robot_dart::gui::magnum::BaseGraphics::set_simu (\nRobotDARTSimu * simu\n) override\n

Implements robot_dart::gui::Base::set_simu

"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1BaseGraphics/#function-shadowed","title":"function shadowed","text":"
inline bool robot_dart::gui::magnum::BaseGraphics::shadowed () const\n
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1BaseGraphics/#function-transparent_shadows","title":"function transparent_shadows","text":"
inline bool robot_dart::gui::magnum::BaseGraphics::transparent_shadows () const\n
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1BaseGraphics/#function-width","title":"function width","text":"
inline virtual size_t robot_dart::gui::magnum::BaseGraphics::width () override const\n

Implements robot_dart::gui::Base::width

"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1BaseGraphics/#function-basegraphics_1","title":"function ~BaseGraphics","text":"
inline virtual robot_dart::gui::magnum::BaseGraphics::~BaseGraphics () 
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1BaseGraphics/#protected-attributes-documentation","title":"Protected Attributes Documentation","text":""},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1BaseGraphics/#variable-_configuration","title":"variable _configuration","text":"
GraphicsConfiguration robot_dart::gui::magnum::BaseGraphics< T >::_configuration;\n
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1BaseGraphics/#variable-_enabled","title":"variable _enabled","text":"
bool robot_dart::gui::magnum::BaseGraphics< T >::_enabled;\n
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1BaseGraphics/#variable-_fps","title":"variable _fps","text":"
int robot_dart::gui::magnum::BaseGraphics< T >::_fps;\n
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1BaseGraphics/#variable-_magnum_app","title":"variable _magnum_app","text":"
std::unique_ptr<BaseApplication> robot_dart::gui::magnum::BaseGraphics< T >::_magnum_app;\n
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1BaseGraphics/#variable-_magnum_silence_output","title":"variable _magnum_silence_output","text":"
Corrade::Utility::Debug robot_dart::gui::magnum::BaseGraphics< T >::_magnum_silence_output;\n

The documentation for this class was generated from the following file robot_dart/gui/magnum/base_graphics.hpp

"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1CubeMapShadowedColorObject/","title":"Class robot_dart::gui::magnum::CubeMapShadowedColorObject","text":"

ClassList > robot_dart > gui > magnum > CubeMapShadowedColorObject

Inherits the following classes: Object3D, Magnum::SceneGraph::Drawable3D

"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1CubeMapShadowedColorObject/#public-functions","title":"Public Functions","text":"Type Name CubeMapShadowedColorObject (RobotDARTSimu * simu, dart::dynamics::ShapeNode * shape, const std::vector< std::reference_wrapper< Magnum::GL::Mesh > > & meshes, gs::CubeMapColor & shader, gs::CubeMapColor & texture_shader, Object3D * parent, Magnum::SceneGraph::DrawableGroup3D * group) CubeMapShadowedColorObject & set_materials (const std::vector< gs::Material > & materials) CubeMapShadowedColorObject & set_meshes (const std::vector< std::reference_wrapper< Magnum::GL::Mesh > > & meshes) CubeMapShadowedColorObject & set_scalings (const std::vector< Magnum::Vector3 > & scalings) dart::dynamics::ShapeNode * shape () const RobotDARTSimu * simu () const"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1CubeMapShadowedColorObject/#public-functions-documentation","title":"Public Functions Documentation","text":""},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1CubeMapShadowedColorObject/#function-cubemapshadowedcolorobject","title":"function CubeMapShadowedColorObject","text":"
explicit robot_dart::gui::magnum::CubeMapShadowedColorObject::CubeMapShadowedColorObject (\nRobotDARTSimu * simu,\ndart::dynamics::ShapeNode * shape,\nconst std::vector< std::reference_wrapper< Magnum::GL::Mesh > > & meshes,\ngs::CubeMapColor & shader,\ngs::CubeMapColor & texture_shader,\nObject3D * parent,\nMagnum::SceneGraph::DrawableGroup3D * group\n) 
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1CubeMapShadowedColorObject/#function-set_materials","title":"function set_materials","text":"
CubeMapShadowedColorObject & robot_dart::gui::magnum::CubeMapShadowedColorObject::set_materials (\nconst std::vector< gs::Material > & materials\n) 
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1CubeMapShadowedColorObject/#function-set_meshes","title":"function set_meshes","text":"
CubeMapShadowedColorObject & robot_dart::gui::magnum::CubeMapShadowedColorObject::set_meshes (\nconst std::vector< std::reference_wrapper< Magnum::GL::Mesh > > & meshes\n) 
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1CubeMapShadowedColorObject/#function-set_scalings","title":"function set_scalings","text":"
CubeMapShadowedColorObject & robot_dart::gui::magnum::CubeMapShadowedColorObject::set_scalings (\nconst std::vector< Magnum::Vector3 > & scalings\n) 
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1CubeMapShadowedColorObject/#function-shape","title":"function shape","text":"
inline dart::dynamics::ShapeNode * robot_dart::gui::magnum::CubeMapShadowedColorObject::shape () const\n
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1CubeMapShadowedColorObject/#function-simu","title":"function simu","text":"
inline RobotDARTSimu * robot_dart::gui::magnum::CubeMapShadowedColorObject::simu () const\n

The documentation for this class was generated from the following file robot_dart/gui/magnum/drawables.hpp

"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1CubeMapShadowedObject/","title":"Class robot_dart::gui::magnum::CubeMapShadowedObject","text":"

ClassList > robot_dart > gui > magnum > CubeMapShadowedObject

Inherits the following classes: Object3D, Magnum::SceneGraph::Drawable3D

"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1CubeMapShadowedObject/#public-functions","title":"Public Functions","text":"Type Name CubeMapShadowedObject (RobotDARTSimu * simu, dart::dynamics::ShapeNode * shape, const std::vector< std::reference_wrapper< Magnum::GL::Mesh > > & meshes, gs::CubeMap & shader, gs::CubeMap & texture_shader, Object3D * parent, Magnum::SceneGraph::DrawableGroup3D * group) CubeMapShadowedObject & set_materials (const std::vector< gs::Material > & materials) CubeMapShadowedObject & set_meshes (const std::vector< std::reference_wrapper< Magnum::GL::Mesh > > & meshes) CubeMapShadowedObject & set_scalings (const std::vector< Magnum::Vector3 > & scalings) dart::dynamics::ShapeNode * shape () const RobotDARTSimu * simu () const"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1CubeMapShadowedObject/#public-functions-documentation","title":"Public Functions Documentation","text":""},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1CubeMapShadowedObject/#function-cubemapshadowedobject","title":"function CubeMapShadowedObject","text":"
explicit robot_dart::gui::magnum::CubeMapShadowedObject::CubeMapShadowedObject (\nRobotDARTSimu * simu,\ndart::dynamics::ShapeNode * shape,\nconst std::vector< std::reference_wrapper< Magnum::GL::Mesh > > & meshes,\ngs::CubeMap & shader,\ngs::CubeMap & texture_shader,\nObject3D * parent,\nMagnum::SceneGraph::DrawableGroup3D * group\n) 
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1CubeMapShadowedObject/#function-set_materials","title":"function set_materials","text":"
CubeMapShadowedObject & robot_dart::gui::magnum::CubeMapShadowedObject::set_materials (\nconst std::vector< gs::Material > & materials\n) 
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1CubeMapShadowedObject/#function-set_meshes","title":"function set_meshes","text":"
CubeMapShadowedObject & robot_dart::gui::magnum::CubeMapShadowedObject::set_meshes (\nconst std::vector< std::reference_wrapper< Magnum::GL::Mesh > > & meshes\n) 
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1CubeMapShadowedObject/#function-set_scalings","title":"function set_scalings","text":"
CubeMapShadowedObject & robot_dart::gui::magnum::CubeMapShadowedObject::set_scalings (\nconst std::vector< Magnum::Vector3 > & scalings\n) 
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1CubeMapShadowedObject/#function-shape","title":"function shape","text":"
inline dart::dynamics::ShapeNode * robot_dart::gui::magnum::CubeMapShadowedObject::shape () const\n
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1CubeMapShadowedObject/#function-simu","title":"function simu","text":"
inline RobotDARTSimu * robot_dart::gui::magnum::CubeMapShadowedObject::simu () const\n

The documentation for this class was generated from the following file robot_dart/gui/magnum/drawables.hpp

"},{"location":"api/structrobot__dart_1_1gui_1_1magnum_1_1DebugDrawData/","title":"Struct robot_dart::gui::magnum::DebugDrawData","text":"

ClassList > robot_dart > gui > magnum > DebugDrawData

"},{"location":"api/structrobot__dart_1_1gui_1_1magnum_1_1DebugDrawData/#public-attributes","title":"Public Attributes","text":"Type Name Magnum::GL::Mesh * axes_mesh Magnum::Shaders::VertexColorGL3D * axes_shader Magnum::GL::Mesh * background_mesh Magnum::Shaders::FlatGL2D * background_shader Magnum::Text::DistanceFieldGlyphCache * cache Magnum::Text::AbstractFont * font Magnum::GL::Buffer * text_indices Magnum::Shaders::DistanceFieldVectorGL2D * text_shader Magnum::GL::Buffer * text_vertices"},{"location":"api/structrobot__dart_1_1gui_1_1magnum_1_1DebugDrawData/#public-attributes-documentation","title":"Public Attributes Documentation","text":""},{"location":"api/structrobot__dart_1_1gui_1_1magnum_1_1DebugDrawData/#variable-axes_mesh","title":"variable axes_mesh","text":"
Magnum::GL::Mesh* robot_dart::gui::magnum::DebugDrawData::axes_mesh;\n
"},{"location":"api/structrobot__dart_1_1gui_1_1magnum_1_1DebugDrawData/#variable-axes_shader","title":"variable axes_shader","text":"
Magnum::Shaders::VertexColorGL3D* robot_dart::gui::magnum::DebugDrawData::axes_shader;\n
"},{"location":"api/structrobot__dart_1_1gui_1_1magnum_1_1DebugDrawData/#variable-background_mesh","title":"variable background_mesh","text":"
Magnum::GL::Mesh* robot_dart::gui::magnum::DebugDrawData::background_mesh;\n
"},{"location":"api/structrobot__dart_1_1gui_1_1magnum_1_1DebugDrawData/#variable-background_shader","title":"variable background_shader","text":"
Magnum::Shaders::FlatGL2D* robot_dart::gui::magnum::DebugDrawData::background_shader;\n
"},{"location":"api/structrobot__dart_1_1gui_1_1magnum_1_1DebugDrawData/#variable-cache","title":"variable cache","text":"
Magnum::Text::DistanceFieldGlyphCache* robot_dart::gui::magnum::DebugDrawData::cache;\n
"},{"location":"api/structrobot__dart_1_1gui_1_1magnum_1_1DebugDrawData/#variable-font","title":"variable font","text":"
Magnum::Text::AbstractFont* robot_dart::gui::magnum::DebugDrawData::font;\n
"},{"location":"api/structrobot__dart_1_1gui_1_1magnum_1_1DebugDrawData/#variable-text_indices","title":"variable text_indices","text":"
Magnum::GL::Buffer* robot_dart::gui::magnum::DebugDrawData::text_indices;\n
"},{"location":"api/structrobot__dart_1_1gui_1_1magnum_1_1DebugDrawData/#variable-text_shader","title":"variable text_shader","text":"
Magnum::Shaders::DistanceFieldVectorGL2D* robot_dart::gui::magnum::DebugDrawData::text_shader;\n
"},{"location":"api/structrobot__dart_1_1gui_1_1magnum_1_1DebugDrawData/#variable-text_vertices","title":"variable text_vertices","text":"
Magnum::GL::Buffer* robot_dart::gui::magnum::DebugDrawData::text_vertices;\n

The documentation for this class was generated from the following file robot_dart/gui/magnum/base_application.hpp

"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1DrawableObject/","title":"Class robot_dart::gui::magnum::DrawableObject","text":"

ClassList > robot_dart > gui > magnum > DrawableObject

Inherits the following classes: Object3D, Magnum::SceneGraph::Drawable3D

"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1DrawableObject/#public-functions","title":"Public Functions","text":"Type Name DrawableObject (RobotDARTSimu * simu, dart::dynamics::ShapeNode * shape, const std::vector< std::reference_wrapper< Magnum::GL::Mesh > > & meshes, const std::vector< gs::Material > & materials, gs::PhongMultiLight & color, gs::PhongMultiLight & texture, Object3D * parent, Magnum::SceneGraph::DrawableGroup3D * group) const std::vector< gs::Material > & materials () const DrawableObject & set_color_shader (std::reference_wrapper< gs::PhongMultiLight > shader) DrawableObject & set_materials (const std::vector< gs::Material > & materials) DrawableObject & set_meshes (const std::vector< std::reference_wrapper< Magnum::GL::Mesh > > & meshes) DrawableObject & set_scalings (const std::vector< Magnum::Vector3 > & scalings) DrawableObject & set_soft_bodies (const std::vector< bool > & softBody) DrawableObject & set_texture_shader (std::reference_wrapper< gs::PhongMultiLight > shader) DrawableObject & set_transparent (bool transparent=true) dart::dynamics::ShapeNode * shape () const RobotDARTSimu * simu () const bool transparent () const"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1DrawableObject/#public-functions-documentation","title":"Public Functions Documentation","text":""},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1DrawableObject/#function-drawableobject","title":"function DrawableObject","text":"
explicit robot_dart::gui::magnum::DrawableObject::DrawableObject (\nRobotDARTSimu * simu,\ndart::dynamics::ShapeNode * shape,\nconst std::vector< std::reference_wrapper< Magnum::GL::Mesh > > & meshes,\nconst std::vector< gs::Material > & materials,\ngs::PhongMultiLight & color,\ngs::PhongMultiLight & texture,\nObject3D * parent,\nMagnum::SceneGraph::DrawableGroup3D * group\n) 
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1DrawableObject/#function-materials","title":"function materials","text":"
inline const std::vector< gs::Material > & robot_dart::gui::magnum::DrawableObject::materials () const\n
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1DrawableObject/#function-set_color_shader","title":"function set_color_shader","text":"
DrawableObject & robot_dart::gui::magnum::DrawableObject::set_color_shader (\nstd::reference_wrapper< gs::PhongMultiLight > shader\n) 
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1DrawableObject/#function-set_materials","title":"function set_materials","text":"
DrawableObject & robot_dart::gui::magnum::DrawableObject::set_materials (\nconst std::vector< gs::Material > & materials\n) 
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1DrawableObject/#function-set_meshes","title":"function set_meshes","text":"
DrawableObject & robot_dart::gui::magnum::DrawableObject::set_meshes (\nconst std::vector< std::reference_wrapper< Magnum::GL::Mesh > > & meshes\n) 
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1DrawableObject/#function-set_scalings","title":"function set_scalings","text":"
DrawableObject & robot_dart::gui::magnum::DrawableObject::set_scalings (\nconst std::vector< Magnum::Vector3 > & scalings\n) 
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1DrawableObject/#function-set_soft_bodies","title":"function set_soft_bodies","text":"
DrawableObject & robot_dart::gui::magnum::DrawableObject::set_soft_bodies (\nconst std::vector< bool > & softBody\n) 
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1DrawableObject/#function-set_texture_shader","title":"function set_texture_shader","text":"
DrawableObject & robot_dart::gui::magnum::DrawableObject::set_texture_shader (\nstd::reference_wrapper< gs::PhongMultiLight > shader\n) 
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1DrawableObject/#function-set_transparent","title":"function set_transparent","text":"
DrawableObject & robot_dart::gui::magnum::DrawableObject::set_transparent (\nbool transparent=true\n) 
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1DrawableObject/#function-shape","title":"function shape","text":"
inline dart::dynamics::ShapeNode * robot_dart::gui::magnum::DrawableObject::shape () const\n
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1DrawableObject/#function-simu","title":"function simu","text":"
inline RobotDARTSimu * robot_dart::gui::magnum::DrawableObject::simu () const\n
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1DrawableObject/#function-transparent","title":"function transparent","text":"
inline bool robot_dart::gui::magnum::DrawableObject::transparent () const\n

The documentation for this class was generated from the following file robot_dart/gui/magnum/drawables.hpp

"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1GlfwApplication/","title":"Class robot_dart::gui::magnum::GlfwApplication","text":"

ClassList > robot_dart > gui > magnum > GlfwApplication

Inherits the following classes: robot_dart::gui::magnum::BaseApplication, Magnum::Platform::Application

"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1GlfwApplication/#public-functions","title":"Public Functions","text":"Type Name GlfwApplication (int argc, char ** argv, RobotDARTSimu * simu, const GraphicsConfiguration & configuration=GraphicsConfiguration()) virtual void render () override ~GlfwApplication ()"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1GlfwApplication/#public-functions-inherited-from-robot_dartguimagnumbaseapplication","title":"Public Functions inherited from robot_dart::gui::magnum::BaseApplication","text":"

See robot_dart::gui::magnum::BaseApplication

Type Name BaseApplication (const GraphicsConfiguration & configuration=GraphicsConfiguration()) void add_light (const gs::Light & light) bool attach_camera (gs::Camera & camera, dart::dynamics::BodyNode * body) gs::Camera & camera () const gs::Camera & camera () const void clear_lights () DebugDrawData debug_draw_data () DepthImage depth_array () GrayscaleImage depth_image () bool done () const Magnum::SceneGraph::DrawableGroup3D & drawables () void enable_shadows (bool enable=true, bool drawTransparentShadows=false) Corrade::Containers::Optional< Magnum::Image2D > & image () void init (RobotDARTSimu * simu, const GraphicsConfiguration & configuration) gs::Light & light (size_t i) std::vector< gs::Light > & lights () void look_at (const Eigen::Vector3d & camera_pos, const Eigen::Vector3d & look_at, const Eigen::Vector3d & up) size_t num_lights () const GrayscaleImage raw_depth_image () void record_video (const std::string & video_fname, int fps) virtual void render () void render_shadows () Scene3D & scene () bool shadowed () const bool transparent_shadows () const void update_graphics () void update_lights (const gs::Camera & camera) virtual ~BaseApplication ()"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1GlfwApplication/#protected-attributes","title":"Protected Attributes","text":"Type Name Magnum::Color4 _bg_color bool _draw_debug bool _draw_main_camera RobotDARTSimu * _simu Magnum::Float _speed_move Magnum::Float _speed_strafe"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1GlfwApplication/#protected-attributes-inherited-from-robot_dartguimagnumbaseapplication","title":"Protected Attributes inherited from robot_dart::gui::magnum::BaseApplication","text":"

See robot_dart::gui::magnum::BaseApplication

Type Name std::unique_ptr< Magnum::GL::Mesh > _3D_axis_mesh std::unique_ptr< Magnum::Shaders::VertexColorGL3D > _3D_axis_shader std::unique_ptr< Magnum::GL::Mesh > _background_mesh std::unique_ptr< Magnum::Shaders::FlatGL2D > _background_shader std::unique_ptr< gs::Camera > _camera std::unique_ptr< gs::PhongMultiLight > _color_shader GraphicsConfiguration _configuration Magnum::SceneGraph::DrawableGroup3D _cubemap_color_drawables std::unique_ptr< gs::CubeMapColor > _cubemap_color_shader Magnum::SceneGraph::DrawableGroup3D _cubemap_drawables std::unique_ptr< gs::CubeMap > _cubemap_shader std::unique_ptr< gs::CubeMapColor > _cubemap_texture_color_shader std::unique_ptr< gs::CubeMap > _cubemap_texture_shader std::unique_ptr< Magnum::DartIntegration::World > _dart_world bool _done = = false std::unordered_map< Magnum::DartIntegration::Object *, ObjectStruct * > _drawable_objects Magnum::SceneGraph::DrawableGroup3D _drawables Corrade::Containers::Pointer< Magnum::Text::AbstractFont > _font Corrade::PluginManager::Manager< Magnum::Text::AbstractFont > _font_manager Corrade::Containers::Pointer< Magnum::Text::DistanceFieldGlyphCache > _glyph_cache Corrade::PluginManager::Manager< Magnum::Trade::AbstractImporter > _importer_manager std::vector< gs::Light > _lights int _max_lights = = 5 Scene3D _scene std::unique_ptr< Camera3D > _shadow_camera Object3D * _shadow_camera_object std::unique_ptr< Magnum::GL::CubeMapTextureArray > _shadow_color_cube_map std::unique_ptr< gs::ShadowMapColor > _shadow_color_shader std::unique_ptr< Magnum::GL::Texture2DArray > _shadow_color_texture std::unique_ptr< Magnum::GL::CubeMapTextureArray > _shadow_cube_map std::vector< ShadowData > _shadow_data int _shadow_map_size = = 512 std::unique_ptr< gs::ShadowMap > _shadow_shader std::unique_ptr< Magnum::GL::Texture2DArray > _shadow_texture std::unique_ptr< gs::ShadowMapColor > _shadow_texture_color_shader std::unique_ptr< gs::ShadowMap > _shadow_texture_shader bool _shadowed = = true Magnum::SceneGraph::DrawableGroup3D _shadowed_color_drawables Magnum::SceneGraph::DrawableGroup3D _shadowed_drawables RobotDARTSimu * _simu Corrade::Containers::Pointer< Magnum::GL::Buffer > _text_indices std::unique_ptr< Magnum::Shaders::DistanceFieldVectorGL2D > _text_shader Corrade::Containers::Pointer< Magnum::GL::Buffer > _text_vertices std::unique_ptr< gs::PhongMultiLight > _texture_shader int _transparentSize = = 0 bool _transparent_shadows = = false"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1GlfwApplication/#protected-static-attributes","title":"Protected Static Attributes","text":"Type Name constexpr Magnum::Float _speed = = 0.05f"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1GlfwApplication/#protected-functions","title":"Protected Functions","text":"Type Name void drawEvent () override void exitEvent (ExitEvent & event) override virtual void keyPressEvent (KeyEvent & event) override virtual void keyReleaseEvent (KeyEvent & event) override virtual void mouseMoveEvent (MouseMoveEvent & event) override virtual void mouseScrollEvent (MouseScrollEvent & event) override void viewportEvent (ViewportEvent & event) override"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1GlfwApplication/#protected-functions-inherited-from-robot_dartguimagnumbaseapplication","title":"Protected Functions inherited from robot_dart::gui::magnum::BaseApplication","text":"

See robot_dart::gui::magnum::BaseApplication

Type Name void _gl_clean_up () void _prepare_shadows ()"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1GlfwApplication/#public-functions-documentation","title":"Public Functions Documentation","text":""},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1GlfwApplication/#function-glfwapplication","title":"function GlfwApplication","text":"
explicit robot_dart::gui::magnum::GlfwApplication::GlfwApplication (\nint argc,\nchar ** argv,\nRobotDARTSimu * simu,\nconst GraphicsConfiguration & configuration=GraphicsConfiguration ()\n) 
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1GlfwApplication/#function-render","title":"function render","text":"
virtual void robot_dart::gui::magnum::GlfwApplication::render () override\n

Implements robot_dart::gui::magnum::BaseApplication::render

"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1GlfwApplication/#function-glfwapplication_1","title":"function ~GlfwApplication","text":"
robot_dart::gui::magnum::GlfwApplication::~GlfwApplication () 
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1GlfwApplication/#protected-attributes-documentation","title":"Protected Attributes Documentation","text":""},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1GlfwApplication/#variable-_bg_color","title":"variable _bg_color","text":"
Magnum::Color4 robot_dart::gui::magnum::GlfwApplication::_bg_color;\n
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1GlfwApplication/#variable-_draw_debug","title":"variable _draw_debug","text":"
bool robot_dart::gui::magnum::GlfwApplication::_draw_debug;\n
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1GlfwApplication/#variable-_draw_main_camera","title":"variable _draw_main_camera","text":"
bool robot_dart::gui::magnum::GlfwApplication::_draw_main_camera;\n
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1GlfwApplication/#variable-_simu","title":"variable _simu","text":"
RobotDARTSimu* robot_dart::gui::magnum::GlfwApplication::_simu;\n
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1GlfwApplication/#variable-_speed_move","title":"variable _speed_move","text":"
Magnum::Float robot_dart::gui::magnum::GlfwApplication::_speed_move;\n
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1GlfwApplication/#variable-_speed_strafe","title":"variable _speed_strafe","text":"
Magnum::Float robot_dart::gui::magnum::GlfwApplication::_speed_strafe;\n
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1GlfwApplication/#protected-static-attributes-documentation","title":"Protected Static Attributes Documentation","text":""},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1GlfwApplication/#variable-_speed","title":"variable _speed","text":"
constexpr Magnum::Float robot_dart::gui::magnum::GlfwApplication::_speed;\n
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1GlfwApplication/#protected-functions-documentation","title":"Protected Functions Documentation","text":""},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1GlfwApplication/#function-drawevent","title":"function drawEvent","text":"
void robot_dart::gui::magnum::GlfwApplication::drawEvent () override\n
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1GlfwApplication/#function-exitevent","title":"function exitEvent","text":"
void robot_dart::gui::magnum::GlfwApplication::exitEvent (\nExitEvent & event\n) override\n
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1GlfwApplication/#function-keypressevent","title":"function keyPressEvent","text":"
virtual void robot_dart::gui::magnum::GlfwApplication::keyPressEvent (\nKeyEvent & event\n) override\n
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1GlfwApplication/#function-keyreleaseevent","title":"function keyReleaseEvent","text":"
virtual void robot_dart::gui::magnum::GlfwApplication::keyReleaseEvent (\nKeyEvent & event\n) override\n
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1GlfwApplication/#function-mousemoveevent","title":"function mouseMoveEvent","text":"
virtual void robot_dart::gui::magnum::GlfwApplication::mouseMoveEvent (\nMouseMoveEvent & event\n) override\n
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1GlfwApplication/#function-mousescrollevent","title":"function mouseScrollEvent","text":"
virtual void robot_dart::gui::magnum::GlfwApplication::mouseScrollEvent (\nMouseScrollEvent & event\n) override\n
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1GlfwApplication/#function-viewportevent","title":"function viewportEvent","text":"
void robot_dart::gui::magnum::GlfwApplication::viewportEvent (\nViewportEvent & event\n) override\n

The documentation for this class was generated from the following file robot_dart/gui/magnum/glfw_application.hpp

"},{"location":"api/structrobot__dart_1_1gui_1_1magnum_1_1GlobalData/","title":"Struct robot_dart::gui::magnum::GlobalData","text":"

ClassList > robot_dart > gui > magnum > GlobalData

"},{"location":"api/structrobot__dart_1_1gui_1_1magnum_1_1GlobalData/#public-functions","title":"Public Functions","text":"Type Name GlobalData (const GlobalData &) = delete void free_gl_context (Magnum::Platform::WindowlessGLContext * context) Magnum::Platform::WindowlessGLContext * gl_context () void operator= (const GlobalData &) = delete void set_max_contexts (size_t N)"},{"location":"api/structrobot__dart_1_1gui_1_1magnum_1_1GlobalData/#public-static-functions","title":"Public Static Functions","text":"Type Name GlobalData * instance ()"},{"location":"api/structrobot__dart_1_1gui_1_1magnum_1_1GlobalData/#public-functions-documentation","title":"Public Functions Documentation","text":""},{"location":"api/structrobot__dart_1_1gui_1_1magnum_1_1GlobalData/#function-globaldata-12","title":"function GlobalData [\u00bd]","text":"
robot_dart::gui::magnum::GlobalData::GlobalData (\nconst GlobalData &\n) = delete\n
"},{"location":"api/structrobot__dart_1_1gui_1_1magnum_1_1GlobalData/#function-free_gl_context","title":"function free_gl_context","text":"
void robot_dart::gui::magnum::GlobalData::free_gl_context (\nMagnum::Platform::WindowlessGLContext * context\n) 
"},{"location":"api/structrobot__dart_1_1gui_1_1magnum_1_1GlobalData/#function-gl_context","title":"function gl_context","text":"
Magnum::Platform::WindowlessGLContext * robot_dart::gui::magnum::GlobalData::gl_context () 
"},{"location":"api/structrobot__dart_1_1gui_1_1magnum_1_1GlobalData/#function-operator","title":"function operator=","text":"
void robot_dart::gui::magnum::GlobalData::operator= (\nconst GlobalData &\n) = delete\n
"},{"location":"api/structrobot__dart_1_1gui_1_1magnum_1_1GlobalData/#function-set_max_contexts","title":"function set_max_contexts","text":"
void robot_dart::gui::magnum::GlobalData::set_max_contexts (\nsize_t N\n) 
"},{"location":"api/structrobot__dart_1_1gui_1_1magnum_1_1GlobalData/#public-static-functions-documentation","title":"Public Static Functions Documentation","text":""},{"location":"api/structrobot__dart_1_1gui_1_1magnum_1_1GlobalData/#function-instance","title":"function instance","text":"
static inline GlobalData * robot_dart::gui::magnum::GlobalData::instance () 

The documentation for this class was generated from the following file robot_dart/gui/magnum/base_application.hpp

"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1Graphics/","title":"Class robot_dart::gui::magnum::Graphics","text":"

ClassList > robot_dart > gui > magnum > Graphics

Inherits the following classes: robot_dart::gui::magnum::BaseGraphics

"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1Graphics/#public-functions","title":"Public Functions","text":"Type Name Graphics (const GraphicsConfiguration & configuration=default_configuration()) virtual void set_simu (RobotDARTSimu * simu) override ~Graphics ()"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1Graphics/#public-functions-inherited-from-robot_dartguimagnumbasegraphics","title":"Public Functions inherited from robot_dart::gui::magnum::BaseGraphics","text":"

See robot_dart::gui::magnum::BaseGraphics

Type Name BaseGraphics (const GraphicsConfiguration & configuration=GraphicsConfiguration()) void add_light (const magnum::Light & light) gs::Camera & camera () const gs::Camera & camera () const Eigen::Matrix4d camera_extrinsic_matrix () const Eigen::Matrix3d camera_intrinsic_matrix () const void clear_lights () virtual DepthImage depth_array () override virtual GrayscaleImage depth_image () override virtual bool done () override const void enable_shadows (bool enable=true, bool transparent=true) virtual size_t height () override const virtual Image image () override magnum::Light & light (size_t i) std::vector< gs::Light > & lights () void look_at (const Eigen::Vector3d & camera_pos, const Eigen::Vector3d & look_at=Eigen::Vector3d(0, 0, 0), const Eigen::Vector3d & up=Eigen::Vector3d(0, 0, 1)) BaseApplication * magnum_app () const BaseApplication * magnum_app () const Magnum::Image2D * magnum_image () size_t num_lights () const virtual GrayscaleImage raw_depth_image () override void record_video (const std::string & video_fname, int fps=-1) virtual void refresh () override virtual void set_enable (bool enable) override virtual void set_fps (int fps) override virtual void set_simu (RobotDARTSimu * simu) override bool shadowed () const bool transparent_shadows () const virtual size_t width () override const virtual ~BaseGraphics ()"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1Graphics/#public-functions-inherited-from-robot_dartguibase","title":"Public Functions inherited from robot_dart::gui::Base","text":"

See robot_dart::gui::Base

Type Name Base () virtual DepthImage depth_array () virtual GrayscaleImage depth_image () virtual bool done () const virtual size_t height () const virtual Image image () virtual GrayscaleImage raw_depth_image () virtual void refresh () virtual void set_enable (bool) virtual void set_fps (int) virtual void set_render_period (double) virtual void set_simu (RobotDARTSimu * simu) const RobotDARTSimu * simu () const virtual size_t width () const virtual ~Base ()"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1Graphics/#public-static-functions","title":"Public Static Functions","text":"Type Name GraphicsConfiguration default_configuration ()"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1Graphics/#protected-attributes-inherited-from-robot_dartguimagnumbasegraphics","title":"Protected Attributes inherited from robot_dart::gui::magnum::BaseGraphics","text":"

See robot_dart::gui::magnum::BaseGraphics

Type Name GraphicsConfiguration _configuration bool _enabled int _fps std::unique_ptr< BaseApplication > _magnum_app Corrade::Utility::Debug _magnum_silence_output = {nullptr}"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1Graphics/#protected-attributes-inherited-from-robot_dartguibase","title":"Protected Attributes inherited from robot_dart::gui::Base","text":"

See robot_dart::gui::Base

Type Name RobotDARTSimu * _simu = = nullptr"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1Graphics/#public-functions-documentation","title":"Public Functions Documentation","text":""},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1Graphics/#function-graphics","title":"function Graphics","text":"
inline robot_dart::gui::magnum::Graphics::Graphics (\nconst GraphicsConfiguration & configuration=default_configuration()\n) 
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1Graphics/#function-set_simu","title":"function set_simu","text":"
virtual void robot_dart::gui::magnum::Graphics::set_simu (\nRobotDARTSimu * simu\n) override\n

Implements robot_dart::gui::magnum::BaseGraphics::set_simu

"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1Graphics/#function-graphics_1","title":"function ~Graphics","text":"
inline robot_dart::gui::magnum::Graphics::~Graphics () 
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1Graphics/#public-static-functions-documentation","title":"Public Static Functions Documentation","text":""},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1Graphics/#function-default_configuration","title":"function default_configuration","text":"
static GraphicsConfiguration robot_dart::gui::magnum::Graphics::default_configuration () 

The documentation for this class was generated from the following file robot_dart/gui/magnum/graphics.hpp

"},{"location":"api/structrobot__dart_1_1gui_1_1magnum_1_1GraphicsConfiguration/","title":"Struct robot_dart::gui::magnum::GraphicsConfiguration","text":"

ClassList > robot_dart > gui > magnum > GraphicsConfiguration

"},{"location":"api/structrobot__dart_1_1gui_1_1magnum_1_1GraphicsConfiguration/#public-attributes","title":"Public Attributes","text":"Type Name Eigen::Vector4d bg_color = {0.0, 0.0, 0.0, 1.0} bool draw_debug = = true bool draw_main_camera = = true bool draw_text = = true size_t height = = 480 size_t max_lights = = 3 size_t shadow_map_size = = 1024 bool shadowed = = true double specular_strength = = 0.25 std::string title = = \"DART\" bool transparent_shadows = = true size_t width = = 640"},{"location":"api/structrobot__dart_1_1gui_1_1magnum_1_1GraphicsConfiguration/#public-attributes-documentation","title":"Public Attributes Documentation","text":""},{"location":"api/structrobot__dart_1_1gui_1_1magnum_1_1GraphicsConfiguration/#variable-bg_color","title":"variable bg_color","text":"
Eigen::Vector4d robot_dart::gui::magnum::GraphicsConfiguration::bg_color;\n
"},{"location":"api/structrobot__dart_1_1gui_1_1magnum_1_1GraphicsConfiguration/#variable-draw_debug","title":"variable draw_debug","text":"
bool robot_dart::gui::magnum::GraphicsConfiguration::draw_debug;\n
"},{"location":"api/structrobot__dart_1_1gui_1_1magnum_1_1GraphicsConfiguration/#variable-draw_main_camera","title":"variable draw_main_camera","text":"
bool robot_dart::gui::magnum::GraphicsConfiguration::draw_main_camera;\n
"},{"location":"api/structrobot__dart_1_1gui_1_1magnum_1_1GraphicsConfiguration/#variable-draw_text","title":"variable draw_text","text":"
bool robot_dart::gui::magnum::GraphicsConfiguration::draw_text;\n
"},{"location":"api/structrobot__dart_1_1gui_1_1magnum_1_1GraphicsConfiguration/#variable-height","title":"variable height","text":"
size_t robot_dart::gui::magnum::GraphicsConfiguration::height;\n
"},{"location":"api/structrobot__dart_1_1gui_1_1magnum_1_1GraphicsConfiguration/#variable-max_lights","title":"variable max_lights","text":"
size_t robot_dart::gui::magnum::GraphicsConfiguration::max_lights;\n
"},{"location":"api/structrobot__dart_1_1gui_1_1magnum_1_1GraphicsConfiguration/#variable-shadow_map_size","title":"variable shadow_map_size","text":"
size_t robot_dart::gui::magnum::GraphicsConfiguration::shadow_map_size;\n
"},{"location":"api/structrobot__dart_1_1gui_1_1magnum_1_1GraphicsConfiguration/#variable-shadowed","title":"variable shadowed","text":"
bool robot_dart::gui::magnum::GraphicsConfiguration::shadowed;\n
"},{"location":"api/structrobot__dart_1_1gui_1_1magnum_1_1GraphicsConfiguration/#variable-specular_strength","title":"variable specular_strength","text":"
double robot_dart::gui::magnum::GraphicsConfiguration::specular_strength;\n
"},{"location":"api/structrobot__dart_1_1gui_1_1magnum_1_1GraphicsConfiguration/#variable-title","title":"variable title","text":"
std::string robot_dart::gui::magnum::GraphicsConfiguration::title;\n
"},{"location":"api/structrobot__dart_1_1gui_1_1magnum_1_1GraphicsConfiguration/#variable-transparent_shadows","title":"variable transparent_shadows","text":"
bool robot_dart::gui::magnum::GraphicsConfiguration::transparent_shadows;\n
"},{"location":"api/structrobot__dart_1_1gui_1_1magnum_1_1GraphicsConfiguration/#variable-width","title":"variable width","text":"
size_t robot_dart::gui::magnum::GraphicsConfiguration::width;\n

The documentation for this class was generated from the following file robot_dart/gui/magnum/base_application.hpp

"},{"location":"api/structrobot__dart_1_1gui_1_1magnum_1_1ObjectStruct/","title":"Struct robot_dart::gui::magnum::ObjectStruct","text":"

ClassList > robot_dart > gui > magnum > ObjectStruct

"},{"location":"api/structrobot__dart_1_1gui_1_1magnum_1_1ObjectStruct/#public-attributes","title":"Public Attributes","text":"Type Name CubeMapShadowedObject * cubemapped CubeMapShadowedColorObject * cubemapped_color DrawableObject * drawable ShadowedObject * shadowed ShadowedColorObject * shadowed_color"},{"location":"api/structrobot__dart_1_1gui_1_1magnum_1_1ObjectStruct/#public-attributes-documentation","title":"Public Attributes Documentation","text":""},{"location":"api/structrobot__dart_1_1gui_1_1magnum_1_1ObjectStruct/#variable-cubemapped","title":"variable cubemapped","text":"
CubeMapShadowedObject* robot_dart::gui::magnum::ObjectStruct::cubemapped;\n
"},{"location":"api/structrobot__dart_1_1gui_1_1magnum_1_1ObjectStruct/#variable-cubemapped_color","title":"variable cubemapped_color","text":"
CubeMapShadowedColorObject* robot_dart::gui::magnum::ObjectStruct::cubemapped_color;\n
"},{"location":"api/structrobot__dart_1_1gui_1_1magnum_1_1ObjectStruct/#variable-drawable","title":"variable drawable","text":"
DrawableObject* robot_dart::gui::magnum::ObjectStruct::drawable;\n
"},{"location":"api/structrobot__dart_1_1gui_1_1magnum_1_1ObjectStruct/#variable-shadowed","title":"variable shadowed","text":"
ShadowedObject* robot_dart::gui::magnum::ObjectStruct::shadowed;\n
"},{"location":"api/structrobot__dart_1_1gui_1_1magnum_1_1ObjectStruct/#variable-shadowed_color","title":"variable shadowed_color","text":"
ShadowedColorObject* robot_dart::gui::magnum::ObjectStruct::shadowed_color;\n

The documentation for this class was generated from the following file robot_dart/gui/magnum/drawables.hpp

"},{"location":"api/structrobot__dart_1_1gui_1_1magnum_1_1ShadowData/","title":"Struct robot_dart::gui::magnum::ShadowData","text":"

ClassList > robot_dart > gui > magnum > ShadowData

"},{"location":"api/structrobot__dart_1_1gui_1_1magnum_1_1ShadowData/#public-attributes","title":"Public Attributes","text":"Type Name Magnum::GL::Framebuffer shadow_color_framebuffer = {Magnum::NoCreate} Magnum::GL::Framebuffer shadow_framebuffer = {Magnum::NoCreate}"},{"location":"api/structrobot__dart_1_1gui_1_1magnum_1_1ShadowData/#public-attributes-documentation","title":"Public Attributes Documentation","text":""},{"location":"api/structrobot__dart_1_1gui_1_1magnum_1_1ShadowData/#variable-shadow_color_framebuffer","title":"variable shadow_color_framebuffer","text":"
Magnum::GL::Framebuffer robot_dart::gui::magnum::ShadowData::shadow_color_framebuffer;\n
"},{"location":"api/structrobot__dart_1_1gui_1_1magnum_1_1ShadowData/#variable-shadow_framebuffer","title":"variable shadow_framebuffer","text":"
Magnum::GL::Framebuffer robot_dart::gui::magnum::ShadowData::shadow_framebuffer;\n

The documentation for this class was generated from the following file robot_dart/gui/magnum/drawables.hpp

"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1ShadowedColorObject/","title":"Class robot_dart::gui::magnum::ShadowedColorObject","text":"

ClassList > robot_dart > gui > magnum > ShadowedColorObject

Inherits the following classes: Object3D, Magnum::SceneGraph::Drawable3D

"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1ShadowedColorObject/#public-functions","title":"Public Functions","text":"Type Name ShadowedColorObject (RobotDARTSimu * simu, dart::dynamics::ShapeNode * shape, const std::vector< std::reference_wrapper< Magnum::GL::Mesh > > & meshes, gs::ShadowMapColor & shader, gs::ShadowMapColor & texture_shader, Object3D * parent, Magnum::SceneGraph::DrawableGroup3D * group) ShadowedColorObject & set_materials (const std::vector< gs::Material > & materials) ShadowedColorObject & set_meshes (const std::vector< std::reference_wrapper< Magnum::GL::Mesh > > & meshes) ShadowedColorObject & set_scalings (const std::vector< Magnum::Vector3 > & scalings) dart::dynamics::ShapeNode * shape () const RobotDARTSimu * simu () const"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1ShadowedColorObject/#public-functions-documentation","title":"Public Functions Documentation","text":""},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1ShadowedColorObject/#function-shadowedcolorobject","title":"function ShadowedColorObject","text":"
explicit robot_dart::gui::magnum::ShadowedColorObject::ShadowedColorObject (\nRobotDARTSimu * simu,\ndart::dynamics::ShapeNode * shape,\nconst std::vector< std::reference_wrapper< Magnum::GL::Mesh > > & meshes,\ngs::ShadowMapColor & shader,\ngs::ShadowMapColor & texture_shader,\nObject3D * parent,\nMagnum::SceneGraph::DrawableGroup3D * group\n) 
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1ShadowedColorObject/#function-set_materials","title":"function set_materials","text":"
ShadowedColorObject & robot_dart::gui::magnum::ShadowedColorObject::set_materials (\nconst std::vector< gs::Material > & materials\n) 
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1ShadowedColorObject/#function-set_meshes","title":"function set_meshes","text":"
ShadowedColorObject & robot_dart::gui::magnum::ShadowedColorObject::set_meshes (\nconst std::vector< std::reference_wrapper< Magnum::GL::Mesh > > & meshes\n) 
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1ShadowedColorObject/#function-set_scalings","title":"function set_scalings","text":"
ShadowedColorObject & robot_dart::gui::magnum::ShadowedColorObject::set_scalings (\nconst std::vector< Magnum::Vector3 > & scalings\n) 
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1ShadowedColorObject/#function-shape","title":"function shape","text":"
inline dart::dynamics::ShapeNode * robot_dart::gui::magnum::ShadowedColorObject::shape () const\n
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1ShadowedColorObject/#function-simu","title":"function simu","text":"
inline RobotDARTSimu * robot_dart::gui::magnum::ShadowedColorObject::simu () const\n

The documentation for this class was generated from the following file robot_dart/gui/magnum/drawables.hpp

"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1ShadowedObject/","title":"Class robot_dart::gui::magnum::ShadowedObject","text":"

ClassList > robot_dart > gui > magnum > ShadowedObject

Inherits the following classes: Object3D, Magnum::SceneGraph::Drawable3D

"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1ShadowedObject/#public-functions","title":"Public Functions","text":"Type Name ShadowedObject (RobotDARTSimu * simu, dart::dynamics::ShapeNode * shape, const std::vector< std::reference_wrapper< Magnum::GL::Mesh > > & meshes, gs::ShadowMap & shader, gs::ShadowMap & texture_shader, Object3D * parent, Magnum::SceneGraph::DrawableGroup3D * group) ShadowedObject & set_materials (const std::vector< gs::Material > & materials) ShadowedObject & set_meshes (const std::vector< std::reference_wrapper< Magnum::GL::Mesh > > & meshes) ShadowedObject & set_scalings (const std::vector< Magnum::Vector3 > & scalings) dart::dynamics::ShapeNode * shape () const RobotDARTSimu * simu () const"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1ShadowedObject/#public-functions-documentation","title":"Public Functions Documentation","text":""},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1ShadowedObject/#function-shadowedobject","title":"function ShadowedObject","text":"
explicit robot_dart::gui::magnum::ShadowedObject::ShadowedObject (\nRobotDARTSimu * simu,\ndart::dynamics::ShapeNode * shape,\nconst std::vector< std::reference_wrapper< Magnum::GL::Mesh > > & meshes,\ngs::ShadowMap & shader,\ngs::ShadowMap & texture_shader,\nObject3D * parent,\nMagnum::SceneGraph::DrawableGroup3D * group\n) 
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1ShadowedObject/#function-set_materials","title":"function set_materials","text":"
ShadowedObject & robot_dart::gui::magnum::ShadowedObject::set_materials (\nconst std::vector< gs::Material > & materials\n) 
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1ShadowedObject/#function-set_meshes","title":"function set_meshes","text":"
ShadowedObject & robot_dart::gui::magnum::ShadowedObject::set_meshes (\nconst std::vector< std::reference_wrapper< Magnum::GL::Mesh > > & meshes\n) 
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1ShadowedObject/#function-set_scalings","title":"function set_scalings","text":"
ShadowedObject & robot_dart::gui::magnum::ShadowedObject::set_scalings (\nconst std::vector< Magnum::Vector3 > & scalings\n) 
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1ShadowedObject/#function-shape","title":"function shape","text":"
inline dart::dynamics::ShapeNode * robot_dart::gui::magnum::ShadowedObject::shape () const\n
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1ShadowedObject/#function-simu","title":"function simu","text":"
inline RobotDARTSimu * robot_dart::gui::magnum::ShadowedObject::simu () const\n

The documentation for this class was generated from the following file robot_dart/gui/magnum/drawables.hpp

"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1WindowlessGLApplication/","title":"Class robot_dart::gui::magnum::WindowlessGLApplication","text":"

ClassList > robot_dart > gui > magnum > WindowlessGLApplication

Inherits the following classes: robot_dart::gui::magnum::BaseApplication, Magnum::Platform::WindowlessApplication

"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1WindowlessGLApplication/#public-functions","title":"Public Functions","text":"Type Name WindowlessGLApplication (int argc, char ** argv, RobotDARTSimu * simu, const GraphicsConfiguration & configuration=GraphicsConfiguration()) virtual void render () override ~WindowlessGLApplication ()"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1WindowlessGLApplication/#public-functions-inherited-from-robot_dartguimagnumbaseapplication","title":"Public Functions inherited from robot_dart::gui::magnum::BaseApplication","text":"

See robot_dart::gui::magnum::BaseApplication

Type Name BaseApplication (const GraphicsConfiguration & configuration=GraphicsConfiguration()) void add_light (const gs::Light & light) bool attach_camera (gs::Camera & camera, dart::dynamics::BodyNode * body) gs::Camera & camera () const gs::Camera & camera () const void clear_lights () DebugDrawData debug_draw_data () DepthImage depth_array () GrayscaleImage depth_image () bool done () const Magnum::SceneGraph::DrawableGroup3D & drawables () void enable_shadows (bool enable=true, bool drawTransparentShadows=false) Corrade::Containers::Optional< Magnum::Image2D > & image () void init (RobotDARTSimu * simu, const GraphicsConfiguration & configuration) gs::Light & light (size_t i) std::vector< gs::Light > & lights () void look_at (const Eigen::Vector3d & camera_pos, const Eigen::Vector3d & look_at, const Eigen::Vector3d & up) size_t num_lights () const GrayscaleImage raw_depth_image () void record_video (const std::string & video_fname, int fps) virtual void render () void render_shadows () Scene3D & scene () bool shadowed () const bool transparent_shadows () const void update_graphics () void update_lights (const gs::Camera & camera) virtual ~BaseApplication ()"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1WindowlessGLApplication/#protected-attributes","title":"Protected Attributes","text":"Type Name Magnum::Color4 _bg_color Magnum::GL::Renderbuffer _color = {Magnum::NoCreate} Magnum::GL::Renderbuffer _depth = {Magnum::NoCreate} bool _draw_debug bool _draw_main_camera Magnum::PixelFormat _format Magnum::GL::Framebuffer _framebuffer = {Magnum::NoCreate} RobotDARTSimu * _simu"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1WindowlessGLApplication/#protected-attributes-inherited-from-robot_dartguimagnumbaseapplication","title":"Protected Attributes inherited from robot_dart::gui::magnum::BaseApplication","text":"

See robot_dart::gui::magnum::BaseApplication

Type Name std::unique_ptr< Magnum::GL::Mesh > _3D_axis_mesh std::unique_ptr< Magnum::Shaders::VertexColorGL3D > _3D_axis_shader std::unique_ptr< Magnum::GL::Mesh > _background_mesh std::unique_ptr< Magnum::Shaders::FlatGL2D > _background_shader std::unique_ptr< gs::Camera > _camera std::unique_ptr< gs::PhongMultiLight > _color_shader GraphicsConfiguration _configuration Magnum::SceneGraph::DrawableGroup3D _cubemap_color_drawables std::unique_ptr< gs::CubeMapColor > _cubemap_color_shader Magnum::SceneGraph::DrawableGroup3D _cubemap_drawables std::unique_ptr< gs::CubeMap > _cubemap_shader std::unique_ptr< gs::CubeMapColor > _cubemap_texture_color_shader std::unique_ptr< gs::CubeMap > _cubemap_texture_shader std::unique_ptr< Magnum::DartIntegration::World > _dart_world bool _done = = false std::unordered_map< Magnum::DartIntegration::Object *, ObjectStruct * > _drawable_objects Magnum::SceneGraph::DrawableGroup3D _drawables Corrade::Containers::Pointer< Magnum::Text::AbstractFont > _font Corrade::PluginManager::Manager< Magnum::Text::AbstractFont > _font_manager Corrade::Containers::Pointer< Magnum::Text::DistanceFieldGlyphCache > _glyph_cache Corrade::PluginManager::Manager< Magnum::Trade::AbstractImporter > _importer_manager std::vector< gs::Light > _lights int _max_lights = = 5 Scene3D _scene std::unique_ptr< Camera3D > _shadow_camera Object3D * _shadow_camera_object std::unique_ptr< Magnum::GL::CubeMapTextureArray > _shadow_color_cube_map std::unique_ptr< gs::ShadowMapColor > _shadow_color_shader std::unique_ptr< Magnum::GL::Texture2DArray > _shadow_color_texture std::unique_ptr< Magnum::GL::CubeMapTextureArray > _shadow_cube_map std::vector< ShadowData > _shadow_data int _shadow_map_size = = 512 std::unique_ptr< gs::ShadowMap > _shadow_shader std::unique_ptr< Magnum::GL::Texture2DArray > _shadow_texture std::unique_ptr< gs::ShadowMapColor > _shadow_texture_color_shader std::unique_ptr< gs::ShadowMap > _shadow_texture_shader bool _shadowed = = true Magnum::SceneGraph::DrawableGroup3D _shadowed_color_drawables Magnum::SceneGraph::DrawableGroup3D _shadowed_drawables RobotDARTSimu * _simu Corrade::Containers::Pointer< Magnum::GL::Buffer > _text_indices std::unique_ptr< Magnum::Shaders::DistanceFieldVectorGL2D > _text_shader Corrade::Containers::Pointer< Magnum::GL::Buffer > _text_vertices std::unique_ptr< gs::PhongMultiLight > _texture_shader int _transparentSize = = 0 bool _transparent_shadows = = false"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1WindowlessGLApplication/#protected-functions","title":"Protected Functions","text":"Type Name virtual int exec () override"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1WindowlessGLApplication/#protected-functions-inherited-from-robot_dartguimagnumbaseapplication","title":"Protected Functions inherited from robot_dart::gui::magnum::BaseApplication","text":"

See robot_dart::gui::magnum::BaseApplication

Type Name void _gl_clean_up () void _prepare_shadows ()"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1WindowlessGLApplication/#public-functions-documentation","title":"Public Functions Documentation","text":""},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1WindowlessGLApplication/#function-windowlessglapplication","title":"function WindowlessGLApplication","text":"
explicit robot_dart::gui::magnum::WindowlessGLApplication::WindowlessGLApplication (\nint argc,\nchar ** argv,\nRobotDARTSimu * simu,\nconst GraphicsConfiguration & configuration=GraphicsConfiguration ()\n) 
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1WindowlessGLApplication/#function-render","title":"function render","text":"
virtual void robot_dart::gui::magnum::WindowlessGLApplication::render () override\n

Implements robot_dart::gui::magnum::BaseApplication::render

"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1WindowlessGLApplication/#function-windowlessglapplication_1","title":"function ~WindowlessGLApplication","text":"
robot_dart::gui::magnum::WindowlessGLApplication::~WindowlessGLApplication () 
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1WindowlessGLApplication/#protected-attributes-documentation","title":"Protected Attributes Documentation","text":""},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1WindowlessGLApplication/#variable-_bg_color","title":"variable _bg_color","text":"
Magnum::Color4 robot_dart::gui::magnum::WindowlessGLApplication::_bg_color;\n
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1WindowlessGLApplication/#variable-_color","title":"variable _color","text":"
Magnum::GL::Renderbuffer robot_dart::gui::magnum::WindowlessGLApplication::_color;\n
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1WindowlessGLApplication/#variable-_depth","title":"variable _depth","text":"
Magnum::GL::Renderbuffer robot_dart::gui::magnum::WindowlessGLApplication::_depth;\n
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1WindowlessGLApplication/#variable-_draw_debug","title":"variable _draw_debug","text":"
bool robot_dart::gui::magnum::WindowlessGLApplication::_draw_debug;\n
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1WindowlessGLApplication/#variable-_draw_main_camera","title":"variable _draw_main_camera","text":"
bool robot_dart::gui::magnum::WindowlessGLApplication::_draw_main_camera;\n
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1WindowlessGLApplication/#variable-_format","title":"variable _format","text":"
Magnum::PixelFormat robot_dart::gui::magnum::WindowlessGLApplication::_format;\n
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1WindowlessGLApplication/#variable-_framebuffer","title":"variable _framebuffer","text":"
Magnum::GL::Framebuffer robot_dart::gui::magnum::WindowlessGLApplication::_framebuffer;\n
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1WindowlessGLApplication/#variable-_simu","title":"variable _simu","text":"
RobotDARTSimu* robot_dart::gui::magnum::WindowlessGLApplication::_simu;\n
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1WindowlessGLApplication/#protected-functions-documentation","title":"Protected Functions Documentation","text":""},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1WindowlessGLApplication/#function-exec","title":"function exec","text":"
inline virtual int robot_dart::gui::magnum::WindowlessGLApplication::exec () override\n

The documentation for this class was generated from the following file robot_dart/gui/magnum/windowless_gl_application.hpp

"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1WindowlessGraphics/","title":"Class robot_dart::gui::magnum::WindowlessGraphics","text":"

ClassList > robot_dart > gui > magnum > WindowlessGraphics

Inherits the following classes: robot_dart::gui::magnum::BaseGraphics

"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1WindowlessGraphics/#public-functions","title":"Public Functions","text":"Type Name WindowlessGraphics (const GraphicsConfiguration & configuration=default_configuration()) virtual void set_simu (RobotDARTSimu * simu) override ~WindowlessGraphics ()"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1WindowlessGraphics/#public-functions-inherited-from-robot_dartguimagnumbasegraphics","title":"Public Functions inherited from robot_dart::gui::magnum::BaseGraphics","text":"

See robot_dart::gui::magnum::BaseGraphics

Type Name BaseGraphics (const GraphicsConfiguration & configuration=GraphicsConfiguration()) void add_light (const magnum::Light & light) gs::Camera & camera () const gs::Camera & camera () const Eigen::Matrix4d camera_extrinsic_matrix () const Eigen::Matrix3d camera_intrinsic_matrix () const void clear_lights () virtual DepthImage depth_array () override virtual GrayscaleImage depth_image () override virtual bool done () override const void enable_shadows (bool enable=true, bool transparent=true) virtual size_t height () override const virtual Image image () override magnum::Light & light (size_t i) std::vector< gs::Light > & lights () void look_at (const Eigen::Vector3d & camera_pos, const Eigen::Vector3d & look_at=Eigen::Vector3d(0, 0, 0), const Eigen::Vector3d & up=Eigen::Vector3d(0, 0, 1)) BaseApplication * magnum_app () const BaseApplication * magnum_app () const Magnum::Image2D * magnum_image () size_t num_lights () const virtual GrayscaleImage raw_depth_image () override void record_video (const std::string & video_fname, int fps=-1) virtual void refresh () override virtual void set_enable (bool enable) override virtual void set_fps (int fps) override virtual void set_simu (RobotDARTSimu * simu) override bool shadowed () const bool transparent_shadows () const virtual size_t width () override const virtual ~BaseGraphics ()"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1WindowlessGraphics/#public-functions-inherited-from-robot_dartguibase","title":"Public Functions inherited from robot_dart::gui::Base","text":"

See robot_dart::gui::Base

Type Name Base () virtual DepthImage depth_array () virtual GrayscaleImage depth_image () virtual bool done () const virtual size_t height () const virtual Image image () virtual GrayscaleImage raw_depth_image () virtual void refresh () virtual void set_enable (bool) virtual void set_fps (int) virtual void set_render_period (double) virtual void set_simu (RobotDARTSimu * simu) const RobotDARTSimu * simu () const virtual size_t width () const virtual ~Base ()"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1WindowlessGraphics/#public-static-functions","title":"Public Static Functions","text":"Type Name GraphicsConfiguration default_configuration ()"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1WindowlessGraphics/#protected-attributes-inherited-from-robot_dartguimagnumbasegraphics","title":"Protected Attributes inherited from robot_dart::gui::magnum::BaseGraphics","text":"

See robot_dart::gui::magnum::BaseGraphics

Type Name GraphicsConfiguration _configuration bool _enabled int _fps std::unique_ptr< BaseApplication > _magnum_app Corrade::Utility::Debug _magnum_silence_output = {nullptr}"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1WindowlessGraphics/#protected-attributes-inherited-from-robot_dartguibase","title":"Protected Attributes inherited from robot_dart::gui::Base","text":"

See robot_dart::gui::Base

Type Name RobotDARTSimu * _simu = = nullptr"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1WindowlessGraphics/#public-functions-documentation","title":"Public Functions Documentation","text":""},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1WindowlessGraphics/#function-windowlessgraphics","title":"function WindowlessGraphics","text":"
inline robot_dart::gui::magnum::WindowlessGraphics::WindowlessGraphics (\nconst GraphicsConfiguration & configuration=default_configuration()\n) 
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1WindowlessGraphics/#function-set_simu","title":"function set_simu","text":"
virtual void robot_dart::gui::magnum::WindowlessGraphics::set_simu (\nRobotDARTSimu * simu\n) override\n

Implements robot_dart::gui::magnum::BaseGraphics::set_simu

"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1WindowlessGraphics/#function-windowlessgraphics_1","title":"function ~WindowlessGraphics","text":"
inline robot_dart::gui::magnum::WindowlessGraphics::~WindowlessGraphics () 
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1WindowlessGraphics/#public-static-functions-documentation","title":"Public Static Functions Documentation","text":""},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1WindowlessGraphics/#function-default_configuration","title":"function default_configuration","text":"
static GraphicsConfiguration robot_dart::gui::magnum::WindowlessGraphics::default_configuration () 

The documentation for this class was generated from the following file robot_dart/gui/magnum/windowless_graphics.hpp

"},{"location":"api/namespacerobot__dart_1_1gui_1_1magnum_1_1gs/","title":"Namespace robot_dart::gui::magnum::gs","text":"

Namespace List > robot_dart > gui > magnum > gs

"},{"location":"api/namespacerobot__dart_1_1gui_1_1magnum_1_1gs/#classes","title":"Classes","text":"Type Name class Camera class CubeMap class CubeMapColor class Light class Material class PhongMultiLight class ShadowMap class ShadowMapColor"},{"location":"api/namespacerobot__dart_1_1gui_1_1magnum_1_1gs/#public-functions","title":"Public Functions","text":"Type Name Light create_directional_light (const Magnum::Vector3 & direction, const Material & material) Light create_point_light (const Magnum::Vector3 & position, const Material & material, Magnum::Float intensity, const Magnum::Vector3 & attenuationTerms) Light create_spot_light (const Magnum::Vector3 & position, const Material & material, const Magnum::Vector3 & spot_direction, Magnum::Float spot_exponent, Magnum::Float spot_cut_off, Magnum::Float intensity, const Magnum::Vector3 & attenuationTerms) DepthImage depth_array_from_image (Magnum::Image2D * image, Magnum::Float near_plane, Magnum::Float far_plane) GrayscaleImage depth_from_image (Magnum::Image2D * image, bool linearize, Magnum::Float near_plane, Magnum::Float far_plane) Image rgb_from_image (Magnum::Image2D * image)"},{"location":"api/namespacerobot__dart_1_1gui_1_1magnum_1_1gs/#public-static-functions","title":"Public Static Functions","text":"Type Name fs::path search_path (const fs::path & filename)"},{"location":"api/namespacerobot__dart_1_1gui_1_1magnum_1_1gs/#public-functions-documentation","title":"Public Functions Documentation","text":""},{"location":"api/namespacerobot__dart_1_1gui_1_1magnum_1_1gs/#function-create_directional_light","title":"function create_directional_light","text":"
inline Light robot_dart::gui::magnum::gs::create_directional_light (\nconst Magnum::Vector3 & direction,\nconst Material & material\n) 
"},{"location":"api/namespacerobot__dart_1_1gui_1_1magnum_1_1gs/#function-create_point_light","title":"function create_point_light","text":"
inline Light robot_dart::gui::magnum::gs::create_point_light (\nconst Magnum::Vector3 & position,\nconst Material & material,\nMagnum::Float intensity,\nconst Magnum::Vector3 & attenuationTerms\n) 
"},{"location":"api/namespacerobot__dart_1_1gui_1_1magnum_1_1gs/#function-create_spot_light","title":"function create_spot_light","text":"
inline Light robot_dart::gui::magnum::gs::create_spot_light (\nconst Magnum::Vector3 & position,\nconst Material & material,\nconst Magnum::Vector3 & spot_direction,\nMagnum::Float spot_exponent,\nMagnum::Float spot_cut_off,\nMagnum::Float intensity,\nconst Magnum::Vector3 & attenuationTerms\n) 
"},{"location":"api/namespacerobot__dart_1_1gui_1_1magnum_1_1gs/#function-depth_array_from_image","title":"function depth_array_from_image","text":"
DepthImage robot_dart::gui::magnum::gs::depth_array_from_image (\nMagnum::Image2D * image,\nMagnum::Float near_plane,\nMagnum::Float far_plane\n) 
"},{"location":"api/namespacerobot__dart_1_1gui_1_1magnum_1_1gs/#function-depth_from_image","title":"function depth_from_image","text":"
GrayscaleImage robot_dart::gui::magnum::gs::depth_from_image (\nMagnum::Image2D * image,\nbool linearize,\nMagnum::Float near_plane,\nMagnum::Float far_plane\n) 
"},{"location":"api/namespacerobot__dart_1_1gui_1_1magnum_1_1gs/#function-rgb_from_image","title":"function rgb_from_image","text":"
Image robot_dart::gui::magnum::gs::rgb_from_image (\nMagnum::Image2D * image\n) 
"},{"location":"api/namespacerobot__dart_1_1gui_1_1magnum_1_1gs/#public-static-functions-documentation","title":"Public Static Functions Documentation","text":""},{"location":"api/namespacerobot__dart_1_1gui_1_1magnum_1_1gs/#function-search_path","title":"function search_path","text":"
static fs::path robot_dart::gui::magnum::gs::search_path (\nconst fs::path & filename\n) 

The documentation for this class was generated from the following file robot_dart/gui/magnum/gs/camera.cpp

"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1Camera/","title":"Class robot_dart::gui::magnum::Camera","text":"

ClassList > robot_dart > gui > magnum > gs > Camera

Inherits the following classes: Object3D

"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1Camera/#public-functions","title":"Public Functions","text":"Type Name Camera (Object3D & object, Magnum::Int width, Magnum::Int height) Camera3D & camera () const Object3D & camera_object () const Corrade::Containers::Optional< Magnum::Image2D > & depth_image () void draw (Magnum::SceneGraph::DrawableGroup3D & drawables, Magnum::GL::AbstractFramebuffer & framebuffer, Magnum::PixelFormat format, RobotDARTSimu * simu, const DebugDrawData & debug_data, bool draw_debug=true) Magnum::Matrix4 extrinsic_matrix () const Magnum::Float far_plane () const Camera & forward (Magnum::Float speed) Magnum::Float fov () const Magnum::Int height () const Corrade::Containers::Optional< Magnum::Image2D > & image () Magnum::Matrix3 intrinsic_matrix () const Camera & look_at (const Magnum::Vector3 & camera, const Magnum::Vector3 & center, const Magnum::Vector3 & up=Magnum::Vector3::zAxis()) Camera & move (const Magnum::Vector2i & shift) Magnum::Float near_plane () const void record (bool recording, bool recording_depth=false) void record_video (const std::string & video_fname, int fps) bool recording () bool recording_depth () Object3D & root_object () Camera & set_camera_params (Magnum::Float near_plane, Magnum::Float far_plane, Magnum::Float fov, Magnum::Int width, Magnum::Int height) Camera & set_far_plane (Magnum::Float far_plane) Camera & set_fov (Magnum::Float fov) Camera & set_near_plane (Magnum::Float near_plane) Camera & set_speed (const Magnum::Vector2 & speed) Camera & set_viewport (const Magnum::Vector2i & size) Magnum::Vector2 speed () const Camera & strafe (Magnum::Float speed) void transform_lights (std::vector< gs::Light > & lights) const Magnum::Int width () const ~Camera ()"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1Camera/#public-functions-documentation","title":"Public Functions Documentation","text":""},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1Camera/#function-camera","title":"function Camera","text":"
explicit robot_dart::gui::magnum::gs::Camera::Camera (\nObject3D & object,\nMagnum::Int width,\nMagnum::Int height\n) 
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1Camera/#function-camera_1","title":"function camera","text":"
Camera3D & robot_dart::gui::magnum::gs::Camera::camera () const\n
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1Camera/#function-camera_object","title":"function camera_object","text":"
Object3D & robot_dart::gui::magnum::gs::Camera::camera_object () const\n
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1Camera/#function-depth_image","title":"function depth_image","text":"
inline Corrade::Containers::Optional< Magnum::Image2D > & robot_dart::gui::magnum::gs::Camera::depth_image () 
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1Camera/#function-draw","title":"function draw","text":"
void robot_dart::gui::magnum::gs::Camera::draw (\nMagnum::SceneGraph::DrawableGroup3D & drawables,\nMagnum::GL::AbstractFramebuffer & framebuffer,\nMagnum::PixelFormat format,\nRobotDARTSimu * simu,\nconst DebugDrawData & debug_data,\nbool draw_debug=true\n) 
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1Camera/#function-extrinsic_matrix","title":"function extrinsic_matrix","text":"
Magnum::Matrix4 robot_dart::gui::magnum::gs::Camera::extrinsic_matrix () const\n
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1Camera/#function-far_plane","title":"function far_plane","text":"
inline Magnum::Float robot_dart::gui::magnum::gs::Camera::far_plane () const\n
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1Camera/#function-forward","title":"function forward","text":"
Camera & robot_dart::gui::magnum::gs::Camera::forward (\nMagnum::Float speed\n) 
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1Camera/#function-fov","title":"function fov","text":"
inline Magnum::Float robot_dart::gui::magnum::gs::Camera::fov () const\n
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1Camera/#function-height","title":"function height","text":"
inline Magnum::Int robot_dart::gui::magnum::gs::Camera::height () const\n
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1Camera/#function-image","title":"function image","text":"
inline Corrade::Containers::Optional< Magnum::Image2D > & robot_dart::gui::magnum::gs::Camera::image () 
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1Camera/#function-intrinsic_matrix","title":"function intrinsic_matrix","text":"
Magnum::Matrix3 robot_dart::gui::magnum::gs::Camera::intrinsic_matrix () const\n
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1Camera/#function-look_at","title":"function look_at","text":"
Camera & robot_dart::gui::magnum::gs::Camera::look_at (\nconst Magnum::Vector3 & camera,\nconst Magnum::Vector3 & center,\nconst Magnum::Vector3 & up=Magnum::Vector3::zAxis()\n) 
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1Camera/#function-move","title":"function move","text":"
Camera & robot_dart::gui::magnum::gs::Camera::move (\nconst Magnum::Vector2i & shift\n) 
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1Camera/#function-near_plane","title":"function near_plane","text":"
inline Magnum::Float robot_dart::gui::magnum::gs::Camera::near_plane () const\n
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1Camera/#function-record","title":"function record","text":"
inline void robot_dart::gui::magnum::gs::Camera::record (\nbool recording,\nbool recording_depth=false\n) 
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1Camera/#function-record_video","title":"function record_video","text":"
void robot_dart::gui::magnum::gs::Camera::record_video (\nconst std::string & video_fname,\nint fps\n) 
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1Camera/#function-recording","title":"function recording","text":"
inline bool robot_dart::gui::magnum::gs::Camera::recording () 
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1Camera/#function-recording_depth","title":"function recording_depth","text":"
inline bool robot_dart::gui::magnum::gs::Camera::recording_depth () 
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1Camera/#function-root_object","title":"function root_object","text":"
Object3D & robot_dart::gui::magnum::gs::Camera::root_object () 
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1Camera/#function-set_camera_params","title":"function set_camera_params","text":"
Camera & robot_dart::gui::magnum::gs::Camera::set_camera_params (\nMagnum::Float near_plane,\nMagnum::Float far_plane,\nMagnum::Float fov,\nMagnum::Int width,\nMagnum::Int height\n) 
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1Camera/#function-set_far_plane","title":"function set_far_plane","text":"
Camera & robot_dart::gui::magnum::gs::Camera::set_far_plane (\nMagnum::Float far_plane\n) 
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1Camera/#function-set_fov","title":"function set_fov","text":"
Camera & robot_dart::gui::magnum::gs::Camera::set_fov (\nMagnum::Float fov\n) 
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1Camera/#function-set_near_plane","title":"function set_near_plane","text":"
Camera & robot_dart::gui::magnum::gs::Camera::set_near_plane (\nMagnum::Float near_plane\n) 
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1Camera/#function-set_speed","title":"function set_speed","text":"
Camera & robot_dart::gui::magnum::gs::Camera::set_speed (\nconst Magnum::Vector2 & speed\n) 
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1Camera/#function-set_viewport","title":"function set_viewport","text":"
Camera & robot_dart::gui::magnum::gs::Camera::set_viewport (\nconst Magnum::Vector2i & size\n) 
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1Camera/#function-speed","title":"function speed","text":"
inline Magnum::Vector2 robot_dart::gui::magnum::gs::Camera::speed () const\n
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1Camera/#function-strafe","title":"function strafe","text":"
Camera & robot_dart::gui::magnum::gs::Camera::strafe (\nMagnum::Float speed\n) 
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1Camera/#function-transform_lights","title":"function transform_lights","text":"
void robot_dart::gui::magnum::gs::Camera::transform_lights (\nstd::vector< gs::Light > & lights\n) const\n
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1Camera/#function-width","title":"function width","text":"
inline Magnum::Int robot_dart::gui::magnum::gs::Camera::width () const\n
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1Camera/#function-camera_2","title":"function ~Camera","text":"
robot_dart::gui::magnum::gs::Camera::~Camera () 

The documentation for this class was generated from the following file robot_dart/gui/magnum/gs/camera.hpp

"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1CubeMap/","title":"Class robot_dart::gui::magnum::CubeMap","text":"

ClassList > robot_dart > gui > magnum > gs > CubeMap

Inherits the following classes: Magnum::GL::AbstractShaderProgram

"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1CubeMap/#public-types","title":"Public Types","text":"Type Name enum Magnum::UnsignedByte Flag typedef Magnum::Containers::EnumSet< Flag > Flags typedef Magnum::Shaders::Generic3D::Position Position typedef Magnum::Shaders::Generic3D::TextureCoordinates TextureCoordinates"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1CubeMap/#public-functions","title":"Public Functions","text":"Type Name CubeMap (Flags flags={}) CubeMap (Magnum::NoCreateT) noexcept Flags flags () const CubeMap & set_far_plane (Magnum::Float far_plane) CubeMap & set_light_index (Magnum::Int index) CubeMap & set_light_position (const Magnum::Vector3 & position) CubeMap & set_material (Material & material) CubeMap & set_shadow_matrices (Magnum::Matrix4 matrices) CubeMap & set_transformation_matrix (const Magnum::Matrix4 & matrix)"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1CubeMap/#public-types-documentation","title":"Public Types Documentation","text":""},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1CubeMap/#enum-flag","title":"enum Flag","text":"
enum robot_dart::gui::magnum::gs::CubeMap::Flag {\nDiffuseTexture = 1 << 0\n};\n
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1CubeMap/#typedef-flags","title":"typedef Flags","text":"
using robot_dart::gui::magnum::gs::CubeMap::Flags =  Magnum::Containers::EnumSet<Flag>;\n
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1CubeMap/#typedef-position","title":"typedef Position","text":"
using robot_dart::gui::magnum::gs::CubeMap::Position =  Magnum::Shaders::Generic3D::Position;\n
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1CubeMap/#typedef-texturecoordinates","title":"typedef TextureCoordinates","text":"
using robot_dart::gui::magnum::gs::CubeMap::TextureCoordinates =  Magnum::Shaders::Generic3D::TextureCoordinates;\n
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1CubeMap/#public-functions-documentation","title":"Public Functions Documentation","text":""},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1CubeMap/#function-cubemap-12","title":"function CubeMap [\u00bd]","text":"
explicit robot_dart::gui::magnum::gs::CubeMap::CubeMap (\nFlags flags={}\n) 
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1CubeMap/#function-cubemap-22","title":"function CubeMap [2/2]","text":"
explicit robot_dart::gui::magnum::gs::CubeMap::CubeMap (\nMagnum::NoCreateT\n) noexcept\n
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1CubeMap/#function-flags","title":"function flags","text":"
Flags robot_dart::gui::magnum::gs::CubeMap::flags () const\n
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1CubeMap/#function-set_far_plane","title":"function set_far_plane","text":"
CubeMap & robot_dart::gui::magnum::gs::CubeMap::set_far_plane (\nMagnum::Float far_plane\n) 
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1CubeMap/#function-set_light_index","title":"function set_light_index","text":"
CubeMap & robot_dart::gui::magnum::gs::CubeMap::set_light_index (\nMagnum::Int index\n) 
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1CubeMap/#function-set_light_position","title":"function set_light_position","text":"
CubeMap & robot_dart::gui::magnum::gs::CubeMap::set_light_position (\nconst Magnum::Vector3 & position\n) 
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1CubeMap/#function-set_material","title":"function set_material","text":"
CubeMap & robot_dart::gui::magnum::gs::CubeMap::set_material (\nMaterial & material\n) 
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1CubeMap/#function-set_shadow_matrices","title":"function set_shadow_matrices","text":"
CubeMap & robot_dart::gui::magnum::gs::CubeMap::set_shadow_matrices (\nMagnum::Matrix4 matrices\n) 
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1CubeMap/#function-set_transformation_matrix","title":"function set_transformation_matrix","text":"
CubeMap & robot_dart::gui::magnum::gs::CubeMap::set_transformation_matrix (\nconst Magnum::Matrix4 & matrix\n) 

The documentation for this class was generated from the following file robot_dart/gui/magnum/gs/cube_map.hpp

"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1CubeMapColor/","title":"Class robot_dart::gui::magnum::CubeMapColor","text":"

ClassList > robot_dart > gui > magnum > gs > CubeMapColor

Inherits the following classes: Magnum::GL::AbstractShaderProgram

"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1CubeMapColor/#public-types","title":"Public Types","text":"Type Name enum Magnum::UnsignedByte Flag typedef Magnum::Containers::EnumSet< Flag > Flags typedef Magnum::Shaders::Generic3D::Position Position typedef Magnum::Shaders::Generic3D::TextureCoordinates TextureCoordinates"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1CubeMapColor/#public-functions","title":"Public Functions","text":"Type Name CubeMapColor (Flags flags={}) CubeMapColor (Magnum::NoCreateT) noexcept CubeMapColor & bind_cube_map_texture (Magnum::GL::CubeMapTextureArray & texture) Flags flags () const CubeMapColor & set_far_plane (Magnum::Float far_plane) CubeMapColor & set_light_index (Magnum::Int index) CubeMapColor & set_light_position (const Magnum::Vector3 & position) CubeMapColor & set_material (Material & material) CubeMapColor & set_shadow_matrices (Magnum::Matrix4 matrices) CubeMapColor & set_transformation_matrix (const Magnum::Matrix4 & matrix)"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1CubeMapColor/#public-types-documentation","title":"Public Types Documentation","text":""},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1CubeMapColor/#enum-flag","title":"enum Flag","text":"
enum robot_dart::gui::magnum::gs::CubeMapColor::Flag {\nDiffuseTexture = 1 << 0\n};\n
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1CubeMapColor/#typedef-flags","title":"typedef Flags","text":"
using robot_dart::gui::magnum::gs::CubeMapColor::Flags =  Magnum::Containers::EnumSet<Flag>;\n
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1CubeMapColor/#typedef-position","title":"typedef Position","text":"
using robot_dart::gui::magnum::gs::CubeMapColor::Position =  Magnum::Shaders::Generic3D::Position;\n
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1CubeMapColor/#typedef-texturecoordinates","title":"typedef TextureCoordinates","text":"
using robot_dart::gui::magnum::gs::CubeMapColor::TextureCoordinates =  Magnum::Shaders::Generic3D::TextureCoordinates;\n
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1CubeMapColor/#public-functions-documentation","title":"Public Functions Documentation","text":""},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1CubeMapColor/#function-cubemapcolor-12","title":"function CubeMapColor [\u00bd]","text":"
explicit robot_dart::gui::magnum::gs::CubeMapColor::CubeMapColor (\nFlags flags={}\n) 
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1CubeMapColor/#function-cubemapcolor-22","title":"function CubeMapColor [2/2]","text":"
explicit robot_dart::gui::magnum::gs::CubeMapColor::CubeMapColor (\nMagnum::NoCreateT\n) noexcept\n
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1CubeMapColor/#function-bind_cube_map_texture","title":"function bind_cube_map_texture","text":"
CubeMapColor & robot_dart::gui::magnum::gs::CubeMapColor::bind_cube_map_texture (\nMagnum::GL::CubeMapTextureArray & texture\n) 
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1CubeMapColor/#function-flags","title":"function flags","text":"
Flags robot_dart::gui::magnum::gs::CubeMapColor::flags () const\n
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1CubeMapColor/#function-set_far_plane","title":"function set_far_plane","text":"
CubeMapColor & robot_dart::gui::magnum::gs::CubeMapColor::set_far_plane (\nMagnum::Float far_plane\n) 
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1CubeMapColor/#function-set_light_index","title":"function set_light_index","text":"
CubeMapColor & robot_dart::gui::magnum::gs::CubeMapColor::set_light_index (\nMagnum::Int index\n) 
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1CubeMapColor/#function-set_light_position","title":"function set_light_position","text":"
CubeMapColor & robot_dart::gui::magnum::gs::CubeMapColor::set_light_position (\nconst Magnum::Vector3 & position\n) 
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1CubeMapColor/#function-set_material","title":"function set_material","text":"
CubeMapColor & robot_dart::gui::magnum::gs::CubeMapColor::set_material (\nMaterial & material\n) 
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1CubeMapColor/#function-set_shadow_matrices","title":"function set_shadow_matrices","text":"
CubeMapColor & robot_dart::gui::magnum::gs::CubeMapColor::set_shadow_matrices (\nMagnum::Matrix4 matrices\n) 
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1CubeMapColor/#function-set_transformation_matrix","title":"function set_transformation_matrix","text":"
CubeMapColor & robot_dart::gui::magnum::gs::CubeMapColor::set_transformation_matrix (\nconst Magnum::Matrix4 & matrix\n) 

The documentation for this class was generated from the following file robot_dart/gui/magnum/gs/cube_map_color.hpp

"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1Light/","title":"Class robot_dart::gui::magnum::Light","text":"

ClassList > robot_dart > gui > magnum > gs > Light

"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1Light/#public-functions","title":"Public Functions","text":"Type Name Light () Light (const Magnum::Vector4 & position, const Material & material, const Magnum::Vector3 & spot_direction, Magnum::Float spot_exponent, Magnum::Float spot_cut_off, const Magnum::Vector4 & attenuation, bool cast_shadows=true) Magnum::Vector4 & attenuation () Magnum::Vector4 attenuation () const bool casts_shadows () const Material & material () Material material () const Magnum::Vector4 position () const Light & set_attenuation (const Magnum::Vector4 & attenuation) Light & set_casts_shadows (bool cast_shadows) Light & set_material (const Material & material) Light & set_position (const Magnum::Vector4 & position) Light & set_shadow_matrix (const Magnum::Matrix4 & shadowTransform) Light & set_spot_cut_off (Magnum::Float spot_cut_off) Light & set_spot_direction (const Magnum::Vector3 & spot_direction) Light & set_spot_exponent (Magnum::Float spot_exponent) Light & set_transformed_position (const Magnum::Vector4 & transformed_position) Light & set_transformed_spot_direction (const Magnum::Vector3 & transformed_spot_direction) Magnum::Matrix4 shadow_matrix () const Magnum::Float & spot_cut_off () Magnum::Float spot_cut_off () const Magnum::Vector3 spot_direction () const Magnum::Float & spot_exponent () Magnum::Float spot_exponent () const Magnum::Vector4 & transformed_position () Magnum::Vector4 transformed_position () const Magnum::Vector3 & transformed_spot_direction () Magnum::Vector3 transformed_spot_direction () const"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1Light/#protected-attributes","title":"Protected Attributes","text":"Type Name Magnum::Vector4 _attenuation bool _cast_shadows = = true Material _material Magnum::Vector4 _position Magnum::Matrix4 _shadow_transform = {} Magnum::Float _spot_cut_off Magnum::Vector3 _spot_direction Magnum::Float _spot_exponent Magnum::Vector4 _transformed_position Magnum::Vector3 _transformed_spot_direction"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1Light/#public-functions-documentation","title":"Public Functions Documentation","text":""},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1Light/#function-light-12","title":"function Light [\u00bd]","text":"
robot_dart::gui::magnum::gs::Light::Light () 
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1Light/#function-light-22","title":"function Light [2/2]","text":"
robot_dart::gui::magnum::gs::Light::Light (\nconst Magnum::Vector4 & position,\nconst Material & material,\nconst Magnum::Vector3 & spot_direction,\nMagnum::Float spot_exponent,\nMagnum::Float spot_cut_off,\nconst Magnum::Vector4 & attenuation,\nbool cast_shadows=true\n) 
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1Light/#function-attenuation-12","title":"function attenuation [\u00bd]","text":"
Magnum::Vector4 & robot_dart::gui::magnum::gs::Light::attenuation () 
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1Light/#function-attenuation-22","title":"function attenuation [2/2]","text":"
Magnum::Vector4 robot_dart::gui::magnum::gs::Light::attenuation () const\n
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1Light/#function-casts_shadows","title":"function casts_shadows","text":"
bool robot_dart::gui::magnum::gs::Light::casts_shadows () const\n
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1Light/#function-material-12","title":"function material [\u00bd]","text":"
Material & robot_dart::gui::magnum::gs::Light::material () 
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1Light/#function-material-22","title":"function material [2/2]","text":"
Material robot_dart::gui::magnum::gs::Light::material () const\n
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1Light/#function-position","title":"function position","text":"
Magnum::Vector4 robot_dart::gui::magnum::gs::Light::position () const\n
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1Light/#function-set_attenuation","title":"function set_attenuation","text":"
Light & robot_dart::gui::magnum::gs::Light::set_attenuation (\nconst Magnum::Vector4 & attenuation\n) 
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1Light/#function-set_casts_shadows","title":"function set_casts_shadows","text":"
Light & robot_dart::gui::magnum::gs::Light::set_casts_shadows (\nbool cast_shadows\n) 
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1Light/#function-set_material","title":"function set_material","text":"
Light & robot_dart::gui::magnum::gs::Light::set_material (\nconst Material & material\n) 
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1Light/#function-set_position","title":"function set_position","text":"
Light & robot_dart::gui::magnum::gs::Light::set_position (\nconst Magnum::Vector4 & position\n) 
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1Light/#function-set_shadow_matrix","title":"function set_shadow_matrix","text":"
Light & robot_dart::gui::magnum::gs::Light::set_shadow_matrix (\nconst Magnum::Matrix4 & shadowTransform\n) 
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1Light/#function-set_spot_cut_off","title":"function set_spot_cut_off","text":"
Light & robot_dart::gui::magnum::gs::Light::set_spot_cut_off (\nMagnum::Float spot_cut_off\n) 
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1Light/#function-set_spot_direction","title":"function set_spot_direction","text":"
Light & robot_dart::gui::magnum::gs::Light::set_spot_direction (\nconst Magnum::Vector3 & spot_direction\n) 
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1Light/#function-set_spot_exponent","title":"function set_spot_exponent","text":"
Light & robot_dart::gui::magnum::gs::Light::set_spot_exponent (\nMagnum::Float spot_exponent\n) 
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1Light/#function-set_transformed_position","title":"function set_transformed_position","text":"
Light & robot_dart::gui::magnum::gs::Light::set_transformed_position (\nconst Magnum::Vector4 & transformed_position\n) 
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1Light/#function-set_transformed_spot_direction","title":"function set_transformed_spot_direction","text":"
Light & robot_dart::gui::magnum::gs::Light::set_transformed_spot_direction (\nconst Magnum::Vector3 & transformed_spot_direction\n) 
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1Light/#function-shadow_matrix","title":"function shadow_matrix","text":"
Magnum::Matrix4 robot_dart::gui::magnum::gs::Light::shadow_matrix () const\n
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1Light/#function-spot_cut_off-12","title":"function spot_cut_off [\u00bd]","text":"
Magnum::Float & robot_dart::gui::magnum::gs::Light::spot_cut_off () 
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1Light/#function-spot_cut_off-22","title":"function spot_cut_off [2/2]","text":"
Magnum::Float robot_dart::gui::magnum::gs::Light::spot_cut_off () const\n
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1Light/#function-spot_direction","title":"function spot_direction","text":"
Magnum::Vector3 robot_dart::gui::magnum::gs::Light::spot_direction () const\n
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1Light/#function-spot_exponent-12","title":"function spot_exponent [\u00bd]","text":"
Magnum::Float & robot_dart::gui::magnum::gs::Light::spot_exponent () 
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1Light/#function-spot_exponent-22","title":"function spot_exponent [2/2]","text":"
Magnum::Float robot_dart::gui::magnum::gs::Light::spot_exponent () const\n
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1Light/#function-transformed_position-12","title":"function transformed_position [\u00bd]","text":"
Magnum::Vector4 & robot_dart::gui::magnum::gs::Light::transformed_position () 
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1Light/#function-transformed_position-22","title":"function transformed_position [2/2]","text":"
Magnum::Vector4 robot_dart::gui::magnum::gs::Light::transformed_position () const\n
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1Light/#function-transformed_spot_direction-12","title":"function transformed_spot_direction [\u00bd]","text":"
Magnum::Vector3 & robot_dart::gui::magnum::gs::Light::transformed_spot_direction () 
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1Light/#function-transformed_spot_direction-22","title":"function transformed_spot_direction [2/2]","text":"
Magnum::Vector3 robot_dart::gui::magnum::gs::Light::transformed_spot_direction () const\n
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1Light/#protected-attributes-documentation","title":"Protected Attributes Documentation","text":""},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1Light/#variable-_attenuation","title":"variable _attenuation","text":"
Magnum::Vector4 robot_dart::gui::magnum::gs::Light::_attenuation;\n
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1Light/#variable-_cast_shadows","title":"variable _cast_shadows","text":"
bool robot_dart::gui::magnum::gs::Light::_cast_shadows;\n
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1Light/#variable-_material","title":"variable _material","text":"
Material robot_dart::gui::magnum::gs::Light::_material;\n
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1Light/#variable-_position","title":"variable _position","text":"
Magnum::Vector4 robot_dart::gui::magnum::gs::Light::_position;\n
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1Light/#variable-_shadow_transform","title":"variable _shadow_transform","text":"
Magnum::Matrix4 robot_dart::gui::magnum::gs::Light::_shadow_transform;\n
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1Light/#variable-_spot_cut_off","title":"variable _spot_cut_off","text":"
Magnum::Float robot_dart::gui::magnum::gs::Light::_spot_cut_off;\n
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1Light/#variable-_spot_direction","title":"variable _spot_direction","text":"
Magnum::Vector3 robot_dart::gui::magnum::gs::Light::_spot_direction;\n
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1Light/#variable-_spot_exponent","title":"variable _spot_exponent","text":"
Magnum::Float robot_dart::gui::magnum::gs::Light::_spot_exponent;\n
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1Light/#variable-_transformed_position","title":"variable _transformed_position","text":"
Magnum::Vector4 robot_dart::gui::magnum::gs::Light::_transformed_position;\n
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1Light/#variable-_transformed_spot_direction","title":"variable _transformed_spot_direction","text":"
Magnum::Vector3 robot_dart::gui::magnum::gs::Light::_transformed_spot_direction;\n

The documentation for this class was generated from the following file robot_dart/gui/magnum/gs/light.hpp

"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1Material/","title":"Class robot_dart::gui::magnum::Material","text":"

ClassList > robot_dart > gui > magnum > gs > Material

"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1Material/#public-functions","title":"Public Functions","text":"Type Name Material () Material (const Magnum::Color4 & ambient, const Magnum::Color4 & diffuse, const Magnum::Color4 & specular, Magnum::Float shininess) Material (Magnum::GL::Texture2D * ambient_texture, Magnum::GL::Texture2D * diffuse_texture, Magnum::GL::Texture2D * specular_texture, Magnum::Float shininess) Magnum::Color4 & ambient_color () Magnum::Color4 ambient_color () const Magnum::GL::Texture2D * ambient_texture () Magnum::Color4 & diffuse_color () Magnum::Color4 diffuse_color () const Magnum::GL::Texture2D * diffuse_texture () bool has_ambient_texture () const bool has_diffuse_texture () const bool has_specular_texture () const Material & set_ambient_color (const Magnum::Color4 & ambient) Material & set_ambient_texture (Magnum::GL::Texture2D * ambient_texture) Material & set_diffuse_color (const Magnum::Color4 & diffuse) Material & set_diffuse_texture (Magnum::GL::Texture2D * diffuse_texture) Material & set_shininess (Magnum::Float shininess) Material & set_specular_color (const Magnum::Color4 & specular) Material & set_specular_texture (Magnum::GL::Texture2D * specular_texture) Magnum::Float & shininess () Magnum::Float shininess () const Magnum::Color4 & specular_color () Magnum::Color4 specular_color () const Magnum::GL::Texture2D * specular_texture ()"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1Material/#protected-attributes","title":"Protected Attributes","text":"Type Name Magnum::Color4 _ambient Magnum::GL::Texture2D * _ambient_texture = = NULL Magnum::Color4 _diffuse Magnum::GL::Texture2D * _diffuse_texture = = NULL Magnum::Float _shininess Magnum::Color4 _specular Magnum::GL::Texture2D * _specular_texture = = NULL"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1Material/#public-functions-documentation","title":"Public Functions Documentation","text":""},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1Material/#function-material-13","title":"function Material [\u2153]","text":"
robot_dart::gui::magnum::gs::Material::Material () 
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1Material/#function-material-23","title":"function Material [\u2154]","text":"
robot_dart::gui::magnum::gs::Material::Material (\nconst Magnum::Color4 & ambient,\nconst Magnum::Color4 & diffuse,\nconst Magnum::Color4 & specular,\nMagnum::Float shininess\n) 
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1Material/#function-material-33","title":"function Material [3/3]","text":"
robot_dart::gui::magnum::gs::Material::Material (\nMagnum::GL::Texture2D * ambient_texture,\nMagnum::GL::Texture2D * diffuse_texture,\nMagnum::GL::Texture2D * specular_texture,\nMagnum::Float shininess\n) 
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1Material/#function-ambient_color-12","title":"function ambient_color [\u00bd]","text":"
Magnum::Color4 & robot_dart::gui::magnum::gs::Material::ambient_color () 
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1Material/#function-ambient_color-22","title":"function ambient_color [2/2]","text":"
Magnum::Color4 robot_dart::gui::magnum::gs::Material::ambient_color () const\n
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1Material/#function-ambient_texture","title":"function ambient_texture","text":"
Magnum::GL::Texture2D * robot_dart::gui::magnum::gs::Material::ambient_texture () 
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1Material/#function-diffuse_color-12","title":"function diffuse_color [\u00bd]","text":"
Magnum::Color4 & robot_dart::gui::magnum::gs::Material::diffuse_color () 
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1Material/#function-diffuse_color-22","title":"function diffuse_color [2/2]","text":"
Magnum::Color4 robot_dart::gui::magnum::gs::Material::diffuse_color () const\n
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1Material/#function-diffuse_texture","title":"function diffuse_texture","text":"
Magnum::GL::Texture2D * robot_dart::gui::magnum::gs::Material::diffuse_texture () 
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1Material/#function-has_ambient_texture","title":"function has_ambient_texture","text":"
bool robot_dart::gui::magnum::gs::Material::has_ambient_texture () const\n
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1Material/#function-has_diffuse_texture","title":"function has_diffuse_texture","text":"
bool robot_dart::gui::magnum::gs::Material::has_diffuse_texture () const\n
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1Material/#function-has_specular_texture","title":"function has_specular_texture","text":"
bool robot_dart::gui::magnum::gs::Material::has_specular_texture () const\n
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1Material/#function-set_ambient_color","title":"function set_ambient_color","text":"
Material & robot_dart::gui::magnum::gs::Material::set_ambient_color (\nconst Magnum::Color4 & ambient\n) 
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1Material/#function-set_ambient_texture","title":"function set_ambient_texture","text":"
Material & robot_dart::gui::magnum::gs::Material::set_ambient_texture (\nMagnum::GL::Texture2D * ambient_texture\n) 
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1Material/#function-set_diffuse_color","title":"function set_diffuse_color","text":"
Material & robot_dart::gui::magnum::gs::Material::set_diffuse_color (\nconst Magnum::Color4 & diffuse\n) 
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1Material/#function-set_diffuse_texture","title":"function set_diffuse_texture","text":"
Material & robot_dart::gui::magnum::gs::Material::set_diffuse_texture (\nMagnum::GL::Texture2D * diffuse_texture\n) 
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1Material/#function-set_shininess","title":"function set_shininess","text":"
Material & robot_dart::gui::magnum::gs::Material::set_shininess (\nMagnum::Float shininess\n) 
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1Material/#function-set_specular_color","title":"function set_specular_color","text":"
Material & robot_dart::gui::magnum::gs::Material::set_specular_color (\nconst Magnum::Color4 & specular\n) 
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1Material/#function-set_specular_texture","title":"function set_specular_texture","text":"
Material & robot_dart::gui::magnum::gs::Material::set_specular_texture (\nMagnum::GL::Texture2D * specular_texture\n) 
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1Material/#function-shininess-12","title":"function shininess [\u00bd]","text":"
Magnum::Float & robot_dart::gui::magnum::gs::Material::shininess () 
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1Material/#function-shininess-22","title":"function shininess [2/2]","text":"
Magnum::Float robot_dart::gui::magnum::gs::Material::shininess () const\n
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1Material/#function-specular_color-12","title":"function specular_color [\u00bd]","text":"
Magnum::Color4 & robot_dart::gui::magnum::gs::Material::specular_color () 
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1Material/#function-specular_color-22","title":"function specular_color [2/2]","text":"
Magnum::Color4 robot_dart::gui::magnum::gs::Material::specular_color () const\n
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1Material/#function-specular_texture","title":"function specular_texture","text":"
Magnum::GL::Texture2D * robot_dart::gui::magnum::gs::Material::specular_texture () 
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1Material/#protected-attributes-documentation","title":"Protected Attributes Documentation","text":""},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1Material/#variable-_ambient","title":"variable _ambient","text":"
Magnum::Color4 robot_dart::gui::magnum::gs::Material::_ambient;\n
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1Material/#variable-_ambient_texture","title":"variable _ambient_texture","text":"
Magnum::GL::Texture2D* robot_dart::gui::magnum::gs::Material::_ambient_texture;\n
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1Material/#variable-_diffuse","title":"variable _diffuse","text":"
Magnum::Color4 robot_dart::gui::magnum::gs::Material::_diffuse;\n
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1Material/#variable-_diffuse_texture","title":"variable _diffuse_texture","text":"
Magnum::GL::Texture2D* robot_dart::gui::magnum::gs::Material::_diffuse_texture;\n
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1Material/#variable-_shininess","title":"variable _shininess","text":"
Magnum::Float robot_dart::gui::magnum::gs::Material::_shininess;\n
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1Material/#variable-_specular","title":"variable _specular","text":"
Magnum::Color4 robot_dart::gui::magnum::gs::Material::_specular;\n
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1Material/#variable-_specular_texture","title":"variable _specular_texture","text":"
Magnum::GL::Texture2D* robot_dart::gui::magnum::gs::Material::_specular_texture;\n

The documentation for this class was generated from the following file robot_dart/gui/magnum/gs/material.hpp

"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1PhongMultiLight/","title":"Class robot_dart::gui::magnum::PhongMultiLight","text":"

ClassList > robot_dart > gui > magnum > gs > PhongMultiLight

Inherits the following classes: Magnum::GL::AbstractShaderProgram

"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1PhongMultiLight/#public-types","title":"Public Types","text":"Type Name enum Magnum::UnsignedByte Flag typedef Magnum::Containers::EnumSet< Flag > Flags typedef Magnum::Shaders::Generic3D::Normal Normal typedef Magnum::Shaders::Generic3D::Position Position typedef Magnum::Shaders::Generic3D::TextureCoordinates TextureCoordinates"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1PhongMultiLight/#public-functions","title":"Public Functions","text":"Type Name PhongMultiLight (Flags flags={}, Magnum::Int max_lights=10) PhongMultiLight (Magnum::NoCreateT) noexcept PhongMultiLight & bind_cube_map_color_texture (Magnum::GL::CubeMapTextureArray & texture) PhongMultiLight & bind_cube_map_texture (Magnum::GL::CubeMapTextureArray & texture) PhongMultiLight & bind_shadow_color_texture (Magnum::GL::Texture2DArray & texture) PhongMultiLight & bind_shadow_texture (Magnum::GL::Texture2DArray & texture) Flags flags () const Magnum::Int max_lights () const PhongMultiLight & set_camera_matrix (const Magnum::Matrix4 & matrix) PhongMultiLight & set_far_plane (Magnum::Float far_plane) PhongMultiLight & set_is_shadowed (bool shadows) PhongMultiLight & set_light (Magnum::Int i, const Light & light) PhongMultiLight & set_material (Material & material) PhongMultiLight & set_normal_matrix (const Magnum::Matrix3x3 & matrix) PhongMultiLight & set_projection_matrix (const Magnum::Matrix4 & matrix) PhongMultiLight & set_specular_strength (Magnum::Float specular_strength) PhongMultiLight & set_transformation_matrix (const Magnum::Matrix4 & matrix) PhongMultiLight & set_transparent_shadows (bool shadows)"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1PhongMultiLight/#public-types-documentation","title":"Public Types Documentation","text":""},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1PhongMultiLight/#enum-flag","title":"enum Flag","text":"
enum robot_dart::gui::magnum::gs::PhongMultiLight::Flag {\nAmbientTexture = 1 << 0,\nDiffuseTexture = 1 << 1,\nSpecularTexture = 1 << 2\n};\n
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1PhongMultiLight/#typedef-flags","title":"typedef Flags","text":"
using robot_dart::gui::magnum::gs::PhongMultiLight::Flags =  Magnum::Containers::EnumSet<Flag>;\n
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1PhongMultiLight/#typedef-normal","title":"typedef Normal","text":"
using robot_dart::gui::magnum::gs::PhongMultiLight::Normal =  Magnum::Shaders::Generic3D::Normal;\n
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1PhongMultiLight/#typedef-position","title":"typedef Position","text":"
using robot_dart::gui::magnum::gs::PhongMultiLight::Position =  Magnum::Shaders::Generic3D::Position;\n
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1PhongMultiLight/#typedef-texturecoordinates","title":"typedef TextureCoordinates","text":"
using robot_dart::gui::magnum::gs::PhongMultiLight::TextureCoordinates =  Magnum::Shaders::Generic3D::TextureCoordinates;\n
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1PhongMultiLight/#public-functions-documentation","title":"Public Functions Documentation","text":""},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1PhongMultiLight/#function-phongmultilight-12","title":"function PhongMultiLight [\u00bd]","text":"
explicit robot_dart::gui::magnum::gs::PhongMultiLight::PhongMultiLight (\nFlags flags={},\nMagnum::Int max_lights=10\n) 
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1PhongMultiLight/#function-phongmultilight-22","title":"function PhongMultiLight [2/2]","text":"
explicit robot_dart::gui::magnum::gs::PhongMultiLight::PhongMultiLight (\nMagnum::NoCreateT\n) noexcept\n
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1PhongMultiLight/#function-bind_cube_map_color_texture","title":"function bind_cube_map_color_texture","text":"
PhongMultiLight & robot_dart::gui::magnum::gs::PhongMultiLight::bind_cube_map_color_texture (\nMagnum::GL::CubeMapTextureArray & texture\n) 
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1PhongMultiLight/#function-bind_cube_map_texture","title":"function bind_cube_map_texture","text":"
PhongMultiLight & robot_dart::gui::magnum::gs::PhongMultiLight::bind_cube_map_texture (\nMagnum::GL::CubeMapTextureArray & texture\n) 
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1PhongMultiLight/#function-bind_shadow_color_texture","title":"function bind_shadow_color_texture","text":"
PhongMultiLight & robot_dart::gui::magnum::gs::PhongMultiLight::bind_shadow_color_texture (\nMagnum::GL::Texture2DArray & texture\n) 
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1PhongMultiLight/#function-bind_shadow_texture","title":"function bind_shadow_texture","text":"
PhongMultiLight & robot_dart::gui::magnum::gs::PhongMultiLight::bind_shadow_texture (\nMagnum::GL::Texture2DArray & texture\n) 
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1PhongMultiLight/#function-flags","title":"function flags","text":"
Flags robot_dart::gui::magnum::gs::PhongMultiLight::flags () const\n
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1PhongMultiLight/#function-max_lights","title":"function max_lights","text":"
Magnum::Int robot_dart::gui::magnum::gs::PhongMultiLight::max_lights () const\n
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1PhongMultiLight/#function-set_camera_matrix","title":"function set_camera_matrix","text":"
PhongMultiLight & robot_dart::gui::magnum::gs::PhongMultiLight::set_camera_matrix (\nconst Magnum::Matrix4 & matrix\n) 
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1PhongMultiLight/#function-set_far_plane","title":"function set_far_plane","text":"
PhongMultiLight & robot_dart::gui::magnum::gs::PhongMultiLight::set_far_plane (\nMagnum::Float far_plane\n) 
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1PhongMultiLight/#function-set_is_shadowed","title":"function set_is_shadowed","text":"
PhongMultiLight & robot_dart::gui::magnum::gs::PhongMultiLight::set_is_shadowed (\nbool shadows\n) 
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1PhongMultiLight/#function-set_light","title":"function set_light","text":"
PhongMultiLight & robot_dart::gui::magnum::gs::PhongMultiLight::set_light (\nMagnum::Int i,\nconst Light & light\n) 
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1PhongMultiLight/#function-set_material","title":"function set_material","text":"
PhongMultiLight & robot_dart::gui::magnum::gs::PhongMultiLight::set_material (\nMaterial & material\n) 
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1PhongMultiLight/#function-set_normal_matrix","title":"function set_normal_matrix","text":"
PhongMultiLight & robot_dart::gui::magnum::gs::PhongMultiLight::set_normal_matrix (\nconst Magnum::Matrix3x3 & matrix\n) 
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1PhongMultiLight/#function-set_projection_matrix","title":"function set_projection_matrix","text":"
PhongMultiLight & robot_dart::gui::magnum::gs::PhongMultiLight::set_projection_matrix (\nconst Magnum::Matrix4 & matrix\n) 
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1PhongMultiLight/#function-set_specular_strength","title":"function set_specular_strength","text":"
PhongMultiLight & robot_dart::gui::magnum::gs::PhongMultiLight::set_specular_strength (\nMagnum::Float specular_strength\n) 
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1PhongMultiLight/#function-set_transformation_matrix","title":"function set_transformation_matrix","text":"
PhongMultiLight & robot_dart::gui::magnum::gs::PhongMultiLight::set_transformation_matrix (\nconst Magnum::Matrix4 & matrix\n) 
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1PhongMultiLight/#function-set_transparent_shadows","title":"function set_transparent_shadows","text":"
PhongMultiLight & robot_dart::gui::magnum::gs::PhongMultiLight::set_transparent_shadows (\nbool shadows\n) 

The documentation for this class was generated from the following file robot_dart/gui/magnum/gs/phong_multi_light.hpp

"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1ShadowMap/","title":"Class robot_dart::gui::magnum::ShadowMap","text":"

ClassList > robot_dart > gui > magnum > gs > ShadowMap

Inherits the following classes: Magnum::GL::AbstractShaderProgram

"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1ShadowMap/#public-types","title":"Public Types","text":"Type Name enum Magnum::UnsignedByte Flag typedef Magnum::Containers::EnumSet< Flag > Flags typedef Magnum::Shaders::Generic3D::Position Position typedef Magnum::Shaders::Generic3D::TextureCoordinates TextureCoordinates"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1ShadowMap/#public-functions","title":"Public Functions","text":"Type Name ShadowMap (Flags flags={}) ShadowMap (Magnum::NoCreateT) noexcept Flags flags () const ShadowMap & set_material (Material & material) ShadowMap & set_projection_matrix (const Magnum::Matrix4 & matrix) ShadowMap & set_transformation_matrix (const Magnum::Matrix4 & matrix)"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1ShadowMap/#public-types-documentation","title":"Public Types Documentation","text":""},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1ShadowMap/#enum-flag","title":"enum Flag","text":"
enum robot_dart::gui::magnum::gs::ShadowMap::Flag {\nDiffuseTexture = 1 << 0\n};\n
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1ShadowMap/#typedef-flags","title":"typedef Flags","text":"
using robot_dart::gui::magnum::gs::ShadowMap::Flags =  Magnum::Containers::EnumSet<Flag>;\n
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1ShadowMap/#typedef-position","title":"typedef Position","text":"
using robot_dart::gui::magnum::gs::ShadowMap::Position =  Magnum::Shaders::Generic3D::Position;\n
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1ShadowMap/#typedef-texturecoordinates","title":"typedef TextureCoordinates","text":"
using robot_dart::gui::magnum::gs::ShadowMap::TextureCoordinates =  Magnum::Shaders::Generic3D::TextureCoordinates;\n
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1ShadowMap/#public-functions-documentation","title":"Public Functions Documentation","text":""},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1ShadowMap/#function-shadowmap-12","title":"function ShadowMap [\u00bd]","text":"
explicit robot_dart::gui::magnum::gs::ShadowMap::ShadowMap (\nFlags flags={}\n) 
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1ShadowMap/#function-shadowmap-22","title":"function ShadowMap [2/2]","text":"
explicit robot_dart::gui::magnum::gs::ShadowMap::ShadowMap (\nMagnum::NoCreateT\n) noexcept\n
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1ShadowMap/#function-flags","title":"function flags","text":"
Flags robot_dart::gui::magnum::gs::ShadowMap::flags () const\n
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1ShadowMap/#function-set_material","title":"function set_material","text":"
ShadowMap & robot_dart::gui::magnum::gs::ShadowMap::set_material (\nMaterial & material\n) 
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1ShadowMap/#function-set_projection_matrix","title":"function set_projection_matrix","text":"
ShadowMap & robot_dart::gui::magnum::gs::ShadowMap::set_projection_matrix (\nconst Magnum::Matrix4 & matrix\n) 
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1ShadowMap/#function-set_transformation_matrix","title":"function set_transformation_matrix","text":"
ShadowMap & robot_dart::gui::magnum::gs::ShadowMap::set_transformation_matrix (\nconst Magnum::Matrix4 & matrix\n) 

The documentation for this class was generated from the following file robot_dart/gui/magnum/gs/shadow_map.hpp

"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1ShadowMapColor/","title":"Class robot_dart::gui::magnum::ShadowMapColor","text":"

ClassList > robot_dart > gui > magnum > gs > ShadowMapColor

Inherits the following classes: Magnum::GL::AbstractShaderProgram

"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1ShadowMapColor/#public-types","title":"Public Types","text":"Type Name enum Magnum::UnsignedByte Flag typedef Magnum::Containers::EnumSet< Flag > Flags typedef Magnum::Shaders::Generic3D::Position Position typedef Magnum::Shaders::Generic3D::TextureCoordinates TextureCoordinates"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1ShadowMapColor/#public-functions","title":"Public Functions","text":"Type Name ShadowMapColor (Flags flags={}) ShadowMapColor (Magnum::NoCreateT) noexcept Flags flags () const ShadowMapColor & set_material (Material & material) ShadowMapColor & set_projection_matrix (const Magnum::Matrix4 & matrix) ShadowMapColor & set_transformation_matrix (const Magnum::Matrix4 & matrix)"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1ShadowMapColor/#public-types-documentation","title":"Public Types Documentation","text":""},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1ShadowMapColor/#enum-flag","title":"enum Flag","text":"
enum robot_dart::gui::magnum::gs::ShadowMapColor::Flag {\nDiffuseTexture = 1 << 0\n};\n
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1ShadowMapColor/#typedef-flags","title":"typedef Flags","text":"
using robot_dart::gui::magnum::gs::ShadowMapColor::Flags =  Magnum::Containers::EnumSet<Flag>;\n
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1ShadowMapColor/#typedef-position","title":"typedef Position","text":"
using robot_dart::gui::magnum::gs::ShadowMapColor::Position =  Magnum::Shaders::Generic3D::Position;\n
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1ShadowMapColor/#typedef-texturecoordinates","title":"typedef TextureCoordinates","text":"
using robot_dart::gui::magnum::gs::ShadowMapColor::TextureCoordinates =  Magnum::Shaders::Generic3D::TextureCoordinates;\n
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1ShadowMapColor/#public-functions-documentation","title":"Public Functions Documentation","text":""},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1ShadowMapColor/#function-shadowmapcolor-12","title":"function ShadowMapColor [\u00bd]","text":"
explicit robot_dart::gui::magnum::gs::ShadowMapColor::ShadowMapColor (\nFlags flags={}\n) 
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1ShadowMapColor/#function-shadowmapcolor-22","title":"function ShadowMapColor [2/2]","text":"
explicit robot_dart::gui::magnum::gs::ShadowMapColor::ShadowMapColor (\nMagnum::NoCreateT\n) noexcept\n
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1ShadowMapColor/#function-flags","title":"function flags","text":"
Flags robot_dart::gui::magnum::gs::ShadowMapColor::flags () const\n
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1ShadowMapColor/#function-set_material","title":"function set_material","text":"
ShadowMapColor & robot_dart::gui::magnum::gs::ShadowMapColor::set_material (\nMaterial & material\n) 
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1ShadowMapColor/#function-set_projection_matrix","title":"function set_projection_matrix","text":"
ShadowMapColor & robot_dart::gui::magnum::gs::ShadowMapColor::set_projection_matrix (\nconst Magnum::Matrix4 & matrix\n) 
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1ShadowMapColor/#function-set_transformation_matrix","title":"function set_transformation_matrix","text":"
ShadowMapColor & robot_dart::gui::magnum::gs::ShadowMapColor::set_transformation_matrix (\nconst Magnum::Matrix4 & matrix\n) 

The documentation for this class was generated from the following file robot_dart/gui/magnum/gs/shadow_map_color.hpp

"},{"location":"api/namespacerobot__dart_1_1gui_1_1magnum_1_1sensor/","title":"Namespace robot_dart::gui::magnum::sensor","text":"

Namespace List > robot_dart > gui > magnum > sensor

"},{"location":"api/namespacerobot__dart_1_1gui_1_1magnum_1_1sensor/#classes","title":"Classes","text":"Type Name class Camera

The documentation for this class was generated from the following file robot_dart/gui/magnum/sensor/camera.cpp

"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1sensor_1_1Camera/","title":"Class robot_dart::gui::magnum::sensor::Camera","text":"

ClassList > robot_dart > gui > magnum > sensor > Camera

Inherits the following classes: robot_dart::sensor::Sensor

"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1sensor_1_1Camera/#public-functions","title":"Public Functions","text":"Type Name Camera (BaseApplication * app, size_t width, size_t height, size_t freq=30, bool draw_debug=false) virtual void attach_to_body (dart::dynamics::BodyNode * body, const Eigen::Isometry3d & tf=Eigen::Isometry3d::Identity()) override virtual void attach_to_joint (dart::dynamics::Joint *, const Eigen::Isometry3d &) override virtual void calculate (double) override gs::Camera & camera () const gs::Camera & camera () const Eigen::Matrix4d camera_extrinsic_matrix () const Eigen::Matrix3d camera_intrinsic_matrix () const DepthImage depth_array () GrayscaleImage depth_image () void draw_debug (bool draw=true) bool drawing_debug () const Image image () virtual void init () override void look_at (const Eigen::Vector3d & camera_pos, const Eigen::Vector3d & look_at=Eigen::Vector3d(0, 0, 0), const Eigen::Vector3d & up=Eigen::Vector3d(0, 0, 1)) Magnum::Image2D * magnum_depth_image () Magnum::Image2D * magnum_image () GrayscaleImage raw_depth_image () void record_video (const std::string & video_fname) virtual std::string type () override const ~Camera ()"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1sensor_1_1Camera/#public-functions-inherited-from-robot_dartsensorsensor","title":"Public Functions inherited from robot_dart::sensor::Sensor","text":"

See robot_dart::sensor::Sensor

Type Name Sensor (size_t freq=40) void activate (bool enable=true) bool active () const virtual void attach_to_body (dart::dynamics::BodyNode * body, const Eigen::Isometry3d & tf=Eigen::Isometry3d::Identity()) void attach_to_body (const std::shared_ptr< Robot > & robot, const std::string & body_name, const Eigen::Isometry3d & tf=Eigen::Isometry3d::Identity()) virtual void attach_to_joint (dart::dynamics::Joint * joint, const Eigen::Isometry3d & tf=Eigen::Isometry3d::Identity()) void attach_to_joint (const std::shared_ptr< Robot > & robot, const std::string & joint_name, const Eigen::Isometry3d & tf=Eigen::Isometry3d::Identity()) const std::string & attached_to () const virtual void calculate (double) = 0 void detach () size_t frequency () const virtual void init () = 0 const Eigen::Isometry3d & pose () const void refresh (double t) void set_frequency (size_t freq) void set_pose (const Eigen::Isometry3d & tf) void set_simu (RobotDARTSimu * simu) const RobotDARTSimu * simu () const virtual std::string type () const = 0 virtual ~Sensor ()"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1sensor_1_1Camera/#protected-attributes","title":"Protected Attributes","text":"Type Name std::unique_ptr< gs::Camera > _camera Magnum::GL::Renderbuffer _color Magnum::GL::Renderbuffer _depth bool _draw_debug Magnum::PixelFormat _format Magnum::GL::Framebuffer _framebuffer = {Magnum::NoCreate} size_t _height BaseApplication * _magnum_app size_t _width"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1sensor_1_1Camera/#protected-attributes-inherited-from-robot_dartsensorsensor","title":"Protected Attributes inherited from robot_dart::sensor::Sensor","text":"

See robot_dart::sensor::Sensor

Type Name bool _active Eigen::Isometry3d _attached_tf bool _attached_to_body = = false bool _attached_to_joint = = false bool _attaching_to_body = = false bool _attaching_to_joint = = false dart::dynamics::BodyNode * _body_attached size_t _frequency dart::dynamics::Joint * _joint_attached RobotDARTSimu * _simu = = nullptr Eigen::Isometry3d _world_pose"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1sensor_1_1Camera/#public-functions-documentation","title":"Public Functions Documentation","text":""},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1sensor_1_1Camera/#function-camera","title":"function Camera","text":"
robot_dart::gui::magnum::sensor::Camera::Camera (\nBaseApplication * app,\nsize_t width,\nsize_t height,\nsize_t freq=30,\nbool draw_debug=false\n) 
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1sensor_1_1Camera/#function-attach_to_body","title":"function attach_to_body","text":"
virtual void robot_dart::gui::magnum::sensor::Camera::attach_to_body (\ndart::dynamics::BodyNode * body,\nconst Eigen::Isometry3d & tf=Eigen::Isometry3d::Identity()\n) override\n

Implements robot_dart::sensor::Sensor::attach_to_body

"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1sensor_1_1Camera/#function-attach_to_joint","title":"function attach_to_joint","text":"
inline virtual void robot_dart::gui::magnum::sensor::Camera::attach_to_joint (\ndart::dynamics::Joint *,\nconst Eigen::Isometry3d &\n) override\n

Implements robot_dart::sensor::Sensor::attach_to_joint

"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1sensor_1_1Camera/#function-calculate","title":"function calculate","text":"
virtual void robot_dart::gui::magnum::sensor::Camera::calculate (\ndouble\n) override\n

Implements robot_dart::sensor::Sensor::calculate

"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1sensor_1_1Camera/#function-camera-12","title":"function camera [\u00bd]","text":"
inline gs::Camera & robot_dart::gui::magnum::sensor::Camera::camera () 
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1sensor_1_1Camera/#function-camera-22","title":"function camera [2/2]","text":"
inline const gs::Camera & robot_dart::gui::magnum::sensor::Camera::camera () const\n
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1sensor_1_1Camera/#function-camera_extrinsic_matrix","title":"function camera_extrinsic_matrix","text":"
Eigen::Matrix4d robot_dart::gui::magnum::sensor::Camera::camera_extrinsic_matrix () const\n
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1sensor_1_1Camera/#function-camera_intrinsic_matrix","title":"function camera_intrinsic_matrix","text":"
Eigen::Matrix3d robot_dart::gui::magnum::sensor::Camera::camera_intrinsic_matrix () const\n
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1sensor_1_1Camera/#function-depth_array","title":"function depth_array","text":"
DepthImage robot_dart::gui::magnum::sensor::Camera::depth_array () 
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1sensor_1_1Camera/#function-depth_image","title":"function depth_image","text":"
GrayscaleImage robot_dart::gui::magnum::sensor::Camera::depth_image () 
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1sensor_1_1Camera/#function-draw_debug","title":"function draw_debug","text":"
inline void robot_dart::gui::magnum::sensor::Camera::draw_debug (\nbool draw=true\n) 
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1sensor_1_1Camera/#function-drawing_debug","title":"function drawing_debug","text":"
inline bool robot_dart::gui::magnum::sensor::Camera::drawing_debug () const\n
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1sensor_1_1Camera/#function-image","title":"function image","text":"
inline Image robot_dart::gui::magnum::sensor::Camera::image () 
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1sensor_1_1Camera/#function-init","title":"function init","text":"
virtual void robot_dart::gui::magnum::sensor::Camera::init () override\n

Implements robot_dart::sensor::Sensor::init

"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1sensor_1_1Camera/#function-look_at","title":"function look_at","text":"
void robot_dart::gui::magnum::sensor::Camera::look_at (\nconst Eigen::Vector3d & camera_pos,\nconst Eigen::Vector3d & look_at=Eigen::Vector3d(0, 0, 0),\nconst Eigen::Vector3d & up=Eigen::Vector3d(0, 0, 1)\n) 
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1sensor_1_1Camera/#function-magnum_depth_image","title":"function magnum_depth_image","text":"
inline Magnum::Image2D * robot_dart::gui::magnum::sensor::Camera::magnum_depth_image () 
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1sensor_1_1Camera/#function-magnum_image","title":"function magnum_image","text":"
inline Magnum::Image2D * robot_dart::gui::magnum::sensor::Camera::magnum_image () 
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1sensor_1_1Camera/#function-raw_depth_image","title":"function raw_depth_image","text":"
GrayscaleImage robot_dart::gui::magnum::sensor::Camera::raw_depth_image () 
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1sensor_1_1Camera/#function-record_video","title":"function record_video","text":"
inline void robot_dart::gui::magnum::sensor::Camera::record_video (\nconst std::string & video_fname\n) 
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1sensor_1_1Camera/#function-type","title":"function type","text":"
virtual std::string robot_dart::gui::magnum::sensor::Camera::type () override const\n

Implements robot_dart::sensor::Sensor::type

"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1sensor_1_1Camera/#function-camera_1","title":"function ~Camera","text":"
inline robot_dart::gui::magnum::sensor::Camera::~Camera () 
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1sensor_1_1Camera/#protected-attributes-documentation","title":"Protected Attributes Documentation","text":""},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1sensor_1_1Camera/#variable-_camera","title":"variable _camera","text":"
std::unique_ptr<gs::Camera> robot_dart::gui::magnum::sensor::Camera::_camera;\n
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1sensor_1_1Camera/#variable-_color","title":"variable _color","text":"
Magnum::GL::Renderbuffer robot_dart::gui::magnum::sensor::Camera::_color;\n
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1sensor_1_1Camera/#variable-_depth","title":"variable _depth","text":"
Magnum::GL::Renderbuffer robot_dart::gui::magnum::sensor::Camera::_depth;\n
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1sensor_1_1Camera/#variable-_draw_debug","title":"variable _draw_debug","text":"
bool robot_dart::gui::magnum::sensor::Camera::_draw_debug;\n
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1sensor_1_1Camera/#variable-_format","title":"variable _format","text":"
Magnum::PixelFormat robot_dart::gui::magnum::sensor::Camera::_format;\n
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1sensor_1_1Camera/#variable-_framebuffer","title":"variable _framebuffer","text":"
Magnum::GL::Framebuffer robot_dart::gui::magnum::sensor::Camera::_framebuffer;\n
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1sensor_1_1Camera/#variable-_height","title":"variable _height","text":"
size_t robot_dart::gui::magnum::sensor::Camera::_height;\n
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1sensor_1_1Camera/#variable-_magnum_app","title":"variable _magnum_app","text":"
BaseApplication* robot_dart::gui::magnum::sensor::Camera::_magnum_app;\n
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1sensor_1_1Camera/#variable-_width","title":"variable _width","text":"
size_t robot_dart::gui::magnum::sensor::Camera::_width;\n

The documentation for this class was generated from the following file robot_dart/gui/magnum/sensor/camera.hpp

"},{"location":"api/namespacerobot__dart_1_1robots/","title":"Namespace robot_dart::robots","text":"

Namespace List > robot_dart > robots

"},{"location":"api/namespacerobot__dart_1_1robots/#classes","title":"Classes","text":"Type Name class A1 class Arm class Franka class Hexapod class ICub class Iiwa class Pendulum class Talos datasheet: https://pal-robotics.com/wp-content/uploads/2019/07/Datasheet_TALOS.pdf __ class TalosFastCollision class TalosLight class Tiago datasheet: https://pal-robotics.com/wp-content/uploads/2021/07/Datasheet-complete_TIAGo-2021.pdf __ class Ur3e class Ur3eHand class Vx300

The documentation for this class was generated from the following file robot_dart/robots/a1.cpp

"},{"location":"api/classrobot__dart_1_1robots_1_1A1/","title":"Class robot_dart::robots::A1","text":"

ClassList > robot_dart > robots > A1

Inherits the following classes: robot_dart::Robot

"},{"location":"api/classrobot__dart_1_1robots_1_1A1/#public-functions","title":"Public Functions","text":"Type Name A1 (size_t frequency=1000, const std::string & urdf=\"unitree_a1/a1.urdf\", const std::vector< std::pair< std::string, std::string > > & packages=('a1\\_description', 'unitree\\_a1/a1\\_description')) const sensor::IMU & imu () const virtual void reset () override"},{"location":"api/classrobot__dart_1_1robots_1_1A1/#public-functions-inherited-from-robot_dartrobot","title":"Public Functions inherited from robot_dart::Robot","text":"

See robot_dart::Robot

Type Name Robot (const std::string & model_file, const std::vector< std::pair< std::string, std::string > > & packages, const std::string & robot_name=\"robot\", bool is_urdf_string=false, bool cast_shadows=true) Robot (const std::string & model_file, const std::string & robot_name=\"robot\", bool is_urdf_string=false, bool cast_shadows=true) Robot (dart::dynamics::SkeletonPtr skeleton, const std::string & robot_name=\"robot\", bool cast_shadows=true) Eigen::VectorXd acceleration_lower_limits (const std::vector< std::string > & dof_names={}) const Eigen::VectorXd acceleration_upper_limits (const std::vector< std::string > & dof_names={}) const Eigen::VectorXd accelerations (const std::vector< std::string > & dof_names={}) const std::vector< std::shared_ptr< control::RobotControl > > active_controllers () const std::string actuator_type (const std::string & joint_name) const std::vector< std::string > actuator_types (const std::vector< std::string > & joint_names={}) const void add_body_mass (const std::string & body_name, double mass) void add_body_mass (size_t body_index, double mass) void add_controller (const std::shared_ptr< control::RobotControl > & controller, double weight=1.0) void add_external_force (const std::string & body_name, const Eigen::Vector3d & force, const Eigen::Vector3d & offset=Eigen::Vector3d::Zero(), bool force_local=false, bool offset_local=true) void add_external_force (size_t body_index, const Eigen::Vector3d & force, const Eigen::Vector3d & offset=Eigen::Vector3d::Zero(), bool force_local=false, bool offset_local=true) void add_external_torque (const std::string & body_name, const Eigen::Vector3d & torque, bool local=false) void add_external_torque (size_t body_index, const Eigen::Vector3d & torque, bool local=false) bool adjacent_colliding () const Eigen::MatrixXd aug_mass_matrix (const std::vector< std::string > & dof_names={}) const Eigen::Isometry3d base_pose () const Eigen::Vector6d base_pose_vec () const Eigen::Vector6d body_acceleration (const std::string & body_name) const Eigen::Vector6d body_acceleration (size_t body_index) const size_t body_index (const std::string & body_name) const double body_mass (const std::string & body_name) const double body_mass (size_t body_index) const std::string body_name (size_t body_index) const std::vector< std::string > body_names () const dart::dynamics::BodyNode * body_node (const std::string & body_name) dart::dynamics::BodyNode * body_node (size_t body_index) Eigen::Isometry3d body_pose (const std::string & body_name) const Eigen::Isometry3d body_pose (size_t body_index) const Eigen::Vector6d body_pose_vec (const std::string & body_name) const Eigen::Vector6d body_pose_vec (size_t body_index) const Eigen::Vector6d body_velocity (const std::string & body_name) const Eigen::Vector6d body_velocity (size_t body_index) const bool cast_shadows () const void clear_controllers () void clear_external_forces () void clear_internal_forces () std::shared_ptr< Robot > clone () const std::shared_ptr< Robot > clone_ghost (const std::string & ghost_name=\"ghost\", const Eigen::Vector4d & ghost_color={0.3, 0.3, 0.3, 0.7}) const Eigen::Vector3d com () const Eigen::Vector6d com_acceleration () const Eigen::MatrixXd com_jacobian (const std::vector< std::string > & dof_names={}) const Eigen::MatrixXd com_jacobian_deriv (const std::vector< std::string > & dof_names={}) const Eigen::Vector6d com_velocity () const Eigen::VectorXd commands (const std::vector< std::string > & dof_names={}) const Eigen::VectorXd constraint_forces (const std::vector< std::string > & dof_names={}) const std::shared_ptr< control::RobotControl > controller (size_t index) const std::vector< std::shared_ptr< control::RobotControl > > controllers () const Eigen::VectorXd coriolis_forces (const std::vector< std::string > & dof_names={}) const Eigen::VectorXd coriolis_gravity_forces (const std::vector< std::string > & dof_names={}) const std::vector< double > coulomb_coeffs (const std::vector< std::string > & dof_names={}) const std::vector< double > damping_coeffs (const std::vector< std::string > & dof_names={}) const dart::dynamics::DegreeOfFreedom * dof (const std::string & dof_name) dart::dynamics::DegreeOfFreedom * dof (size_t dof_index) size_t dof_index (const std::string & dof_name) const const std::unordered_map< std::string, size_t > & dof_map () const std::string dof_name (size_t dof_index) const std::vector< std::string > dof_names (bool filter_mimics=false, bool filter_locked=false, bool filter_passive=false) const const std::vector< std::pair< dart::dynamics::BodyNode *, double > > & drawing_axes () const Eigen::Vector6d external_forces (const std::string & body_name) const Eigen::Vector6d external_forces (size_t body_index) const void fix_to_world () bool fixed () const Eigen::VectorXd force_lower_limits (const std::vector< std::string > & dof_names={}) const void force_position_bounds () std::pair< Eigen::Vector6d, Eigen::Vector6d > force_torque (size_t joint_index) const Eigen::VectorXd force_upper_limits (const std::vector< std::string > & dof_names={}) const Eigen::VectorXd forces (const std::vector< std::string > & dof_names={}) const bool free () const void free_from_world (const Eigen::Vector6d & pose=Eigen::Vector6d::Zero()) double friction_coeff (const std::string & body_name) double friction_coeff (size_t body_index) Eigen::Vector3d friction_dir (const std::string & body_name) Eigen::Vector3d friction_dir (size_t body_index) bool ghost () const Eigen::VectorXd gravity_forces (const std::vector< std::string > & dof_names={}) const Eigen::MatrixXd inv_aug_mass_matrix (const std::vector< std::string > & dof_names={}) const Eigen::MatrixXd inv_mass_matrix (const std::vector< std::string > & dof_names={}) const Eigen::MatrixXd jacobian (const std::string & body_name, const std::vector< std::string > & dof_names={}) const Eigen::MatrixXd jacobian_deriv (const std::string & body_name, const std::vector< std::string > & dof_names={}) const dart::dynamics::Joint * joint (const std::string & joint_name) dart::dynamics::Joint * joint (size_t joint_index) size_t joint_index (const std::string & joint_name) const const std::unordered_map< std::string, size_t > & joint_map () const std::string joint_name (size_t joint_index) const std::vector< std::string > joint_names () const std::vector< std::string > locked_dof_names () const Eigen::MatrixXd mass_matrix (const std::vector< std::string > & dof_names={}) const std::vector< std::string > mimic_dof_names () const const std::string & model_filename () const const std::vector< std::pair< std::string, std::string > > & model_packages () const const std::string & name () const size_t num_bodies () const size_t num_controllers () const size_t num_dofs () const size_t num_joints () const std::vector< std::string > passive_dof_names () const std::vector< bool > position_enforced (const std::vector< std::string > & dof_names={}) const Eigen::VectorXd position_lower_limits (const std::vector< std::string > & dof_names={}) const Eigen::VectorXd position_upper_limits (const std::vector< std::string > & dof_names={}) const Eigen::VectorXd positions (const std::vector< std::string > & dof_names={}) const void reinit_controllers () void remove_all_drawing_axis () void remove_controller (const std::shared_ptr< control::RobotControl > & controller) void remove_controller (size_t index) virtual void reset () void reset_commands () double restitution_coeff (const std::string & body_name) double restitution_coeff (size_t body_index) double secondary_friction_coeff (const std::string & body_name) double secondary_friction_coeff (size_t body_index) bool self_colliding () const void set_acceleration_lower_limits (const Eigen::VectorXd & accelerations, const std::vector< std::string > & dof_names={}) void set_acceleration_upper_limits (const Eigen::VectorXd & accelerations, const std::vector< std::string > & dof_names={}) void set_accelerations (const Eigen::VectorXd & accelerations, const std::vector< std::string > & dof_names={}) void set_actuator_type (const std::string & type, const std::string & joint_name, bool override_mimic=false, bool override_base=false) void set_actuator_types (const std::string & type, const std::vector< std::string > & joint_names={}, bool override_mimic=false, bool override_base=false) void set_base_pose (const Eigen::Isometry3d & tf) void set_base_pose (const Eigen::Vector6d & pose) set base pose: pose is a 6D vector (first 3D orientation in angle-axis and last 3D translation) void set_body_mass (const std::string & body_name, double mass) void set_body_mass (size_t body_index, double mass) void set_body_name (size_t body_index, const std::string & body_name) void set_cast_shadows (bool cast_shadows=true) void set_color_mode (const std::string & color_mode) void set_color_mode (const std::string & color_mode, const std::string & body_name) void set_commands (const Eigen::VectorXd & commands, const std::vector< std::string > & dof_names={}) void set_coulomb_coeffs (const std::vector< double > & cfrictions, const std::vector< std::string > & dof_names={}) void set_coulomb_coeffs (double cfriction, const std::vector< std::string > & dof_names={}) void set_damping_coeffs (const std::vector< double > & damps, const std::vector< std::string > & dof_names={}) void set_damping_coeffs (double damp, const std::vector< std::string > & dof_names={}) void set_draw_axis (const std::string & body_name, double size=0.25) void set_external_force (const std::string & body_name, const Eigen::Vector3d & force, const Eigen::Vector3d & offset=Eigen::Vector3d::Zero(), bool force_local=false, bool offset_local=true) void set_external_force (size_t body_index, const Eigen::Vector3d & force, const Eigen::Vector3d & offset=Eigen::Vector3d::Zero(), bool force_local=false, bool offset_local=true) void set_external_torque (const std::string & body_name, const Eigen::Vector3d & torque, bool local=false) void set_external_torque (size_t body_index, const Eigen::Vector3d & torque, bool local=false) void set_force_lower_limits (const Eigen::VectorXd & forces, const std::vector< std::string > & dof_names={}) void set_force_upper_limits (const Eigen::VectorXd & forces, const std::vector< std::string > & dof_names={}) void set_forces (const Eigen::VectorXd & forces, const std::vector< std::string > & dof_names={}) void set_friction_coeff (const std::string & body_name, double value) void set_friction_coeff (size_t body_index, double value) void set_friction_coeffs (double value) void set_friction_dir (const std::string & body_name, const Eigen::Vector3d & direction) void set_friction_dir (size_t body_index, const Eigen::Vector3d & direction) void set_ghost (bool ghost=true) void set_joint_name (size_t joint_index, const std::string & joint_name) void set_mimic (const std::string & joint_name, const std::string & mimic_joint_name, double multiplier=1., double offset=0.) void set_position_enforced (const std::vector< bool > & enforced, const std::vector< std::string > & dof_names={}) void set_position_enforced (bool enforced, const std::vector< std::string > & dof_names={}) void set_position_lower_limits (const Eigen::VectorXd & positions, const std::vector< std::string > & dof_names={}) void set_position_upper_limits (const Eigen::VectorXd & positions, const std::vector< std::string > & dof_names={}) void set_positions (const Eigen::VectorXd & positions, const std::vector< std::string > & dof_names={}) void set_restitution_coeff (const std::string & body_name, double value) void set_restitution_coeff (size_t body_index, double value) void set_restitution_coeffs (double value) void set_secondary_friction_coeff (const std::string & body_name, double value) void set_secondary_friction_coeff (size_t body_index, double value) void set_secondary_friction_coeffs (double value) void set_self_collision (bool enable_self_collisions=true, bool enable_adjacent_collisions=false) void set_spring_stiffnesses (const std::vector< double > & stiffnesses, const std::vector< std::string > & dof_names={}) void set_spring_stiffnesses (double stiffness, const std::vector< std::string > & dof_names={}) void set_velocities (const Eigen::VectorXd & velocities, const std::vector< std::string > & dof_names={}) void set_velocity_lower_limits (const Eigen::VectorXd & velocities, const std::vector< std::string > & dof_names={}) void set_velocity_upper_limits (const Eigen::VectorXd & velocities, const std::vector< std::string > & dof_names={}) dart::dynamics::SkeletonPtr skeleton () std::vector< double > spring_stiffnesses (const std::vector< std::string > & dof_names={}) const void update (double t) void update_joint_dof_maps () Eigen::VectorXd vec_dof (const Eigen::VectorXd & vec, const std::vector< std::string > & dof_names) const Eigen::VectorXd velocities (const std::vector< std::string > & dof_names={}) const Eigen::VectorXd velocity_lower_limits (const std::vector< std::string > & dof_names={}) const Eigen::VectorXd velocity_upper_limits (const std::vector< std::string > & dof_names={}) const virtual ~Robot ()"},{"location":"api/classrobot__dart_1_1robots_1_1A1/#public-static-functions-inherited-from-robot_dartrobot","title":"Public Static Functions inherited from robot_dart::Robot","text":"

See robot_dart::Robot

Type Name std::shared_ptr< Robot > create_box (const Eigen::Vector3d & dims, const Eigen::Isometry3d & tf, const std::string & type=\"free\", double mass=1.0, const Eigen::Vector4d & color=dart::Color::Red(1.0), const std::string & box_name=\"box\") std::shared_ptr< Robot > create_box (const Eigen::Vector3d & dims, const Eigen::Vector6d & pose=Eigen::Vector6d::Zero(), const std::string & type=\"free\", double mass=1.0, const Eigen::Vector4d & color=dart::Color::Red(1.0), const std::string & box_name=\"box\") std::shared_ptr< Robot > create_ellipsoid (const Eigen::Vector3d & dims, const Eigen::Isometry3d & tf, const std::string & type=\"free\", double mass=1.0, const Eigen::Vector4d & color=dart::Color::Red(1.0), const std::string & ellipsoid_name=\"ellipsoid\") std::shared_ptr< Robot > create_ellipsoid (const Eigen::Vector3d & dims, const Eigen::Vector6d & pose=Eigen::Vector6d::Zero(), const std::string & type=\"free\", double mass=1.0, const Eigen::Vector4d & color=dart::Color::Red(1.0), const std::string & ellipsoid_name=\"ellipsoid\")"},{"location":"api/classrobot__dart_1_1robots_1_1A1/#protected-attributes","title":"Protected Attributes","text":"Type Name std::shared_ptr< sensor::IMU > _imu"},{"location":"api/classrobot__dart_1_1robots_1_1A1/#protected-attributes-inherited-from-robot_dartrobot","title":"Protected Attributes inherited from robot_dart::Robot","text":"

See robot_dart::Robot

Type Name std::vector< std::pair< dart::dynamics::BodyNode *, double > > _axis_shapes bool _cast_shadows std::vector< std::shared_ptr< control::RobotControl > > _controllers std::unordered_map< std::string, size_t > _dof_map bool _is_ghost std::unordered_map< std::string, size_t > _joint_map std::string _model_filename std::vector< std::pair< std::string, std::string > > _packages std::string _robot_name dart::dynamics::SkeletonPtr _skeleton"},{"location":"api/classrobot__dart_1_1robots_1_1A1/#protected-functions-inherited-from-robot_dartrobot","title":"Protected Functions inherited from robot_dart::Robot","text":"

See robot_dart::Robot

Type Name dart::dynamics::Joint::ActuatorType _actuator_type (size_t joint_index) const std::vector< dart::dynamics::Joint::ActuatorType > _actuator_types () const std::string _get_path (const std::string & filename) const Eigen::MatrixXd _jacobian (const Eigen::MatrixXd & full_jacobian, const std::vector< std::string > & dof_names) const dart::dynamics::SkeletonPtr _load_model (const std::string & filename, const std::vector< std::pair< std::string, std::string > > & packages=std::vector< std::pair< std::string, std::string > >(), bool is_urdf_string=false) Eigen::MatrixXd _mass_matrix (const Eigen::MatrixXd & full_mass_matrix, const std::vector< std::string > & dof_names) const virtual void _post_addition (RobotDARTSimu *) Function called by RobotDARTSimu object when adding the robot to the world. virtual void _post_removal (RobotDARTSimu *) Function called by RobotDARTSimu object when removing the robot to the world. void _set_actuator_type (size_t joint_index, dart::dynamics::Joint::ActuatorType type, bool override_mimic=false, bool override_base=false) void _set_actuator_types (const std::vector< dart::dynamics::Joint::ActuatorType > & types, bool override_mimic=false, bool override_base=false) void _set_actuator_types (dart::dynamics::Joint::ActuatorType type, bool override_mimic=false, bool override_base=false) void _set_color_mode (dart::dynamics::MeshShape::ColorMode color_mode, dart::dynamics::SkeletonPtr skel) void _set_color_mode (dart::dynamics::MeshShape::ColorMode color_mode, dart::dynamics::ShapeNode * sn)"},{"location":"api/classrobot__dart_1_1robots_1_1A1/#public-functions-documentation","title":"Public Functions Documentation","text":""},{"location":"api/classrobot__dart_1_1robots_1_1A1/#function-a1","title":"function A1","text":"
robot_dart::robots::A1::A1 (\nsize_t frequency=1000,\nconst std::string & urdf=\"unitree_a1/a1.urdf\",\nconst std::vector< std::pair< std::string, std::string > > & packages=('a1_description', 'unitree_a1/a1_description')\n) 
"},{"location":"api/classrobot__dart_1_1robots_1_1A1/#function-imu","title":"function imu","text":"
inline const sensor::IMU & robot_dart::robots::A1::imu () const\n
"},{"location":"api/classrobot__dart_1_1robots_1_1A1/#function-reset","title":"function reset","text":"
virtual void robot_dart::robots::A1::reset () override\n

Implements robot_dart::Robot::reset

"},{"location":"api/classrobot__dart_1_1robots_1_1A1/#protected-attributes-documentation","title":"Protected Attributes Documentation","text":""},{"location":"api/classrobot__dart_1_1robots_1_1A1/#variable-_imu","title":"variable _imu","text":"
std::shared_ptr<sensor::IMU> robot_dart::robots::A1::_imu;\n

The documentation for this class was generated from the following file robot_dart/robots/a1.hpp

"},{"location":"api/classrobot__dart_1_1robots_1_1Arm/","title":"Class robot_dart::robots::Arm","text":"

ClassList > robot_dart > robots > Arm

Inherits the following classes: robot_dart::Robot

"},{"location":"api/classrobot__dart_1_1robots_1_1Arm/#public-functions","title":"Public Functions","text":"Type Name Arm (const std::string & urdf=\"arm.urdf\")"},{"location":"api/classrobot__dart_1_1robots_1_1Arm/#public-functions-inherited-from-robot_dartrobot","title":"Public Functions inherited from robot_dart::Robot","text":"

See robot_dart::Robot

Type Name Robot (const std::string & model_file, const std::vector< std::pair< std::string, std::string > > & packages, const std::string & robot_name=\"robot\", bool is_urdf_string=false, bool cast_shadows=true) Robot (const std::string & model_file, const std::string & robot_name=\"robot\", bool is_urdf_string=false, bool cast_shadows=true) Robot (dart::dynamics::SkeletonPtr skeleton, const std::string & robot_name=\"robot\", bool cast_shadows=true) Eigen::VectorXd acceleration_lower_limits (const std::vector< std::string > & dof_names={}) const Eigen::VectorXd acceleration_upper_limits (const std::vector< std::string > & dof_names={}) const Eigen::VectorXd accelerations (const std::vector< std::string > & dof_names={}) const std::vector< std::shared_ptr< control::RobotControl > > active_controllers () const std::string actuator_type (const std::string & joint_name) const std::vector< std::string > actuator_types (const std::vector< std::string > & joint_names={}) const void add_body_mass (const std::string & body_name, double mass) void add_body_mass (size_t body_index, double mass) void add_controller (const std::shared_ptr< control::RobotControl > & controller, double weight=1.0) void add_external_force (const std::string & body_name, const Eigen::Vector3d & force, const Eigen::Vector3d & offset=Eigen::Vector3d::Zero(), bool force_local=false, bool offset_local=true) void add_external_force (size_t body_index, const Eigen::Vector3d & force, const Eigen::Vector3d & offset=Eigen::Vector3d::Zero(), bool force_local=false, bool offset_local=true) void add_external_torque (const std::string & body_name, const Eigen::Vector3d & torque, bool local=false) void add_external_torque (size_t body_index, const Eigen::Vector3d & torque, bool local=false) bool adjacent_colliding () const Eigen::MatrixXd aug_mass_matrix (const std::vector< std::string > & dof_names={}) const Eigen::Isometry3d base_pose () const Eigen::Vector6d base_pose_vec () const Eigen::Vector6d body_acceleration (const std::string & body_name) const Eigen::Vector6d body_acceleration (size_t body_index) const size_t body_index (const std::string & body_name) const double body_mass (const std::string & body_name) const double body_mass (size_t body_index) const std::string body_name (size_t body_index) const std::vector< std::string > body_names () const dart::dynamics::BodyNode * body_node (const std::string & body_name) dart::dynamics::BodyNode * body_node (size_t body_index) Eigen::Isometry3d body_pose (const std::string & body_name) const Eigen::Isometry3d body_pose (size_t body_index) const Eigen::Vector6d body_pose_vec (const std::string & body_name) const Eigen::Vector6d body_pose_vec (size_t body_index) const Eigen::Vector6d body_velocity (const std::string & body_name) const Eigen::Vector6d body_velocity (size_t body_index) const bool cast_shadows () const void clear_controllers () void clear_external_forces () void clear_internal_forces () std::shared_ptr< Robot > clone () const std::shared_ptr< Robot > clone_ghost (const std::string & ghost_name=\"ghost\", const Eigen::Vector4d & ghost_color={0.3, 0.3, 0.3, 0.7}) const Eigen::Vector3d com () const Eigen::Vector6d com_acceleration () const Eigen::MatrixXd com_jacobian (const std::vector< std::string > & dof_names={}) const Eigen::MatrixXd com_jacobian_deriv (const std::vector< std::string > & dof_names={}) const Eigen::Vector6d com_velocity () const Eigen::VectorXd commands (const std::vector< std::string > & dof_names={}) const Eigen::VectorXd constraint_forces (const std::vector< std::string > & dof_names={}) const std::shared_ptr< control::RobotControl > controller (size_t index) const std::vector< std::shared_ptr< control::RobotControl > > controllers () const Eigen::VectorXd coriolis_forces (const std::vector< std::string > & dof_names={}) const Eigen::VectorXd coriolis_gravity_forces (const std::vector< std::string > & dof_names={}) const std::vector< double > coulomb_coeffs (const std::vector< std::string > & dof_names={}) const std::vector< double > damping_coeffs (const std::vector< std::string > & dof_names={}) const dart::dynamics::DegreeOfFreedom * dof (const std::string & dof_name) dart::dynamics::DegreeOfFreedom * dof (size_t dof_index) size_t dof_index (const std::string & dof_name) const const std::unordered_map< std::string, size_t > & dof_map () const std::string dof_name (size_t dof_index) const std::vector< std::string > dof_names (bool filter_mimics=false, bool filter_locked=false, bool filter_passive=false) const const std::vector< std::pair< dart::dynamics::BodyNode *, double > > & drawing_axes () const Eigen::Vector6d external_forces (const std::string & body_name) const Eigen::Vector6d external_forces (size_t body_index) const void fix_to_world () bool fixed () const Eigen::VectorXd force_lower_limits (const std::vector< std::string > & dof_names={}) const void force_position_bounds () std::pair< Eigen::Vector6d, Eigen::Vector6d > force_torque (size_t joint_index) const Eigen::VectorXd force_upper_limits (const std::vector< std::string > & dof_names={}) const Eigen::VectorXd forces (const std::vector< std::string > & dof_names={}) const bool free () const void free_from_world (const Eigen::Vector6d & pose=Eigen::Vector6d::Zero()) double friction_coeff (const std::string & body_name) double friction_coeff (size_t body_index) Eigen::Vector3d friction_dir (const std::string & body_name) Eigen::Vector3d friction_dir (size_t body_index) bool ghost () const Eigen::VectorXd gravity_forces (const std::vector< std::string > & dof_names={}) const Eigen::MatrixXd inv_aug_mass_matrix (const std::vector< std::string > & dof_names={}) const Eigen::MatrixXd inv_mass_matrix (const std::vector< std::string > & dof_names={}) const Eigen::MatrixXd jacobian (const std::string & body_name, const std::vector< std::string > & dof_names={}) const Eigen::MatrixXd jacobian_deriv (const std::string & body_name, const std::vector< std::string > & dof_names={}) const dart::dynamics::Joint * joint (const std::string & joint_name) dart::dynamics::Joint * joint (size_t joint_index) size_t joint_index (const std::string & joint_name) const const std::unordered_map< std::string, size_t > & joint_map () const std::string joint_name (size_t joint_index) const std::vector< std::string > joint_names () const std::vector< std::string > locked_dof_names () const Eigen::MatrixXd mass_matrix (const std::vector< std::string > & dof_names={}) const std::vector< std::string > mimic_dof_names () const const std::string & model_filename () const const std::vector< std::pair< std::string, std::string > > & model_packages () const const std::string & name () const size_t num_bodies () const size_t num_controllers () const size_t num_dofs () const size_t num_joints () const std::vector< std::string > passive_dof_names () const std::vector< bool > position_enforced (const std::vector< std::string > & dof_names={}) const Eigen::VectorXd position_lower_limits (const std::vector< std::string > & dof_names={}) const Eigen::VectorXd position_upper_limits (const std::vector< std::string > & dof_names={}) const Eigen::VectorXd positions (const std::vector< std::string > & dof_names={}) const void reinit_controllers () void remove_all_drawing_axis () void remove_controller (const std::shared_ptr< control::RobotControl > & controller) void remove_controller (size_t index) virtual void reset () void reset_commands () double restitution_coeff (const std::string & body_name) double restitution_coeff (size_t body_index) double secondary_friction_coeff (const std::string & body_name) double secondary_friction_coeff (size_t body_index) bool self_colliding () const void set_acceleration_lower_limits (const Eigen::VectorXd & accelerations, const std::vector< std::string > & dof_names={}) void set_acceleration_upper_limits (const Eigen::VectorXd & accelerations, const std::vector< std::string > & dof_names={}) void set_accelerations (const Eigen::VectorXd & accelerations, const std::vector< std::string > & dof_names={}) void set_actuator_type (const std::string & type, const std::string & joint_name, bool override_mimic=false, bool override_base=false) void set_actuator_types (const std::string & type, const std::vector< std::string > & joint_names={}, bool override_mimic=false, bool override_base=false) void set_base_pose (const Eigen::Isometry3d & tf) void set_base_pose (const Eigen::Vector6d & pose) set base pose: pose is a 6D vector (first 3D orientation in angle-axis and last 3D translation) void set_body_mass (const std::string & body_name, double mass) void set_body_mass (size_t body_index, double mass) void set_body_name (size_t body_index, const std::string & body_name) void set_cast_shadows (bool cast_shadows=true) void set_color_mode (const std::string & color_mode) void set_color_mode (const std::string & color_mode, const std::string & body_name) void set_commands (const Eigen::VectorXd & commands, const std::vector< std::string > & dof_names={}) void set_coulomb_coeffs (const std::vector< double > & cfrictions, const std::vector< std::string > & dof_names={}) void set_coulomb_coeffs (double cfriction, const std::vector< std::string > & dof_names={}) void set_damping_coeffs (const std::vector< double > & damps, const std::vector< std::string > & dof_names={}) void set_damping_coeffs (double damp, const std::vector< std::string > & dof_names={}) void set_draw_axis (const std::string & body_name, double size=0.25) void set_external_force (const std::string & body_name, const Eigen::Vector3d & force, const Eigen::Vector3d & offset=Eigen::Vector3d::Zero(), bool force_local=false, bool offset_local=true) void set_external_force (size_t body_index, const Eigen::Vector3d & force, const Eigen::Vector3d & offset=Eigen::Vector3d::Zero(), bool force_local=false, bool offset_local=true) void set_external_torque (const std::string & body_name, const Eigen::Vector3d & torque, bool local=false) void set_external_torque (size_t body_index, const Eigen::Vector3d & torque, bool local=false) void set_force_lower_limits (const Eigen::VectorXd & forces, const std::vector< std::string > & dof_names={}) void set_force_upper_limits (const Eigen::VectorXd & forces, const std::vector< std::string > & dof_names={}) void set_forces (const Eigen::VectorXd & forces, const std::vector< std::string > & dof_names={}) void set_friction_coeff (const std::string & body_name, double value) void set_friction_coeff (size_t body_index, double value) void set_friction_coeffs (double value) void set_friction_dir (const std::string & body_name, const Eigen::Vector3d & direction) void set_friction_dir (size_t body_index, const Eigen::Vector3d & direction) void set_ghost (bool ghost=true) void set_joint_name (size_t joint_index, const std::string & joint_name) void set_mimic (const std::string & joint_name, const std::string & mimic_joint_name, double multiplier=1., double offset=0.) void set_position_enforced (const std::vector< bool > & enforced, const std::vector< std::string > & dof_names={}) void set_position_enforced (bool enforced, const std::vector< std::string > & dof_names={}) void set_position_lower_limits (const Eigen::VectorXd & positions, const std::vector< std::string > & dof_names={}) void set_position_upper_limits (const Eigen::VectorXd & positions, const std::vector< std::string > & dof_names={}) void set_positions (const Eigen::VectorXd & positions, const std::vector< std::string > & dof_names={}) void set_restitution_coeff (const std::string & body_name, double value) void set_restitution_coeff (size_t body_index, double value) void set_restitution_coeffs (double value) void set_secondary_friction_coeff (const std::string & body_name, double value) void set_secondary_friction_coeff (size_t body_index, double value) void set_secondary_friction_coeffs (double value) void set_self_collision (bool enable_self_collisions=true, bool enable_adjacent_collisions=false) void set_spring_stiffnesses (const std::vector< double > & stiffnesses, const std::vector< std::string > & dof_names={}) void set_spring_stiffnesses (double stiffness, const std::vector< std::string > & dof_names={}) void set_velocities (const Eigen::VectorXd & velocities, const std::vector< std::string > & dof_names={}) void set_velocity_lower_limits (const Eigen::VectorXd & velocities, const std::vector< std::string > & dof_names={}) void set_velocity_upper_limits (const Eigen::VectorXd & velocities, const std::vector< std::string > & dof_names={}) dart::dynamics::SkeletonPtr skeleton () std::vector< double > spring_stiffnesses (const std::vector< std::string > & dof_names={}) const void update (double t) void update_joint_dof_maps () Eigen::VectorXd vec_dof (const Eigen::VectorXd & vec, const std::vector< std::string > & dof_names) const Eigen::VectorXd velocities (const std::vector< std::string > & dof_names={}) const Eigen::VectorXd velocity_lower_limits (const std::vector< std::string > & dof_names={}) const Eigen::VectorXd velocity_upper_limits (const std::vector< std::string > & dof_names={}) const virtual ~Robot ()"},{"location":"api/classrobot__dart_1_1robots_1_1Arm/#public-static-functions-inherited-from-robot_dartrobot","title":"Public Static Functions inherited from robot_dart::Robot","text":"

See robot_dart::Robot

Type Name std::shared_ptr< Robot > create_box (const Eigen::Vector3d & dims, const Eigen::Isometry3d & tf, const std::string & type=\"free\", double mass=1.0, const Eigen::Vector4d & color=dart::Color::Red(1.0), const std::string & box_name=\"box\") std::shared_ptr< Robot > create_box (const Eigen::Vector3d & dims, const Eigen::Vector6d & pose=Eigen::Vector6d::Zero(), const std::string & type=\"free\", double mass=1.0, const Eigen::Vector4d & color=dart::Color::Red(1.0), const std::string & box_name=\"box\") std::shared_ptr< Robot > create_ellipsoid (const Eigen::Vector3d & dims, const Eigen::Isometry3d & tf, const std::string & type=\"free\", double mass=1.0, const Eigen::Vector4d & color=dart::Color::Red(1.0), const std::string & ellipsoid_name=\"ellipsoid\") std::shared_ptr< Robot > create_ellipsoid (const Eigen::Vector3d & dims, const Eigen::Vector6d & pose=Eigen::Vector6d::Zero(), const std::string & type=\"free\", double mass=1.0, const Eigen::Vector4d & color=dart::Color::Red(1.0), const std::string & ellipsoid_name=\"ellipsoid\")"},{"location":"api/classrobot__dart_1_1robots_1_1Arm/#protected-attributes-inherited-from-robot_dartrobot","title":"Protected Attributes inherited from robot_dart::Robot","text":"

See robot_dart::Robot

Type Name std::vector< std::pair< dart::dynamics::BodyNode *, double > > _axis_shapes bool _cast_shadows std::vector< std::shared_ptr< control::RobotControl > > _controllers std::unordered_map< std::string, size_t > _dof_map bool _is_ghost std::unordered_map< std::string, size_t > _joint_map std::string _model_filename std::vector< std::pair< std::string, std::string > > _packages std::string _robot_name dart::dynamics::SkeletonPtr _skeleton"},{"location":"api/classrobot__dart_1_1robots_1_1Arm/#protected-functions-inherited-from-robot_dartrobot","title":"Protected Functions inherited from robot_dart::Robot","text":"

See robot_dart::Robot

Type Name dart::dynamics::Joint::ActuatorType _actuator_type (size_t joint_index) const std::vector< dart::dynamics::Joint::ActuatorType > _actuator_types () const std::string _get_path (const std::string & filename) const Eigen::MatrixXd _jacobian (const Eigen::MatrixXd & full_jacobian, const std::vector< std::string > & dof_names) const dart::dynamics::SkeletonPtr _load_model (const std::string & filename, const std::vector< std::pair< std::string, std::string > > & packages=std::vector< std::pair< std::string, std::string > >(), bool is_urdf_string=false) Eigen::MatrixXd _mass_matrix (const Eigen::MatrixXd & full_mass_matrix, const std::vector< std::string > & dof_names) const virtual void _post_addition (RobotDARTSimu *) Function called by RobotDARTSimu object when adding the robot to the world. virtual void _post_removal (RobotDARTSimu *) Function called by RobotDARTSimu object when removing the robot to the world. void _set_actuator_type (size_t joint_index, dart::dynamics::Joint::ActuatorType type, bool override_mimic=false, bool override_base=false) void _set_actuator_types (const std::vector< dart::dynamics::Joint::ActuatorType > & types, bool override_mimic=false, bool override_base=false) void _set_actuator_types (dart::dynamics::Joint::ActuatorType type, bool override_mimic=false, bool override_base=false) void _set_color_mode (dart::dynamics::MeshShape::ColorMode color_mode, dart::dynamics::SkeletonPtr skel) void _set_color_mode (dart::dynamics::MeshShape::ColorMode color_mode, dart::dynamics::ShapeNode * sn)"},{"location":"api/classrobot__dart_1_1robots_1_1Arm/#public-functions-documentation","title":"Public Functions Documentation","text":""},{"location":"api/classrobot__dart_1_1robots_1_1Arm/#function-arm","title":"function Arm","text":"
inline robot_dart::robots::Arm::Arm (\nconst std::string & urdf=\"arm.urdf\"\n) 

The documentation for this class was generated from the following file robot_dart/robots/arm.hpp

"},{"location":"api/classrobot__dart_1_1robots_1_1Franka/","title":"Class robot_dart::robots::Franka","text":"

ClassList > robot_dart > robots > Franka

Inherits the following classes: robot_dart::Robot

"},{"location":"api/classrobot__dart_1_1robots_1_1Franka/#public-functions","title":"Public Functions","text":"Type Name Franka (size_t frequency=1000, const std::string & urdf=\"franka/franka.urdf\", const std::vector< std::pair< std::string, std::string > > & packages=('franka\\_description', 'franka/franka\\_description')) const sensor::ForceTorque & ft_wrist () const"},{"location":"api/classrobot__dart_1_1robots_1_1Franka/#public-functions-inherited-from-robot_dartrobot","title":"Public Functions inherited from robot_dart::Robot","text":"

See robot_dart::Robot

Type Name Robot (const std::string & model_file, const std::vector< std::pair< std::string, std::string > > & packages, const std::string & robot_name=\"robot\", bool is_urdf_string=false, bool cast_shadows=true) Robot (const std::string & model_file, const std::string & robot_name=\"robot\", bool is_urdf_string=false, bool cast_shadows=true) Robot (dart::dynamics::SkeletonPtr skeleton, const std::string & robot_name=\"robot\", bool cast_shadows=true) Eigen::VectorXd acceleration_lower_limits (const std::vector< std::string > & dof_names={}) const Eigen::VectorXd acceleration_upper_limits (const std::vector< std::string > & dof_names={}) const Eigen::VectorXd accelerations (const std::vector< std::string > & dof_names={}) const std::vector< std::shared_ptr< control::RobotControl > > active_controllers () const std::string actuator_type (const std::string & joint_name) const std::vector< std::string > actuator_types (const std::vector< std::string > & joint_names={}) const void add_body_mass (const std::string & body_name, double mass) void add_body_mass (size_t body_index, double mass) void add_controller (const std::shared_ptr< control::RobotControl > & controller, double weight=1.0) void add_external_force (const std::string & body_name, const Eigen::Vector3d & force, const Eigen::Vector3d & offset=Eigen::Vector3d::Zero(), bool force_local=false, bool offset_local=true) void add_external_force (size_t body_index, const Eigen::Vector3d & force, const Eigen::Vector3d & offset=Eigen::Vector3d::Zero(), bool force_local=false, bool offset_local=true) void add_external_torque (const std::string & body_name, const Eigen::Vector3d & torque, bool local=false) void add_external_torque (size_t body_index, const Eigen::Vector3d & torque, bool local=false) bool adjacent_colliding () const Eigen::MatrixXd aug_mass_matrix (const std::vector< std::string > & dof_names={}) const Eigen::Isometry3d base_pose () const Eigen::Vector6d base_pose_vec () const Eigen::Vector6d body_acceleration (const std::string & body_name) const Eigen::Vector6d body_acceleration (size_t body_index) const size_t body_index (const std::string & body_name) const double body_mass (const std::string & body_name) const double body_mass (size_t body_index) const std::string body_name (size_t body_index) const std::vector< std::string > body_names () const dart::dynamics::BodyNode * body_node (const std::string & body_name) dart::dynamics::BodyNode * body_node (size_t body_index) Eigen::Isometry3d body_pose (const std::string & body_name) const Eigen::Isometry3d body_pose (size_t body_index) const Eigen::Vector6d body_pose_vec (const std::string & body_name) const Eigen::Vector6d body_pose_vec (size_t body_index) const Eigen::Vector6d body_velocity (const std::string & body_name) const Eigen::Vector6d body_velocity (size_t body_index) const bool cast_shadows () const void clear_controllers () void clear_external_forces () void clear_internal_forces () std::shared_ptr< Robot > clone () const std::shared_ptr< Robot > clone_ghost (const std::string & ghost_name=\"ghost\", const Eigen::Vector4d & ghost_color={0.3, 0.3, 0.3, 0.7}) const Eigen::Vector3d com () const Eigen::Vector6d com_acceleration () const Eigen::MatrixXd com_jacobian (const std::vector< std::string > & dof_names={}) const Eigen::MatrixXd com_jacobian_deriv (const std::vector< std::string > & dof_names={}) const Eigen::Vector6d com_velocity () const Eigen::VectorXd commands (const std::vector< std::string > & dof_names={}) const Eigen::VectorXd constraint_forces (const std::vector< std::string > & dof_names={}) const std::shared_ptr< control::RobotControl > controller (size_t index) const std::vector< std::shared_ptr< control::RobotControl > > controllers () const Eigen::VectorXd coriolis_forces (const std::vector< std::string > & dof_names={}) const Eigen::VectorXd coriolis_gravity_forces (const std::vector< std::string > & dof_names={}) const std::vector< double > coulomb_coeffs (const std::vector< std::string > & dof_names={}) const std::vector< double > damping_coeffs (const std::vector< std::string > & dof_names={}) const dart::dynamics::DegreeOfFreedom * dof (const std::string & dof_name) dart::dynamics::DegreeOfFreedom * dof (size_t dof_index) size_t dof_index (const std::string & dof_name) const const std::unordered_map< std::string, size_t > & dof_map () const std::string dof_name (size_t dof_index) const std::vector< std::string > dof_names (bool filter_mimics=false, bool filter_locked=false, bool filter_passive=false) const const std::vector< std::pair< dart::dynamics::BodyNode *, double > > & drawing_axes () const Eigen::Vector6d external_forces (const std::string & body_name) const Eigen::Vector6d external_forces (size_t body_index) const void fix_to_world () bool fixed () const Eigen::VectorXd force_lower_limits (const std::vector< std::string > & dof_names={}) const void force_position_bounds () std::pair< Eigen::Vector6d, Eigen::Vector6d > force_torque (size_t joint_index) const Eigen::VectorXd force_upper_limits (const std::vector< std::string > & dof_names={}) const Eigen::VectorXd forces (const std::vector< std::string > & dof_names={}) const bool free () const void free_from_world (const Eigen::Vector6d & pose=Eigen::Vector6d::Zero()) double friction_coeff (const std::string & body_name) double friction_coeff (size_t body_index) Eigen::Vector3d friction_dir (const std::string & body_name) Eigen::Vector3d friction_dir (size_t body_index) bool ghost () const Eigen::VectorXd gravity_forces (const std::vector< std::string > & dof_names={}) const Eigen::MatrixXd inv_aug_mass_matrix (const std::vector< std::string > & dof_names={}) const Eigen::MatrixXd inv_mass_matrix (const std::vector< std::string > & dof_names={}) const Eigen::MatrixXd jacobian (const std::string & body_name, const std::vector< std::string > & dof_names={}) const Eigen::MatrixXd jacobian_deriv (const std::string & body_name, const std::vector< std::string > & dof_names={}) const dart::dynamics::Joint * joint (const std::string & joint_name) dart::dynamics::Joint * joint (size_t joint_index) size_t joint_index (const std::string & joint_name) const const std::unordered_map< std::string, size_t > & joint_map () const std::string joint_name (size_t joint_index) const std::vector< std::string > joint_names () const std::vector< std::string > locked_dof_names () const Eigen::MatrixXd mass_matrix (const std::vector< std::string > & dof_names={}) const std::vector< std::string > mimic_dof_names () const const std::string & model_filename () const const std::vector< std::pair< std::string, std::string > > & model_packages () const const std::string & name () const size_t num_bodies () const size_t num_controllers () const size_t num_dofs () const size_t num_joints () const std::vector< std::string > passive_dof_names () const std::vector< bool > position_enforced (const std::vector< std::string > & dof_names={}) const Eigen::VectorXd position_lower_limits (const std::vector< std::string > & dof_names={}) const Eigen::VectorXd position_upper_limits (const std::vector< std::string > & dof_names={}) const Eigen::VectorXd positions (const std::vector< std::string > & dof_names={}) const void reinit_controllers () void remove_all_drawing_axis () void remove_controller (const std::shared_ptr< control::RobotControl > & controller) void remove_controller (size_t index) virtual void reset () void reset_commands () double restitution_coeff (const std::string & body_name) double restitution_coeff (size_t body_index) double secondary_friction_coeff (const std::string & body_name) double secondary_friction_coeff (size_t body_index) bool self_colliding () const void set_acceleration_lower_limits (const Eigen::VectorXd & accelerations, const std::vector< std::string > & dof_names={}) void set_acceleration_upper_limits (const Eigen::VectorXd & accelerations, const std::vector< std::string > & dof_names={}) void set_accelerations (const Eigen::VectorXd & accelerations, const std::vector< std::string > & dof_names={}) void set_actuator_type (const std::string & type, const std::string & joint_name, bool override_mimic=false, bool override_base=false) void set_actuator_types (const std::string & type, const std::vector< std::string > & joint_names={}, bool override_mimic=false, bool override_base=false) void set_base_pose (const Eigen::Isometry3d & tf) void set_base_pose (const Eigen::Vector6d & pose) set base pose: pose is a 6D vector (first 3D orientation in angle-axis and last 3D translation) void set_body_mass (const std::string & body_name, double mass) void set_body_mass (size_t body_index, double mass) void set_body_name (size_t body_index, const std::string & body_name) void set_cast_shadows (bool cast_shadows=true) void set_color_mode (const std::string & color_mode) void set_color_mode (const std::string & color_mode, const std::string & body_name) void set_commands (const Eigen::VectorXd & commands, const std::vector< std::string > & dof_names={}) void set_coulomb_coeffs (const std::vector< double > & cfrictions, const std::vector< std::string > & dof_names={}) void set_coulomb_coeffs (double cfriction, const std::vector< std::string > & dof_names={}) void set_damping_coeffs (const std::vector< double > & damps, const std::vector< std::string > & dof_names={}) void set_damping_coeffs (double damp, const std::vector< std::string > & dof_names={}) void set_draw_axis (const std::string & body_name, double size=0.25) void set_external_force (const std::string & body_name, const Eigen::Vector3d & force, const Eigen::Vector3d & offset=Eigen::Vector3d::Zero(), bool force_local=false, bool offset_local=true) void set_external_force (size_t body_index, const Eigen::Vector3d & force, const Eigen::Vector3d & offset=Eigen::Vector3d::Zero(), bool force_local=false, bool offset_local=true) void set_external_torque (const std::string & body_name, const Eigen::Vector3d & torque, bool local=false) void set_external_torque (size_t body_index, const Eigen::Vector3d & torque, bool local=false) void set_force_lower_limits (const Eigen::VectorXd & forces, const std::vector< std::string > & dof_names={}) void set_force_upper_limits (const Eigen::VectorXd & forces, const std::vector< std::string > & dof_names={}) void set_forces (const Eigen::VectorXd & forces, const std::vector< std::string > & dof_names={}) void set_friction_coeff (const std::string & body_name, double value) void set_friction_coeff (size_t body_index, double value) void set_friction_coeffs (double value) void set_friction_dir (const std::string & body_name, const Eigen::Vector3d & direction) void set_friction_dir (size_t body_index, const Eigen::Vector3d & direction) void set_ghost (bool ghost=true) void set_joint_name (size_t joint_index, const std::string & joint_name) void set_mimic (const std::string & joint_name, const std::string & mimic_joint_name, double multiplier=1., double offset=0.) void set_position_enforced (const std::vector< bool > & enforced, const std::vector< std::string > & dof_names={}) void set_position_enforced (bool enforced, const std::vector< std::string > & dof_names={}) void set_position_lower_limits (const Eigen::VectorXd & positions, const std::vector< std::string > & dof_names={}) void set_position_upper_limits (const Eigen::VectorXd & positions, const std::vector< std::string > & dof_names={}) void set_positions (const Eigen::VectorXd & positions, const std::vector< std::string > & dof_names={}) void set_restitution_coeff (const std::string & body_name, double value) void set_restitution_coeff (size_t body_index, double value) void set_restitution_coeffs (double value) void set_secondary_friction_coeff (const std::string & body_name, double value) void set_secondary_friction_coeff (size_t body_index, double value) void set_secondary_friction_coeffs (double value) void set_self_collision (bool enable_self_collisions=true, bool enable_adjacent_collisions=false) void set_spring_stiffnesses (const std::vector< double > & stiffnesses, const std::vector< std::string > & dof_names={}) void set_spring_stiffnesses (double stiffness, const std::vector< std::string > & dof_names={}) void set_velocities (const Eigen::VectorXd & velocities, const std::vector< std::string > & dof_names={}) void set_velocity_lower_limits (const Eigen::VectorXd & velocities, const std::vector< std::string > & dof_names={}) void set_velocity_upper_limits (const Eigen::VectorXd & velocities, const std::vector< std::string > & dof_names={}) dart::dynamics::SkeletonPtr skeleton () std::vector< double > spring_stiffnesses (const std::vector< std::string > & dof_names={}) const void update (double t) void update_joint_dof_maps () Eigen::VectorXd vec_dof (const Eigen::VectorXd & vec, const std::vector< std::string > & dof_names) const Eigen::VectorXd velocities (const std::vector< std::string > & dof_names={}) const Eigen::VectorXd velocity_lower_limits (const std::vector< std::string > & dof_names={}) const Eigen::VectorXd velocity_upper_limits (const std::vector< std::string > & dof_names={}) const virtual ~Robot ()"},{"location":"api/classrobot__dart_1_1robots_1_1Franka/#public-static-functions-inherited-from-robot_dartrobot","title":"Public Static Functions inherited from robot_dart::Robot","text":"

See robot_dart::Robot

Type Name std::shared_ptr< Robot > create_box (const Eigen::Vector3d & dims, const Eigen::Isometry3d & tf, const std::string & type=\"free\", double mass=1.0, const Eigen::Vector4d & color=dart::Color::Red(1.0), const std::string & box_name=\"box\") std::shared_ptr< Robot > create_box (const Eigen::Vector3d & dims, const Eigen::Vector6d & pose=Eigen::Vector6d::Zero(), const std::string & type=\"free\", double mass=1.0, const Eigen::Vector4d & color=dart::Color::Red(1.0), const std::string & box_name=\"box\") std::shared_ptr< Robot > create_ellipsoid (const Eigen::Vector3d & dims, const Eigen::Isometry3d & tf, const std::string & type=\"free\", double mass=1.0, const Eigen::Vector4d & color=dart::Color::Red(1.0), const std::string & ellipsoid_name=\"ellipsoid\") std::shared_ptr< Robot > create_ellipsoid (const Eigen::Vector3d & dims, const Eigen::Vector6d & pose=Eigen::Vector6d::Zero(), const std::string & type=\"free\", double mass=1.0, const Eigen::Vector4d & color=dart::Color::Red(1.0), const std::string & ellipsoid_name=\"ellipsoid\")"},{"location":"api/classrobot__dart_1_1robots_1_1Franka/#protected-attributes","title":"Protected Attributes","text":"Type Name std::shared_ptr< sensor::ForceTorque > _ft_wrist"},{"location":"api/classrobot__dart_1_1robots_1_1Franka/#protected-attributes-inherited-from-robot_dartrobot","title":"Protected Attributes inherited from robot_dart::Robot","text":"

See robot_dart::Robot

Type Name std::vector< std::pair< dart::dynamics::BodyNode *, double > > _axis_shapes bool _cast_shadows std::vector< std::shared_ptr< control::RobotControl > > _controllers std::unordered_map< std::string, size_t > _dof_map bool _is_ghost std::unordered_map< std::string, size_t > _joint_map std::string _model_filename std::vector< std::pair< std::string, std::string > > _packages std::string _robot_name dart::dynamics::SkeletonPtr _skeleton"},{"location":"api/classrobot__dart_1_1robots_1_1Franka/#protected-functions","title":"Protected Functions","text":"Type Name virtual void _post_addition (RobotDARTSimu *) overrideFunction called by RobotDARTSimu object when adding the robot to the world. virtual void _post_removal (RobotDARTSimu *) overrideFunction called by RobotDARTSimu object when removing the robot to the world."},{"location":"api/classrobot__dart_1_1robots_1_1Franka/#protected-functions-inherited-from-robot_dartrobot","title":"Protected Functions inherited from robot_dart::Robot","text":"

See robot_dart::Robot

Type Name dart::dynamics::Joint::ActuatorType _actuator_type (size_t joint_index) const std::vector< dart::dynamics::Joint::ActuatorType > _actuator_types () const std::string _get_path (const std::string & filename) const Eigen::MatrixXd _jacobian (const Eigen::MatrixXd & full_jacobian, const std::vector< std::string > & dof_names) const dart::dynamics::SkeletonPtr _load_model (const std::string & filename, const std::vector< std::pair< std::string, std::string > > & packages=std::vector< std::pair< std::string, std::string > >(), bool is_urdf_string=false) Eigen::MatrixXd _mass_matrix (const Eigen::MatrixXd & full_mass_matrix, const std::vector< std::string > & dof_names) const virtual void _post_addition (RobotDARTSimu *) Function called by RobotDARTSimu object when adding the robot to the world. virtual void _post_removal (RobotDARTSimu *) Function called by RobotDARTSimu object when removing the robot to the world. void _set_actuator_type (size_t joint_index, dart::dynamics::Joint::ActuatorType type, bool override_mimic=false, bool override_base=false) void _set_actuator_types (const std::vector< dart::dynamics::Joint::ActuatorType > & types, bool override_mimic=false, bool override_base=false) void _set_actuator_types (dart::dynamics::Joint::ActuatorType type, bool override_mimic=false, bool override_base=false) void _set_color_mode (dart::dynamics::MeshShape::ColorMode color_mode, dart::dynamics::SkeletonPtr skel) void _set_color_mode (dart::dynamics::MeshShape::ColorMode color_mode, dart::dynamics::ShapeNode * sn)"},{"location":"api/classrobot__dart_1_1robots_1_1Franka/#public-functions-documentation","title":"Public Functions Documentation","text":""},{"location":"api/classrobot__dart_1_1robots_1_1Franka/#function-franka","title":"function Franka","text":"
robot_dart::robots::Franka::Franka (\nsize_t frequency=1000,\nconst std::string & urdf=\"franka/franka.urdf\",\nconst std::vector< std::pair< std::string, std::string > > & packages=('franka_description', 'franka/franka_description')\n) 
"},{"location":"api/classrobot__dart_1_1robots_1_1Franka/#function-ft_wrist","title":"function ft_wrist","text":"
inline const sensor::ForceTorque & robot_dart::robots::Franka::ft_wrist () const\n
"},{"location":"api/classrobot__dart_1_1robots_1_1Franka/#protected-attributes-documentation","title":"Protected Attributes Documentation","text":""},{"location":"api/classrobot__dart_1_1robots_1_1Franka/#variable-_ft_wrist","title":"variable _ft_wrist","text":"
std::shared_ptr<sensor::ForceTorque> robot_dart::robots::Franka::_ft_wrist;\n
"},{"location":"api/classrobot__dart_1_1robots_1_1Franka/#protected-functions-documentation","title":"Protected Functions Documentation","text":""},{"location":"api/classrobot__dart_1_1robots_1_1Franka/#function-_post_addition","title":"function _post_addition","text":"
virtual void robot_dart::robots::Franka::_post_addition (\nRobotDARTSimu *\n) override\n

Implements robot_dart::Robot::_post_addition

"},{"location":"api/classrobot__dart_1_1robots_1_1Franka/#function-_post_removal","title":"function _post_removal","text":"
virtual void robot_dart::robots::Franka::_post_removal (\nRobotDARTSimu *\n) override\n

Implements robot_dart::Robot::_post_removal

The documentation for this class was generated from the following file robot_dart/robots/franka.hpp

"},{"location":"api/classrobot__dart_1_1robots_1_1Hexapod/","title":"Class robot_dart::robots::Hexapod","text":"

ClassList > robot_dart > robots > Hexapod

Inherits the following classes: robot_dart::Robot

"},{"location":"api/classrobot__dart_1_1robots_1_1Hexapod/#public-functions","title":"Public Functions","text":"Type Name Hexapod (const std::string & urdf=\"pexod.urdf\") virtual void reset () override"},{"location":"api/classrobot__dart_1_1robots_1_1Hexapod/#public-functions-inherited-from-robot_dartrobot","title":"Public Functions inherited from robot_dart::Robot","text":"

See robot_dart::Robot

Type Name Robot (const std::string & model_file, const std::vector< std::pair< std::string, std::string > > & packages, const std::string & robot_name=\"robot\", bool is_urdf_string=false, bool cast_shadows=true) Robot (const std::string & model_file, const std::string & robot_name=\"robot\", bool is_urdf_string=false, bool cast_shadows=true) Robot (dart::dynamics::SkeletonPtr skeleton, const std::string & robot_name=\"robot\", bool cast_shadows=true) Eigen::VectorXd acceleration_lower_limits (const std::vector< std::string > & dof_names={}) const Eigen::VectorXd acceleration_upper_limits (const std::vector< std::string > & dof_names={}) const Eigen::VectorXd accelerations (const std::vector< std::string > & dof_names={}) const std::vector< std::shared_ptr< control::RobotControl > > active_controllers () const std::string actuator_type (const std::string & joint_name) const std::vector< std::string > actuator_types (const std::vector< std::string > & joint_names={}) const void add_body_mass (const std::string & body_name, double mass) void add_body_mass (size_t body_index, double mass) void add_controller (const std::shared_ptr< control::RobotControl > & controller, double weight=1.0) void add_external_force (const std::string & body_name, const Eigen::Vector3d & force, const Eigen::Vector3d & offset=Eigen::Vector3d::Zero(), bool force_local=false, bool offset_local=true) void add_external_force (size_t body_index, const Eigen::Vector3d & force, const Eigen::Vector3d & offset=Eigen::Vector3d::Zero(), bool force_local=false, bool offset_local=true) void add_external_torque (const std::string & body_name, const Eigen::Vector3d & torque, bool local=false) void add_external_torque (size_t body_index, const Eigen::Vector3d & torque, bool local=false) bool adjacent_colliding () const Eigen::MatrixXd aug_mass_matrix (const std::vector< std::string > & dof_names={}) const Eigen::Isometry3d base_pose () const Eigen::Vector6d base_pose_vec () const Eigen::Vector6d body_acceleration (const std::string & body_name) const Eigen::Vector6d body_acceleration (size_t body_index) const size_t body_index (const std::string & body_name) const double body_mass (const std::string & body_name) const double body_mass (size_t body_index) const std::string body_name (size_t body_index) const std::vector< std::string > body_names () const dart::dynamics::BodyNode * body_node (const std::string & body_name) dart::dynamics::BodyNode * body_node (size_t body_index) Eigen::Isometry3d body_pose (const std::string & body_name) const Eigen::Isometry3d body_pose (size_t body_index) const Eigen::Vector6d body_pose_vec (const std::string & body_name) const Eigen::Vector6d body_pose_vec (size_t body_index) const Eigen::Vector6d body_velocity (const std::string & body_name) const Eigen::Vector6d body_velocity (size_t body_index) const bool cast_shadows () const void clear_controllers () void clear_external_forces () void clear_internal_forces () std::shared_ptr< Robot > clone () const std::shared_ptr< Robot > clone_ghost (const std::string & ghost_name=\"ghost\", const Eigen::Vector4d & ghost_color={0.3, 0.3, 0.3, 0.7}) const Eigen::Vector3d com () const Eigen::Vector6d com_acceleration () const Eigen::MatrixXd com_jacobian (const std::vector< std::string > & dof_names={}) const Eigen::MatrixXd com_jacobian_deriv (const std::vector< std::string > & dof_names={}) const Eigen::Vector6d com_velocity () const Eigen::VectorXd commands (const std::vector< std::string > & dof_names={}) const Eigen::VectorXd constraint_forces (const std::vector< std::string > & dof_names={}) const std::shared_ptr< control::RobotControl > controller (size_t index) const std::vector< std::shared_ptr< control::RobotControl > > controllers () const Eigen::VectorXd coriolis_forces (const std::vector< std::string > & dof_names={}) const Eigen::VectorXd coriolis_gravity_forces (const std::vector< std::string > & dof_names={}) const std::vector< double > coulomb_coeffs (const std::vector< std::string > & dof_names={}) const std::vector< double > damping_coeffs (const std::vector< std::string > & dof_names={}) const dart::dynamics::DegreeOfFreedom * dof (const std::string & dof_name) dart::dynamics::DegreeOfFreedom * dof (size_t dof_index) size_t dof_index (const std::string & dof_name) const const std::unordered_map< std::string, size_t > & dof_map () const std::string dof_name (size_t dof_index) const std::vector< std::string > dof_names (bool filter_mimics=false, bool filter_locked=false, bool filter_passive=false) const const std::vector< std::pair< dart::dynamics::BodyNode *, double > > & drawing_axes () const Eigen::Vector6d external_forces (const std::string & body_name) const Eigen::Vector6d external_forces (size_t body_index) const void fix_to_world () bool fixed () const Eigen::VectorXd force_lower_limits (const std::vector< std::string > & dof_names={}) const void force_position_bounds () std::pair< Eigen::Vector6d, Eigen::Vector6d > force_torque (size_t joint_index) const Eigen::VectorXd force_upper_limits (const std::vector< std::string > & dof_names={}) const Eigen::VectorXd forces (const std::vector< std::string > & dof_names={}) const bool free () const void free_from_world (const Eigen::Vector6d & pose=Eigen::Vector6d::Zero()) double friction_coeff (const std::string & body_name) double friction_coeff (size_t body_index) Eigen::Vector3d friction_dir (const std::string & body_name) Eigen::Vector3d friction_dir (size_t body_index) bool ghost () const Eigen::VectorXd gravity_forces (const std::vector< std::string > & dof_names={}) const Eigen::MatrixXd inv_aug_mass_matrix (const std::vector< std::string > & dof_names={}) const Eigen::MatrixXd inv_mass_matrix (const std::vector< std::string > & dof_names={}) const Eigen::MatrixXd jacobian (const std::string & body_name, const std::vector< std::string > & dof_names={}) const Eigen::MatrixXd jacobian_deriv (const std::string & body_name, const std::vector< std::string > & dof_names={}) const dart::dynamics::Joint * joint (const std::string & joint_name) dart::dynamics::Joint * joint (size_t joint_index) size_t joint_index (const std::string & joint_name) const const std::unordered_map< std::string, size_t > & joint_map () const std::string joint_name (size_t joint_index) const std::vector< std::string > joint_names () const std::vector< std::string > locked_dof_names () const Eigen::MatrixXd mass_matrix (const std::vector< std::string > & dof_names={}) const std::vector< std::string > mimic_dof_names () const const std::string & model_filename () const const std::vector< std::pair< std::string, std::string > > & model_packages () const const std::string & name () const size_t num_bodies () const size_t num_controllers () const size_t num_dofs () const size_t num_joints () const std::vector< std::string > passive_dof_names () const std::vector< bool > position_enforced (const std::vector< std::string > & dof_names={}) const Eigen::VectorXd position_lower_limits (const std::vector< std::string > & dof_names={}) const Eigen::VectorXd position_upper_limits (const std::vector< std::string > & dof_names={}) const Eigen::VectorXd positions (const std::vector< std::string > & dof_names={}) const void reinit_controllers () void remove_all_drawing_axis () void remove_controller (const std::shared_ptr< control::RobotControl > & controller) void remove_controller (size_t index) virtual void reset () void reset_commands () double restitution_coeff (const std::string & body_name) double restitution_coeff (size_t body_index) double secondary_friction_coeff (const std::string & body_name) double secondary_friction_coeff (size_t body_index) bool self_colliding () const void set_acceleration_lower_limits (const Eigen::VectorXd & accelerations, const std::vector< std::string > & dof_names={}) void set_acceleration_upper_limits (const Eigen::VectorXd & accelerations, const std::vector< std::string > & dof_names={}) void set_accelerations (const Eigen::VectorXd & accelerations, const std::vector< std::string > & dof_names={}) void set_actuator_type (const std::string & type, const std::string & joint_name, bool override_mimic=false, bool override_base=false) void set_actuator_types (const std::string & type, const std::vector< std::string > & joint_names={}, bool override_mimic=false, bool override_base=false) void set_base_pose (const Eigen::Isometry3d & tf) void set_base_pose (const Eigen::Vector6d & pose) set base pose: pose is a 6D vector (first 3D orientation in angle-axis and last 3D translation) void set_body_mass (const std::string & body_name, double mass) void set_body_mass (size_t body_index, double mass) void set_body_name (size_t body_index, const std::string & body_name) void set_cast_shadows (bool cast_shadows=true) void set_color_mode (const std::string & color_mode) void set_color_mode (const std::string & color_mode, const std::string & body_name) void set_commands (const Eigen::VectorXd & commands, const std::vector< std::string > & dof_names={}) void set_coulomb_coeffs (const std::vector< double > & cfrictions, const std::vector< std::string > & dof_names={}) void set_coulomb_coeffs (double cfriction, const std::vector< std::string > & dof_names={}) void set_damping_coeffs (const std::vector< double > & damps, const std::vector< std::string > & dof_names={}) void set_damping_coeffs (double damp, const std::vector< std::string > & dof_names={}) void set_draw_axis (const std::string & body_name, double size=0.25) void set_external_force (const std::string & body_name, const Eigen::Vector3d & force, const Eigen::Vector3d & offset=Eigen::Vector3d::Zero(), bool force_local=false, bool offset_local=true) void set_external_force (size_t body_index, const Eigen::Vector3d & force, const Eigen::Vector3d & offset=Eigen::Vector3d::Zero(), bool force_local=false, bool offset_local=true) void set_external_torque (const std::string & body_name, const Eigen::Vector3d & torque, bool local=false) void set_external_torque (size_t body_index, const Eigen::Vector3d & torque, bool local=false) void set_force_lower_limits (const Eigen::VectorXd & forces, const std::vector< std::string > & dof_names={}) void set_force_upper_limits (const Eigen::VectorXd & forces, const std::vector< std::string > & dof_names={}) void set_forces (const Eigen::VectorXd & forces, const std::vector< std::string > & dof_names={}) void set_friction_coeff (const std::string & body_name, double value) void set_friction_coeff (size_t body_index, double value) void set_friction_coeffs (double value) void set_friction_dir (const std::string & body_name, const Eigen::Vector3d & direction) void set_friction_dir (size_t body_index, const Eigen::Vector3d & direction) void set_ghost (bool ghost=true) void set_joint_name (size_t joint_index, const std::string & joint_name) void set_mimic (const std::string & joint_name, const std::string & mimic_joint_name, double multiplier=1., double offset=0.) void set_position_enforced (const std::vector< bool > & enforced, const std::vector< std::string > & dof_names={}) void set_position_enforced (bool enforced, const std::vector< std::string > & dof_names={}) void set_position_lower_limits (const Eigen::VectorXd & positions, const std::vector< std::string > & dof_names={}) void set_position_upper_limits (const Eigen::VectorXd & positions, const std::vector< std::string > & dof_names={}) void set_positions (const Eigen::VectorXd & positions, const std::vector< std::string > & dof_names={}) void set_restitution_coeff (const std::string & body_name, double value) void set_restitution_coeff (size_t body_index, double value) void set_restitution_coeffs (double value) void set_secondary_friction_coeff (const std::string & body_name, double value) void set_secondary_friction_coeff (size_t body_index, double value) void set_secondary_friction_coeffs (double value) void set_self_collision (bool enable_self_collisions=true, bool enable_adjacent_collisions=false) void set_spring_stiffnesses (const std::vector< double > & stiffnesses, const std::vector< std::string > & dof_names={}) void set_spring_stiffnesses (double stiffness, const std::vector< std::string > & dof_names={}) void set_velocities (const Eigen::VectorXd & velocities, const std::vector< std::string > & dof_names={}) void set_velocity_lower_limits (const Eigen::VectorXd & velocities, const std::vector< std::string > & dof_names={}) void set_velocity_upper_limits (const Eigen::VectorXd & velocities, const std::vector< std::string > & dof_names={}) dart::dynamics::SkeletonPtr skeleton () std::vector< double > spring_stiffnesses (const std::vector< std::string > & dof_names={}) const void update (double t) void update_joint_dof_maps () Eigen::VectorXd vec_dof (const Eigen::VectorXd & vec, const std::vector< std::string > & dof_names) const Eigen::VectorXd velocities (const std::vector< std::string > & dof_names={}) const Eigen::VectorXd velocity_lower_limits (const std::vector< std::string > & dof_names={}) const Eigen::VectorXd velocity_upper_limits (const std::vector< std::string > & dof_names={}) const virtual ~Robot ()"},{"location":"api/classrobot__dart_1_1robots_1_1Hexapod/#public-static-functions-inherited-from-robot_dartrobot","title":"Public Static Functions inherited from robot_dart::Robot","text":"

See robot_dart::Robot

Type Name std::shared_ptr< Robot > create_box (const Eigen::Vector3d & dims, const Eigen::Isometry3d & tf, const std::string & type=\"free\", double mass=1.0, const Eigen::Vector4d & color=dart::Color::Red(1.0), const std::string & box_name=\"box\") std::shared_ptr< Robot > create_box (const Eigen::Vector3d & dims, const Eigen::Vector6d & pose=Eigen::Vector6d::Zero(), const std::string & type=\"free\", double mass=1.0, const Eigen::Vector4d & color=dart::Color::Red(1.0), const std::string & box_name=\"box\") std::shared_ptr< Robot > create_ellipsoid (const Eigen::Vector3d & dims, const Eigen::Isometry3d & tf, const std::string & type=\"free\", double mass=1.0, const Eigen::Vector4d & color=dart::Color::Red(1.0), const std::string & ellipsoid_name=\"ellipsoid\") std::shared_ptr< Robot > create_ellipsoid (const Eigen::Vector3d & dims, const Eigen::Vector6d & pose=Eigen::Vector6d::Zero(), const std::string & type=\"free\", double mass=1.0, const Eigen::Vector4d & color=dart::Color::Red(1.0), const std::string & ellipsoid_name=\"ellipsoid\")"},{"location":"api/classrobot__dart_1_1robots_1_1Hexapod/#protected-attributes-inherited-from-robot_dartrobot","title":"Protected Attributes inherited from robot_dart::Robot","text":"

See robot_dart::Robot

Type Name std::vector< std::pair< dart::dynamics::BodyNode *, double > > _axis_shapes bool _cast_shadows std::vector< std::shared_ptr< control::RobotControl > > _controllers std::unordered_map< std::string, size_t > _dof_map bool _is_ghost std::unordered_map< std::string, size_t > _joint_map std::string _model_filename std::vector< std::pair< std::string, std::string > > _packages std::string _robot_name dart::dynamics::SkeletonPtr _skeleton"},{"location":"api/classrobot__dart_1_1robots_1_1Hexapod/#protected-functions-inherited-from-robot_dartrobot","title":"Protected Functions inherited from robot_dart::Robot","text":"

See robot_dart::Robot

Type Name dart::dynamics::Joint::ActuatorType _actuator_type (size_t joint_index) const std::vector< dart::dynamics::Joint::ActuatorType > _actuator_types () const std::string _get_path (const std::string & filename) const Eigen::MatrixXd _jacobian (const Eigen::MatrixXd & full_jacobian, const std::vector< std::string > & dof_names) const dart::dynamics::SkeletonPtr _load_model (const std::string & filename, const std::vector< std::pair< std::string, std::string > > & packages=std::vector< std::pair< std::string, std::string > >(), bool is_urdf_string=false) Eigen::MatrixXd _mass_matrix (const Eigen::MatrixXd & full_mass_matrix, const std::vector< std::string > & dof_names) const virtual void _post_addition (RobotDARTSimu *) Function called by RobotDARTSimu object when adding the robot to the world. virtual void _post_removal (RobotDARTSimu *) Function called by RobotDARTSimu object when removing the robot to the world. void _set_actuator_type (size_t joint_index, dart::dynamics::Joint::ActuatorType type, bool override_mimic=false, bool override_base=false) void _set_actuator_types (const std::vector< dart::dynamics::Joint::ActuatorType > & types, bool override_mimic=false, bool override_base=false) void _set_actuator_types (dart::dynamics::Joint::ActuatorType type, bool override_mimic=false, bool override_base=false) void _set_color_mode (dart::dynamics::MeshShape::ColorMode color_mode, dart::dynamics::SkeletonPtr skel) void _set_color_mode (dart::dynamics::MeshShape::ColorMode color_mode, dart::dynamics::ShapeNode * sn)"},{"location":"api/classrobot__dart_1_1robots_1_1Hexapod/#public-functions-documentation","title":"Public Functions Documentation","text":""},{"location":"api/classrobot__dart_1_1robots_1_1Hexapod/#function-hexapod","title":"function Hexapod","text":"
inline robot_dart::robots::Hexapod::Hexapod (\nconst std::string & urdf=\"pexod.urdf\"\n) 
"},{"location":"api/classrobot__dart_1_1robots_1_1Hexapod/#function-reset","title":"function reset","text":"
inline virtual void robot_dart::robots::Hexapod::reset () override\n

Implements robot_dart::Robot::reset

The documentation for this class was generated from the following file robot_dart/robots/hexapod.hpp

"},{"location":"api/classrobot__dart_1_1robots_1_1ICub/","title":"Class robot_dart::robots::ICub","text":"

ClassList > robot_dart > robots > ICub

Inherits the following classes: robot_dart::Robot

"},{"location":"api/classrobot__dart_1_1robots_1_1ICub/#public-functions","title":"Public Functions","text":"Type Name ICub (size_t frequency=1000, const std::string & urdf=\"icub/icub.urdf\", const std::vector< std::pair< std::string, std::string > > & packages=('icub\\_description', 'icub/icub\\_description')) const sensor::ForceTorque & ft_foot_left () const const sensor::ForceTorque & ft_foot_right () const const sensor::IMU & imu () const virtual void reset () override"},{"location":"api/classrobot__dart_1_1robots_1_1ICub/#public-functions-inherited-from-robot_dartrobot","title":"Public Functions inherited from robot_dart::Robot","text":"

See robot_dart::Robot

Type Name Robot (const std::string & model_file, const std::vector< std::pair< std::string, std::string > > & packages, const std::string & robot_name=\"robot\", bool is_urdf_string=false, bool cast_shadows=true) Robot (const std::string & model_file, const std::string & robot_name=\"robot\", bool is_urdf_string=false, bool cast_shadows=true) Robot (dart::dynamics::SkeletonPtr skeleton, const std::string & robot_name=\"robot\", bool cast_shadows=true) Eigen::VectorXd acceleration_lower_limits (const std::vector< std::string > & dof_names={}) const Eigen::VectorXd acceleration_upper_limits (const std::vector< std::string > & dof_names={}) const Eigen::VectorXd accelerations (const std::vector< std::string > & dof_names={}) const std::vector< std::shared_ptr< control::RobotControl > > active_controllers () const std::string actuator_type (const std::string & joint_name) const std::vector< std::string > actuator_types (const std::vector< std::string > & joint_names={}) const void add_body_mass (const std::string & body_name, double mass) void add_body_mass (size_t body_index, double mass) void add_controller (const std::shared_ptr< control::RobotControl > & controller, double weight=1.0) void add_external_force (const std::string & body_name, const Eigen::Vector3d & force, const Eigen::Vector3d & offset=Eigen::Vector3d::Zero(), bool force_local=false, bool offset_local=true) void add_external_force (size_t body_index, const Eigen::Vector3d & force, const Eigen::Vector3d & offset=Eigen::Vector3d::Zero(), bool force_local=false, bool offset_local=true) void add_external_torque (const std::string & body_name, const Eigen::Vector3d & torque, bool local=false) void add_external_torque (size_t body_index, const Eigen::Vector3d & torque, bool local=false) bool adjacent_colliding () const Eigen::MatrixXd aug_mass_matrix (const std::vector< std::string > & dof_names={}) const Eigen::Isometry3d base_pose () const Eigen::Vector6d base_pose_vec () const Eigen::Vector6d body_acceleration (const std::string & body_name) const Eigen::Vector6d body_acceleration (size_t body_index) const size_t body_index (const std::string & body_name) const double body_mass (const std::string & body_name) const double body_mass (size_t body_index) const std::string body_name (size_t body_index) const std::vector< std::string > body_names () const dart::dynamics::BodyNode * body_node (const std::string & body_name) dart::dynamics::BodyNode * body_node (size_t body_index) Eigen::Isometry3d body_pose (const std::string & body_name) const Eigen::Isometry3d body_pose (size_t body_index) const Eigen::Vector6d body_pose_vec (const std::string & body_name) const Eigen::Vector6d body_pose_vec (size_t body_index) const Eigen::Vector6d body_velocity (const std::string & body_name) const Eigen::Vector6d body_velocity (size_t body_index) const bool cast_shadows () const void clear_controllers () void clear_external_forces () void clear_internal_forces () std::shared_ptr< Robot > clone () const std::shared_ptr< Robot > clone_ghost (const std::string & ghost_name=\"ghost\", const Eigen::Vector4d & ghost_color={0.3, 0.3, 0.3, 0.7}) const Eigen::Vector3d com () const Eigen::Vector6d com_acceleration () const Eigen::MatrixXd com_jacobian (const std::vector< std::string > & dof_names={}) const Eigen::MatrixXd com_jacobian_deriv (const std::vector< std::string > & dof_names={}) const Eigen::Vector6d com_velocity () const Eigen::VectorXd commands (const std::vector< std::string > & dof_names={}) const Eigen::VectorXd constraint_forces (const std::vector< std::string > & dof_names={}) const std::shared_ptr< control::RobotControl > controller (size_t index) const std::vector< std::shared_ptr< control::RobotControl > > controllers () const Eigen::VectorXd coriolis_forces (const std::vector< std::string > & dof_names={}) const Eigen::VectorXd coriolis_gravity_forces (const std::vector< std::string > & dof_names={}) const std::vector< double > coulomb_coeffs (const std::vector< std::string > & dof_names={}) const std::vector< double > damping_coeffs (const std::vector< std::string > & dof_names={}) const dart::dynamics::DegreeOfFreedom * dof (const std::string & dof_name) dart::dynamics::DegreeOfFreedom * dof (size_t dof_index) size_t dof_index (const std::string & dof_name) const const std::unordered_map< std::string, size_t > & dof_map () const std::string dof_name (size_t dof_index) const std::vector< std::string > dof_names (bool filter_mimics=false, bool filter_locked=false, bool filter_passive=false) const const std::vector< std::pair< dart::dynamics::BodyNode *, double > > & drawing_axes () const Eigen::Vector6d external_forces (const std::string & body_name) const Eigen::Vector6d external_forces (size_t body_index) const void fix_to_world () bool fixed () const Eigen::VectorXd force_lower_limits (const std::vector< std::string > & dof_names={}) const void force_position_bounds () std::pair< Eigen::Vector6d, Eigen::Vector6d > force_torque (size_t joint_index) const Eigen::VectorXd force_upper_limits (const std::vector< std::string > & dof_names={}) const Eigen::VectorXd forces (const std::vector< std::string > & dof_names={}) const bool free () const void free_from_world (const Eigen::Vector6d & pose=Eigen::Vector6d::Zero()) double friction_coeff (const std::string & body_name) double friction_coeff (size_t body_index) Eigen::Vector3d friction_dir (const std::string & body_name) Eigen::Vector3d friction_dir (size_t body_index) bool ghost () const Eigen::VectorXd gravity_forces (const std::vector< std::string > & dof_names={}) const Eigen::MatrixXd inv_aug_mass_matrix (const std::vector< std::string > & dof_names={}) const Eigen::MatrixXd inv_mass_matrix (const std::vector< std::string > & dof_names={}) const Eigen::MatrixXd jacobian (const std::string & body_name, const std::vector< std::string > & dof_names={}) const Eigen::MatrixXd jacobian_deriv (const std::string & body_name, const std::vector< std::string > & dof_names={}) const dart::dynamics::Joint * joint (const std::string & joint_name) dart::dynamics::Joint * joint (size_t joint_index) size_t joint_index (const std::string & joint_name) const const std::unordered_map< std::string, size_t > & joint_map () const std::string joint_name (size_t joint_index) const std::vector< std::string > joint_names () const std::vector< std::string > locked_dof_names () const Eigen::MatrixXd mass_matrix (const std::vector< std::string > & dof_names={}) const std::vector< std::string > mimic_dof_names () const const std::string & model_filename () const const std::vector< std::pair< std::string, std::string > > & model_packages () const const std::string & name () const size_t num_bodies () const size_t num_controllers () const size_t num_dofs () const size_t num_joints () const std::vector< std::string > passive_dof_names () const std::vector< bool > position_enforced (const std::vector< std::string > & dof_names={}) const Eigen::VectorXd position_lower_limits (const std::vector< std::string > & dof_names={}) const Eigen::VectorXd position_upper_limits (const std::vector< std::string > & dof_names={}) const Eigen::VectorXd positions (const std::vector< std::string > & dof_names={}) const void reinit_controllers () void remove_all_drawing_axis () void remove_controller (const std::shared_ptr< control::RobotControl > & controller) void remove_controller (size_t index) virtual void reset () void reset_commands () double restitution_coeff (const std::string & body_name) double restitution_coeff (size_t body_index) double secondary_friction_coeff (const std::string & body_name) double secondary_friction_coeff (size_t body_index) bool self_colliding () const void set_acceleration_lower_limits (const Eigen::VectorXd & accelerations, const std::vector< std::string > & dof_names={}) void set_acceleration_upper_limits (const Eigen::VectorXd & accelerations, const std::vector< std::string > & dof_names={}) void set_accelerations (const Eigen::VectorXd & accelerations, const std::vector< std::string > & dof_names={}) void set_actuator_type (const std::string & type, const std::string & joint_name, bool override_mimic=false, bool override_base=false) void set_actuator_types (const std::string & type, const std::vector< std::string > & joint_names={}, bool override_mimic=false, bool override_base=false) void set_base_pose (const Eigen::Isometry3d & tf) void set_base_pose (const Eigen::Vector6d & pose) set base pose: pose is a 6D vector (first 3D orientation in angle-axis and last 3D translation) void set_body_mass (const std::string & body_name, double mass) void set_body_mass (size_t body_index, double mass) void set_body_name (size_t body_index, const std::string & body_name) void set_cast_shadows (bool cast_shadows=true) void set_color_mode (const std::string & color_mode) void set_color_mode (const std::string & color_mode, const std::string & body_name) void set_commands (const Eigen::VectorXd & commands, const std::vector< std::string > & dof_names={}) void set_coulomb_coeffs (const std::vector< double > & cfrictions, const std::vector< std::string > & dof_names={}) void set_coulomb_coeffs (double cfriction, const std::vector< std::string > & dof_names={}) void set_damping_coeffs (const std::vector< double > & damps, const std::vector< std::string > & dof_names={}) void set_damping_coeffs (double damp, const std::vector< std::string > & dof_names={}) void set_draw_axis (const std::string & body_name, double size=0.25) void set_external_force (const std::string & body_name, const Eigen::Vector3d & force, const Eigen::Vector3d & offset=Eigen::Vector3d::Zero(), bool force_local=false, bool offset_local=true) void set_external_force (size_t body_index, const Eigen::Vector3d & force, const Eigen::Vector3d & offset=Eigen::Vector3d::Zero(), bool force_local=false, bool offset_local=true) void set_external_torque (const std::string & body_name, const Eigen::Vector3d & torque, bool local=false) void set_external_torque (size_t body_index, const Eigen::Vector3d & torque, bool local=false) void set_force_lower_limits (const Eigen::VectorXd & forces, const std::vector< std::string > & dof_names={}) void set_force_upper_limits (const Eigen::VectorXd & forces, const std::vector< std::string > & dof_names={}) void set_forces (const Eigen::VectorXd & forces, const std::vector< std::string > & dof_names={}) void set_friction_coeff (const std::string & body_name, double value) void set_friction_coeff (size_t body_index, double value) void set_friction_coeffs (double value) void set_friction_dir (const std::string & body_name, const Eigen::Vector3d & direction) void set_friction_dir (size_t body_index, const Eigen::Vector3d & direction) void set_ghost (bool ghost=true) void set_joint_name (size_t joint_index, const std::string & joint_name) void set_mimic (const std::string & joint_name, const std::string & mimic_joint_name, double multiplier=1., double offset=0.) void set_position_enforced (const std::vector< bool > & enforced, const std::vector< std::string > & dof_names={}) void set_position_enforced (bool enforced, const std::vector< std::string > & dof_names={}) void set_position_lower_limits (const Eigen::VectorXd & positions, const std::vector< std::string > & dof_names={}) void set_position_upper_limits (const Eigen::VectorXd & positions, const std::vector< std::string > & dof_names={}) void set_positions (const Eigen::VectorXd & positions, const std::vector< std::string > & dof_names={}) void set_restitution_coeff (const std::string & body_name, double value) void set_restitution_coeff (size_t body_index, double value) void set_restitution_coeffs (double value) void set_secondary_friction_coeff (const std::string & body_name, double value) void set_secondary_friction_coeff (size_t body_index, double value) void set_secondary_friction_coeffs (double value) void set_self_collision (bool enable_self_collisions=true, bool enable_adjacent_collisions=false) void set_spring_stiffnesses (const std::vector< double > & stiffnesses, const std::vector< std::string > & dof_names={}) void set_spring_stiffnesses (double stiffness, const std::vector< std::string > & dof_names={}) void set_velocities (const Eigen::VectorXd & velocities, const std::vector< std::string > & dof_names={}) void set_velocity_lower_limits (const Eigen::VectorXd & velocities, const std::vector< std::string > & dof_names={}) void set_velocity_upper_limits (const Eigen::VectorXd & velocities, const std::vector< std::string > & dof_names={}) dart::dynamics::SkeletonPtr skeleton () std::vector< double > spring_stiffnesses (const std::vector< std::string > & dof_names={}) const void update (double t) void update_joint_dof_maps () Eigen::VectorXd vec_dof (const Eigen::VectorXd & vec, const std::vector< std::string > & dof_names) const Eigen::VectorXd velocities (const std::vector< std::string > & dof_names={}) const Eigen::VectorXd velocity_lower_limits (const std::vector< std::string > & dof_names={}) const Eigen::VectorXd velocity_upper_limits (const std::vector< std::string > & dof_names={}) const virtual ~Robot ()"},{"location":"api/classrobot__dart_1_1robots_1_1ICub/#public-static-functions-inherited-from-robot_dartrobot","title":"Public Static Functions inherited from robot_dart::Robot","text":"

See robot_dart::Robot

Type Name std::shared_ptr< Robot > create_box (const Eigen::Vector3d & dims, const Eigen::Isometry3d & tf, const std::string & type=\"free\", double mass=1.0, const Eigen::Vector4d & color=dart::Color::Red(1.0), const std::string & box_name=\"box\") std::shared_ptr< Robot > create_box (const Eigen::Vector3d & dims, const Eigen::Vector6d & pose=Eigen::Vector6d::Zero(), const std::string & type=\"free\", double mass=1.0, const Eigen::Vector4d & color=dart::Color::Red(1.0), const std::string & box_name=\"box\") std::shared_ptr< Robot > create_ellipsoid (const Eigen::Vector3d & dims, const Eigen::Isometry3d & tf, const std::string & type=\"free\", double mass=1.0, const Eigen::Vector4d & color=dart::Color::Red(1.0), const std::string & ellipsoid_name=\"ellipsoid\") std::shared_ptr< Robot > create_ellipsoid (const Eigen::Vector3d & dims, const Eigen::Vector6d & pose=Eigen::Vector6d::Zero(), const std::string & type=\"free\", double mass=1.0, const Eigen::Vector4d & color=dart::Color::Red(1.0), const std::string & ellipsoid_name=\"ellipsoid\")"},{"location":"api/classrobot__dart_1_1robots_1_1ICub/#protected-attributes","title":"Protected Attributes","text":"Type Name std::shared_ptr< sensor::ForceTorque > _ft_foot_left std::shared_ptr< sensor::ForceTorque > _ft_foot_right std::shared_ptr< sensor::IMU > _imu"},{"location":"api/classrobot__dart_1_1robots_1_1ICub/#protected-attributes-inherited-from-robot_dartrobot","title":"Protected Attributes inherited from robot_dart::Robot","text":"

See robot_dart::Robot

Type Name std::vector< std::pair< dart::dynamics::BodyNode *, double > > _axis_shapes bool _cast_shadows std::vector< std::shared_ptr< control::RobotControl > > _controllers std::unordered_map< std::string, size_t > _dof_map bool _is_ghost std::unordered_map< std::string, size_t > _joint_map std::string _model_filename std::vector< std::pair< std::string, std::string > > _packages std::string _robot_name dart::dynamics::SkeletonPtr _skeleton"},{"location":"api/classrobot__dart_1_1robots_1_1ICub/#protected-functions","title":"Protected Functions","text":"Type Name virtual void _post_addition (RobotDARTSimu *) overrideFunction called by RobotDARTSimu object when adding the robot to the world. virtual void _post_removal (RobotDARTSimu *) overrideFunction called by RobotDARTSimu object when removing the robot to the world."},{"location":"api/classrobot__dart_1_1robots_1_1ICub/#protected-functions-inherited-from-robot_dartrobot","title":"Protected Functions inherited from robot_dart::Robot","text":"

See robot_dart::Robot

Type Name dart::dynamics::Joint::ActuatorType _actuator_type (size_t joint_index) const std::vector< dart::dynamics::Joint::ActuatorType > _actuator_types () const std::string _get_path (const std::string & filename) const Eigen::MatrixXd _jacobian (const Eigen::MatrixXd & full_jacobian, const std::vector< std::string > & dof_names) const dart::dynamics::SkeletonPtr _load_model (const std::string & filename, const std::vector< std::pair< std::string, std::string > > & packages=std::vector< std::pair< std::string, std::string > >(), bool is_urdf_string=false) Eigen::MatrixXd _mass_matrix (const Eigen::MatrixXd & full_mass_matrix, const std::vector< std::string > & dof_names) const virtual void _post_addition (RobotDARTSimu *) Function called by RobotDARTSimu object when adding the robot to the world. virtual void _post_removal (RobotDARTSimu *) Function called by RobotDARTSimu object when removing the robot to the world. void _set_actuator_type (size_t joint_index, dart::dynamics::Joint::ActuatorType type, bool override_mimic=false, bool override_base=false) void _set_actuator_types (const std::vector< dart::dynamics::Joint::ActuatorType > & types, bool override_mimic=false, bool override_base=false) void _set_actuator_types (dart::dynamics::Joint::ActuatorType type, bool override_mimic=false, bool override_base=false) void _set_color_mode (dart::dynamics::MeshShape::ColorMode color_mode, dart::dynamics::SkeletonPtr skel) void _set_color_mode (dart::dynamics::MeshShape::ColorMode color_mode, dart::dynamics::ShapeNode * sn)"},{"location":"api/classrobot__dart_1_1robots_1_1ICub/#public-functions-documentation","title":"Public Functions Documentation","text":""},{"location":"api/classrobot__dart_1_1robots_1_1ICub/#function-icub","title":"function ICub","text":"
robot_dart::robots::ICub::ICub (\nsize_t frequency=1000,\nconst std::string & urdf=\"icub/icub.urdf\",\nconst std::vector< std::pair< std::string, std::string > > & packages=('icub_description', 'icub/icub_description')\n) 
"},{"location":"api/classrobot__dart_1_1robots_1_1ICub/#function-ft_foot_left","title":"function ft_foot_left","text":"
inline const sensor::ForceTorque & robot_dart::robots::ICub::ft_foot_left () const\n
"},{"location":"api/classrobot__dart_1_1robots_1_1ICub/#function-ft_foot_right","title":"function ft_foot_right","text":"
inline const sensor::ForceTorque & robot_dart::robots::ICub::ft_foot_right () const\n
"},{"location":"api/classrobot__dart_1_1robots_1_1ICub/#function-imu","title":"function imu","text":"
inline const sensor::IMU & robot_dart::robots::ICub::imu () const\n
"},{"location":"api/classrobot__dart_1_1robots_1_1ICub/#function-reset","title":"function reset","text":"
virtual void robot_dart::robots::ICub::reset () override\n

Implements robot_dart::Robot::reset

"},{"location":"api/classrobot__dart_1_1robots_1_1ICub/#protected-attributes-documentation","title":"Protected Attributes Documentation","text":""},{"location":"api/classrobot__dart_1_1robots_1_1ICub/#variable-_ft_foot_left","title":"variable _ft_foot_left","text":"
std::shared_ptr<sensor::ForceTorque> robot_dart::robots::ICub::_ft_foot_left;\n
"},{"location":"api/classrobot__dart_1_1robots_1_1ICub/#variable-_ft_foot_right","title":"variable _ft_foot_right","text":"
std::shared_ptr<sensor::ForceTorque> robot_dart::robots::ICub::_ft_foot_right;\n
"},{"location":"api/classrobot__dart_1_1robots_1_1ICub/#variable-_imu","title":"variable _imu","text":"
std::shared_ptr<sensor::IMU> robot_dart::robots::ICub::_imu;\n
"},{"location":"api/classrobot__dart_1_1robots_1_1ICub/#protected-functions-documentation","title":"Protected Functions Documentation","text":""},{"location":"api/classrobot__dart_1_1robots_1_1ICub/#function-_post_addition","title":"function _post_addition","text":"
virtual void robot_dart::robots::ICub::_post_addition (\nRobotDARTSimu *\n) override\n

Implements robot_dart::Robot::_post_addition

"},{"location":"api/classrobot__dart_1_1robots_1_1ICub/#function-_post_removal","title":"function _post_removal","text":"
virtual void robot_dart::robots::ICub::_post_removal (\nRobotDARTSimu *\n) override\n

Implements robot_dart::Robot::_post_removal

The documentation for this class was generated from the following file robot_dart/robots/icub.hpp

"},{"location":"api/classrobot__dart_1_1robots_1_1Iiwa/","title":"Class robot_dart::robots::Iiwa","text":"

ClassList > robot_dart > robots > Iiwa

Inherits the following classes: robot_dart::Robot

"},{"location":"api/classrobot__dart_1_1robots_1_1Iiwa/#public-functions","title":"Public Functions","text":"Type Name Iiwa (size_t frequency=1000, const std::string & urdf=\"iiwa/iiwa.urdf\", const std::vector< std::pair< std::string, std::string > > & packages=('iiwa\\_description', 'iiwa/iiwa\\_description')) const sensor::ForceTorque & ft_wrist () const"},{"location":"api/classrobot__dart_1_1robots_1_1Iiwa/#public-functions-inherited-from-robot_dartrobot","title":"Public Functions inherited from robot_dart::Robot","text":"

See robot_dart::Robot

Type Name Robot (const std::string & model_file, const std::vector< std::pair< std::string, std::string > > & packages, const std::string & robot_name=\"robot\", bool is_urdf_string=false, bool cast_shadows=true) Robot (const std::string & model_file, const std::string & robot_name=\"robot\", bool is_urdf_string=false, bool cast_shadows=true) Robot (dart::dynamics::SkeletonPtr skeleton, const std::string & robot_name=\"robot\", bool cast_shadows=true) Eigen::VectorXd acceleration_lower_limits (const std::vector< std::string > & dof_names={}) const Eigen::VectorXd acceleration_upper_limits (const std::vector< std::string > & dof_names={}) const Eigen::VectorXd accelerations (const std::vector< std::string > & dof_names={}) const std::vector< std::shared_ptr< control::RobotControl > > active_controllers () const std::string actuator_type (const std::string & joint_name) const std::vector< std::string > actuator_types (const std::vector< std::string > & joint_names={}) const void add_body_mass (const std::string & body_name, double mass) void add_body_mass (size_t body_index, double mass) void add_controller (const std::shared_ptr< control::RobotControl > & controller, double weight=1.0) void add_external_force (const std::string & body_name, const Eigen::Vector3d & force, const Eigen::Vector3d & offset=Eigen::Vector3d::Zero(), bool force_local=false, bool offset_local=true) void add_external_force (size_t body_index, const Eigen::Vector3d & force, const Eigen::Vector3d & offset=Eigen::Vector3d::Zero(), bool force_local=false, bool offset_local=true) void add_external_torque (const std::string & body_name, const Eigen::Vector3d & torque, bool local=false) void add_external_torque (size_t body_index, const Eigen::Vector3d & torque, bool local=false) bool adjacent_colliding () const Eigen::MatrixXd aug_mass_matrix (const std::vector< std::string > & dof_names={}) const Eigen::Isometry3d base_pose () const Eigen::Vector6d base_pose_vec () const Eigen::Vector6d body_acceleration (const std::string & body_name) const Eigen::Vector6d body_acceleration (size_t body_index) const size_t body_index (const std::string & body_name) const double body_mass (const std::string & body_name) const double body_mass (size_t body_index) const std::string body_name (size_t body_index) const std::vector< std::string > body_names () const dart::dynamics::BodyNode * body_node (const std::string & body_name) dart::dynamics::BodyNode * body_node (size_t body_index) Eigen::Isometry3d body_pose (const std::string & body_name) const Eigen::Isometry3d body_pose (size_t body_index) const Eigen::Vector6d body_pose_vec (const std::string & body_name) const Eigen::Vector6d body_pose_vec (size_t body_index) const Eigen::Vector6d body_velocity (const std::string & body_name) const Eigen::Vector6d body_velocity (size_t body_index) const bool cast_shadows () const void clear_controllers () void clear_external_forces () void clear_internal_forces () std::shared_ptr< Robot > clone () const std::shared_ptr< Robot > clone_ghost (const std::string & ghost_name=\"ghost\", const Eigen::Vector4d & ghost_color={0.3, 0.3, 0.3, 0.7}) const Eigen::Vector3d com () const Eigen::Vector6d com_acceleration () const Eigen::MatrixXd com_jacobian (const std::vector< std::string > & dof_names={}) const Eigen::MatrixXd com_jacobian_deriv (const std::vector< std::string > & dof_names={}) const Eigen::Vector6d com_velocity () const Eigen::VectorXd commands (const std::vector< std::string > & dof_names={}) const Eigen::VectorXd constraint_forces (const std::vector< std::string > & dof_names={}) const std::shared_ptr< control::RobotControl > controller (size_t index) const std::vector< std::shared_ptr< control::RobotControl > > controllers () const Eigen::VectorXd coriolis_forces (const std::vector< std::string > & dof_names={}) const Eigen::VectorXd coriolis_gravity_forces (const std::vector< std::string > & dof_names={}) const std::vector< double > coulomb_coeffs (const std::vector< std::string > & dof_names={}) const std::vector< double > damping_coeffs (const std::vector< std::string > & dof_names={}) const dart::dynamics::DegreeOfFreedom * dof (const std::string & dof_name) dart::dynamics::DegreeOfFreedom * dof (size_t dof_index) size_t dof_index (const std::string & dof_name) const const std::unordered_map< std::string, size_t > & dof_map () const std::string dof_name (size_t dof_index) const std::vector< std::string > dof_names (bool filter_mimics=false, bool filter_locked=false, bool filter_passive=false) const const std::vector< std::pair< dart::dynamics::BodyNode *, double > > & drawing_axes () const Eigen::Vector6d external_forces (const std::string & body_name) const Eigen::Vector6d external_forces (size_t body_index) const void fix_to_world () bool fixed () const Eigen::VectorXd force_lower_limits (const std::vector< std::string > & dof_names={}) const void force_position_bounds () std::pair< Eigen::Vector6d, Eigen::Vector6d > force_torque (size_t joint_index) const Eigen::VectorXd force_upper_limits (const std::vector< std::string > & dof_names={}) const Eigen::VectorXd forces (const std::vector< std::string > & dof_names={}) const bool free () const void free_from_world (const Eigen::Vector6d & pose=Eigen::Vector6d::Zero()) double friction_coeff (const std::string & body_name) double friction_coeff (size_t body_index) Eigen::Vector3d friction_dir (const std::string & body_name) Eigen::Vector3d friction_dir (size_t body_index) bool ghost () const Eigen::VectorXd gravity_forces (const std::vector< std::string > & dof_names={}) const Eigen::MatrixXd inv_aug_mass_matrix (const std::vector< std::string > & dof_names={}) const Eigen::MatrixXd inv_mass_matrix (const std::vector< std::string > & dof_names={}) const Eigen::MatrixXd jacobian (const std::string & body_name, const std::vector< std::string > & dof_names={}) const Eigen::MatrixXd jacobian_deriv (const std::string & body_name, const std::vector< std::string > & dof_names={}) const dart::dynamics::Joint * joint (const std::string & joint_name) dart::dynamics::Joint * joint (size_t joint_index) size_t joint_index (const std::string & joint_name) const const std::unordered_map< std::string, size_t > & joint_map () const std::string joint_name (size_t joint_index) const std::vector< std::string > joint_names () const std::vector< std::string > locked_dof_names () const Eigen::MatrixXd mass_matrix (const std::vector< std::string > & dof_names={}) const std::vector< std::string > mimic_dof_names () const const std::string & model_filename () const const std::vector< std::pair< std::string, std::string > > & model_packages () const const std::string & name () const size_t num_bodies () const size_t num_controllers () const size_t num_dofs () const size_t num_joints () const std::vector< std::string > passive_dof_names () const std::vector< bool > position_enforced (const std::vector< std::string > & dof_names={}) const Eigen::VectorXd position_lower_limits (const std::vector< std::string > & dof_names={}) const Eigen::VectorXd position_upper_limits (const std::vector< std::string > & dof_names={}) const Eigen::VectorXd positions (const std::vector< std::string > & dof_names={}) const void reinit_controllers () void remove_all_drawing_axis () void remove_controller (const std::shared_ptr< control::RobotControl > & controller) void remove_controller (size_t index) virtual void reset () void reset_commands () double restitution_coeff (const std::string & body_name) double restitution_coeff (size_t body_index) double secondary_friction_coeff (const std::string & body_name) double secondary_friction_coeff (size_t body_index) bool self_colliding () const void set_acceleration_lower_limits (const Eigen::VectorXd & accelerations, const std::vector< std::string > & dof_names={}) void set_acceleration_upper_limits (const Eigen::VectorXd & accelerations, const std::vector< std::string > & dof_names={}) void set_accelerations (const Eigen::VectorXd & accelerations, const std::vector< std::string > & dof_names={}) void set_actuator_type (const std::string & type, const std::string & joint_name, bool override_mimic=false, bool override_base=false) void set_actuator_types (const std::string & type, const std::vector< std::string > & joint_names={}, bool override_mimic=false, bool override_base=false) void set_base_pose (const Eigen::Isometry3d & tf) void set_base_pose (const Eigen::Vector6d & pose) set base pose: pose is a 6D vector (first 3D orientation in angle-axis and last 3D translation) void set_body_mass (const std::string & body_name, double mass) void set_body_mass (size_t body_index, double mass) void set_body_name (size_t body_index, const std::string & body_name) void set_cast_shadows (bool cast_shadows=true) void set_color_mode (const std::string & color_mode) void set_color_mode (const std::string & color_mode, const std::string & body_name) void set_commands (const Eigen::VectorXd & commands, const std::vector< std::string > & dof_names={}) void set_coulomb_coeffs (const std::vector< double > & cfrictions, const std::vector< std::string > & dof_names={}) void set_coulomb_coeffs (double cfriction, const std::vector< std::string > & dof_names={}) void set_damping_coeffs (const std::vector< double > & damps, const std::vector< std::string > & dof_names={}) void set_damping_coeffs (double damp, const std::vector< std::string > & dof_names={}) void set_draw_axis (const std::string & body_name, double size=0.25) void set_external_force (const std::string & body_name, const Eigen::Vector3d & force, const Eigen::Vector3d & offset=Eigen::Vector3d::Zero(), bool force_local=false, bool offset_local=true) void set_external_force (size_t body_index, const Eigen::Vector3d & force, const Eigen::Vector3d & offset=Eigen::Vector3d::Zero(), bool force_local=false, bool offset_local=true) void set_external_torque (const std::string & body_name, const Eigen::Vector3d & torque, bool local=false) void set_external_torque (size_t body_index, const Eigen::Vector3d & torque, bool local=false) void set_force_lower_limits (const Eigen::VectorXd & forces, const std::vector< std::string > & dof_names={}) void set_force_upper_limits (const Eigen::VectorXd & forces, const std::vector< std::string > & dof_names={}) void set_forces (const Eigen::VectorXd & forces, const std::vector< std::string > & dof_names={}) void set_friction_coeff (const std::string & body_name, double value) void set_friction_coeff (size_t body_index, double value) void set_friction_coeffs (double value) void set_friction_dir (const std::string & body_name, const Eigen::Vector3d & direction) void set_friction_dir (size_t body_index, const Eigen::Vector3d & direction) void set_ghost (bool ghost=true) void set_joint_name (size_t joint_index, const std::string & joint_name) void set_mimic (const std::string & joint_name, const std::string & mimic_joint_name, double multiplier=1., double offset=0.) void set_position_enforced (const std::vector< bool > & enforced, const std::vector< std::string > & dof_names={}) void set_position_enforced (bool enforced, const std::vector< std::string > & dof_names={}) void set_position_lower_limits (const Eigen::VectorXd & positions, const std::vector< std::string > & dof_names={}) void set_position_upper_limits (const Eigen::VectorXd & positions, const std::vector< std::string > & dof_names={}) void set_positions (const Eigen::VectorXd & positions, const std::vector< std::string > & dof_names={}) void set_restitution_coeff (const std::string & body_name, double value) void set_restitution_coeff (size_t body_index, double value) void set_restitution_coeffs (double value) void set_secondary_friction_coeff (const std::string & body_name, double value) void set_secondary_friction_coeff (size_t body_index, double value) void set_secondary_friction_coeffs (double value) void set_self_collision (bool enable_self_collisions=true, bool enable_adjacent_collisions=false) void set_spring_stiffnesses (const std::vector< double > & stiffnesses, const std::vector< std::string > & dof_names={}) void set_spring_stiffnesses (double stiffness, const std::vector< std::string > & dof_names={}) void set_velocities (const Eigen::VectorXd & velocities, const std::vector< std::string > & dof_names={}) void set_velocity_lower_limits (const Eigen::VectorXd & velocities, const std::vector< std::string > & dof_names={}) void set_velocity_upper_limits (const Eigen::VectorXd & velocities, const std::vector< std::string > & dof_names={}) dart::dynamics::SkeletonPtr skeleton () std::vector< double > spring_stiffnesses (const std::vector< std::string > & dof_names={}) const void update (double t) void update_joint_dof_maps () Eigen::VectorXd vec_dof (const Eigen::VectorXd & vec, const std::vector< std::string > & dof_names) const Eigen::VectorXd velocities (const std::vector< std::string > & dof_names={}) const Eigen::VectorXd velocity_lower_limits (const std::vector< std::string > & dof_names={}) const Eigen::VectorXd velocity_upper_limits (const std::vector< std::string > & dof_names={}) const virtual ~Robot ()"},{"location":"api/classrobot__dart_1_1robots_1_1Iiwa/#public-static-functions-inherited-from-robot_dartrobot","title":"Public Static Functions inherited from robot_dart::Robot","text":"

See robot_dart::Robot

Type Name std::shared_ptr< Robot > create_box (const Eigen::Vector3d & dims, const Eigen::Isometry3d & tf, const std::string & type=\"free\", double mass=1.0, const Eigen::Vector4d & color=dart::Color::Red(1.0), const std::string & box_name=\"box\") std::shared_ptr< Robot > create_box (const Eigen::Vector3d & dims, const Eigen::Vector6d & pose=Eigen::Vector6d::Zero(), const std::string & type=\"free\", double mass=1.0, const Eigen::Vector4d & color=dart::Color::Red(1.0), const std::string & box_name=\"box\") std::shared_ptr< Robot > create_ellipsoid (const Eigen::Vector3d & dims, const Eigen::Isometry3d & tf, const std::string & type=\"free\", double mass=1.0, const Eigen::Vector4d & color=dart::Color::Red(1.0), const std::string & ellipsoid_name=\"ellipsoid\") std::shared_ptr< Robot > create_ellipsoid (const Eigen::Vector3d & dims, const Eigen::Vector6d & pose=Eigen::Vector6d::Zero(), const std::string & type=\"free\", double mass=1.0, const Eigen::Vector4d & color=dart::Color::Red(1.0), const std::string & ellipsoid_name=\"ellipsoid\")"},{"location":"api/classrobot__dart_1_1robots_1_1Iiwa/#protected-attributes","title":"Protected Attributes","text":"Type Name std::shared_ptr< sensor::ForceTorque > _ft_wrist"},{"location":"api/classrobot__dart_1_1robots_1_1Iiwa/#protected-attributes-inherited-from-robot_dartrobot","title":"Protected Attributes inherited from robot_dart::Robot","text":"

See robot_dart::Robot

Type Name std::vector< std::pair< dart::dynamics::BodyNode *, double > > _axis_shapes bool _cast_shadows std::vector< std::shared_ptr< control::RobotControl > > _controllers std::unordered_map< std::string, size_t > _dof_map bool _is_ghost std::unordered_map< std::string, size_t > _joint_map std::string _model_filename std::vector< std::pair< std::string, std::string > > _packages std::string _robot_name dart::dynamics::SkeletonPtr _skeleton"},{"location":"api/classrobot__dart_1_1robots_1_1Iiwa/#protected-functions","title":"Protected Functions","text":"Type Name virtual void _post_addition (RobotDARTSimu *) overrideFunction called by RobotDARTSimu object when adding the robot to the world. virtual void _post_removal (RobotDARTSimu *) overrideFunction called by RobotDARTSimu object when removing the robot to the world."},{"location":"api/classrobot__dart_1_1robots_1_1Iiwa/#protected-functions-inherited-from-robot_dartrobot","title":"Protected Functions inherited from robot_dart::Robot","text":"

See robot_dart::Robot

Type Name dart::dynamics::Joint::ActuatorType _actuator_type (size_t joint_index) const std::vector< dart::dynamics::Joint::ActuatorType > _actuator_types () const std::string _get_path (const std::string & filename) const Eigen::MatrixXd _jacobian (const Eigen::MatrixXd & full_jacobian, const std::vector< std::string > & dof_names) const dart::dynamics::SkeletonPtr _load_model (const std::string & filename, const std::vector< std::pair< std::string, std::string > > & packages=std::vector< std::pair< std::string, std::string > >(), bool is_urdf_string=false) Eigen::MatrixXd _mass_matrix (const Eigen::MatrixXd & full_mass_matrix, const std::vector< std::string > & dof_names) const virtual void _post_addition (RobotDARTSimu *) Function called by RobotDARTSimu object when adding the robot to the world. virtual void _post_removal (RobotDARTSimu *) Function called by RobotDARTSimu object when removing the robot to the world. void _set_actuator_type (size_t joint_index, dart::dynamics::Joint::ActuatorType type, bool override_mimic=false, bool override_base=false) void _set_actuator_types (const std::vector< dart::dynamics::Joint::ActuatorType > & types, bool override_mimic=false, bool override_base=false) void _set_actuator_types (dart::dynamics::Joint::ActuatorType type, bool override_mimic=false, bool override_base=false) void _set_color_mode (dart::dynamics::MeshShape::ColorMode color_mode, dart::dynamics::SkeletonPtr skel) void _set_color_mode (dart::dynamics::MeshShape::ColorMode color_mode, dart::dynamics::ShapeNode * sn)"},{"location":"api/classrobot__dart_1_1robots_1_1Iiwa/#public-functions-documentation","title":"Public Functions Documentation","text":""},{"location":"api/classrobot__dart_1_1robots_1_1Iiwa/#function-iiwa","title":"function Iiwa","text":"
robot_dart::robots::Iiwa::Iiwa (\nsize_t frequency=1000,\nconst std::string & urdf=\"iiwa/iiwa.urdf\",\nconst std::vector< std::pair< std::string, std::string > > & packages=('iiwa_description', 'iiwa/iiwa_description')\n) 
"},{"location":"api/classrobot__dart_1_1robots_1_1Iiwa/#function-ft_wrist","title":"function ft_wrist","text":"
inline const sensor::ForceTorque & robot_dart::robots::Iiwa::ft_wrist () const\n
"},{"location":"api/classrobot__dart_1_1robots_1_1Iiwa/#protected-attributes-documentation","title":"Protected Attributes Documentation","text":""},{"location":"api/classrobot__dart_1_1robots_1_1Iiwa/#variable-_ft_wrist","title":"variable _ft_wrist","text":"
std::shared_ptr<sensor::ForceTorque> robot_dart::robots::Iiwa::_ft_wrist;\n
"},{"location":"api/classrobot__dart_1_1robots_1_1Iiwa/#protected-functions-documentation","title":"Protected Functions Documentation","text":""},{"location":"api/classrobot__dart_1_1robots_1_1Iiwa/#function-_post_addition","title":"function _post_addition","text":"
virtual void robot_dart::robots::Iiwa::_post_addition (\nRobotDARTSimu *\n) override\n

Implements robot_dart::Robot::_post_addition

"},{"location":"api/classrobot__dart_1_1robots_1_1Iiwa/#function-_post_removal","title":"function _post_removal","text":"
virtual void robot_dart::robots::Iiwa::_post_removal (\nRobotDARTSimu *\n) override\n

Implements robot_dart::Robot::_post_removal

The documentation for this class was generated from the following file robot_dart/robots/iiwa.hpp

"},{"location":"api/classrobot__dart_1_1robots_1_1Pendulum/","title":"Class robot_dart::robots::Pendulum","text":"

ClassList > robot_dart > robots > Pendulum

Inherits the following classes: robot_dart::Robot

"},{"location":"api/classrobot__dart_1_1robots_1_1Pendulum/#public-functions","title":"Public Functions","text":"Type Name Pendulum (const std::string & urdf=\"pendulum.urdf\")"},{"location":"api/classrobot__dart_1_1robots_1_1Pendulum/#public-functions-inherited-from-robot_dartrobot","title":"Public Functions inherited from robot_dart::Robot","text":"

See robot_dart::Robot

Type Name Robot (const std::string & model_file, const std::vector< std::pair< std::string, std::string > > & packages, const std::string & robot_name=\"robot\", bool is_urdf_string=false, bool cast_shadows=true) Robot (const std::string & model_file, const std::string & robot_name=\"robot\", bool is_urdf_string=false, bool cast_shadows=true) Robot (dart::dynamics::SkeletonPtr skeleton, const std::string & robot_name=\"robot\", bool cast_shadows=true) Eigen::VectorXd acceleration_lower_limits (const std::vector< std::string > & dof_names={}) const Eigen::VectorXd acceleration_upper_limits (const std::vector< std::string > & dof_names={}) const Eigen::VectorXd accelerations (const std::vector< std::string > & dof_names={}) const std::vector< std::shared_ptr< control::RobotControl > > active_controllers () const std::string actuator_type (const std::string & joint_name) const std::vector< std::string > actuator_types (const std::vector< std::string > & joint_names={}) const void add_body_mass (const std::string & body_name, double mass) void add_body_mass (size_t body_index, double mass) void add_controller (const std::shared_ptr< control::RobotControl > & controller, double weight=1.0) void add_external_force (const std::string & body_name, const Eigen::Vector3d & force, const Eigen::Vector3d & offset=Eigen::Vector3d::Zero(), bool force_local=false, bool offset_local=true) void add_external_force (size_t body_index, const Eigen::Vector3d & force, const Eigen::Vector3d & offset=Eigen::Vector3d::Zero(), bool force_local=false, bool offset_local=true) void add_external_torque (const std::string & body_name, const Eigen::Vector3d & torque, bool local=false) void add_external_torque (size_t body_index, const Eigen::Vector3d & torque, bool local=false) bool adjacent_colliding () const Eigen::MatrixXd aug_mass_matrix (const std::vector< std::string > & dof_names={}) const Eigen::Isometry3d base_pose () const Eigen::Vector6d base_pose_vec () const Eigen::Vector6d body_acceleration (const std::string & body_name) const Eigen::Vector6d body_acceleration (size_t body_index) const size_t body_index (const std::string & body_name) const double body_mass (const std::string & body_name) const double body_mass (size_t body_index) const std::string body_name (size_t body_index) const std::vector< std::string > body_names () const dart::dynamics::BodyNode * body_node (const std::string & body_name) dart::dynamics::BodyNode * body_node (size_t body_index) Eigen::Isometry3d body_pose (const std::string & body_name) const Eigen::Isometry3d body_pose (size_t body_index) const Eigen::Vector6d body_pose_vec (const std::string & body_name) const Eigen::Vector6d body_pose_vec (size_t body_index) const Eigen::Vector6d body_velocity (const std::string & body_name) const Eigen::Vector6d body_velocity (size_t body_index) const bool cast_shadows () const void clear_controllers () void clear_external_forces () void clear_internal_forces () std::shared_ptr< Robot > clone () const std::shared_ptr< Robot > clone_ghost (const std::string & ghost_name=\"ghost\", const Eigen::Vector4d & ghost_color={0.3, 0.3, 0.3, 0.7}) const Eigen::Vector3d com () const Eigen::Vector6d com_acceleration () const Eigen::MatrixXd com_jacobian (const std::vector< std::string > & dof_names={}) const Eigen::MatrixXd com_jacobian_deriv (const std::vector< std::string > & dof_names={}) const Eigen::Vector6d com_velocity () const Eigen::VectorXd commands (const std::vector< std::string > & dof_names={}) const Eigen::VectorXd constraint_forces (const std::vector< std::string > & dof_names={}) const std::shared_ptr< control::RobotControl > controller (size_t index) const std::vector< std::shared_ptr< control::RobotControl > > controllers () const Eigen::VectorXd coriolis_forces (const std::vector< std::string > & dof_names={}) const Eigen::VectorXd coriolis_gravity_forces (const std::vector< std::string > & dof_names={}) const std::vector< double > coulomb_coeffs (const std::vector< std::string > & dof_names={}) const std::vector< double > damping_coeffs (const std::vector< std::string > & dof_names={}) const dart::dynamics::DegreeOfFreedom * dof (const std::string & dof_name) dart::dynamics::DegreeOfFreedom * dof (size_t dof_index) size_t dof_index (const std::string & dof_name) const const std::unordered_map< std::string, size_t > & dof_map () const std::string dof_name (size_t dof_index) const std::vector< std::string > dof_names (bool filter_mimics=false, bool filter_locked=false, bool filter_passive=false) const const std::vector< std::pair< dart::dynamics::BodyNode *, double > > & drawing_axes () const Eigen::Vector6d external_forces (const std::string & body_name) const Eigen::Vector6d external_forces (size_t body_index) const void fix_to_world () bool fixed () const Eigen::VectorXd force_lower_limits (const std::vector< std::string > & dof_names={}) const void force_position_bounds () std::pair< Eigen::Vector6d, Eigen::Vector6d > force_torque (size_t joint_index) const Eigen::VectorXd force_upper_limits (const std::vector< std::string > & dof_names={}) const Eigen::VectorXd forces (const std::vector< std::string > & dof_names={}) const bool free () const void free_from_world (const Eigen::Vector6d & pose=Eigen::Vector6d::Zero()) double friction_coeff (const std::string & body_name) double friction_coeff (size_t body_index) Eigen::Vector3d friction_dir (const std::string & body_name) Eigen::Vector3d friction_dir (size_t body_index) bool ghost () const Eigen::VectorXd gravity_forces (const std::vector< std::string > & dof_names={}) const Eigen::MatrixXd inv_aug_mass_matrix (const std::vector< std::string > & dof_names={}) const Eigen::MatrixXd inv_mass_matrix (const std::vector< std::string > & dof_names={}) const Eigen::MatrixXd jacobian (const std::string & body_name, const std::vector< std::string > & dof_names={}) const Eigen::MatrixXd jacobian_deriv (const std::string & body_name, const std::vector< std::string > & dof_names={}) const dart::dynamics::Joint * joint (const std::string & joint_name) dart::dynamics::Joint * joint (size_t joint_index) size_t joint_index (const std::string & joint_name) const const std::unordered_map< std::string, size_t > & joint_map () const std::string joint_name (size_t joint_index) const std::vector< std::string > joint_names () const std::vector< std::string > locked_dof_names () const Eigen::MatrixXd mass_matrix (const std::vector< std::string > & dof_names={}) const std::vector< std::string > mimic_dof_names () const const std::string & model_filename () const const std::vector< std::pair< std::string, std::string > > & model_packages () const const std::string & name () const size_t num_bodies () const size_t num_controllers () const size_t num_dofs () const size_t num_joints () const std::vector< std::string > passive_dof_names () const std::vector< bool > position_enforced (const std::vector< std::string > & dof_names={}) const Eigen::VectorXd position_lower_limits (const std::vector< std::string > & dof_names={}) const Eigen::VectorXd position_upper_limits (const std::vector< std::string > & dof_names={}) const Eigen::VectorXd positions (const std::vector< std::string > & dof_names={}) const void reinit_controllers () void remove_all_drawing_axis () void remove_controller (const std::shared_ptr< control::RobotControl > & controller) void remove_controller (size_t index) virtual void reset () void reset_commands () double restitution_coeff (const std::string & body_name) double restitution_coeff (size_t body_index) double secondary_friction_coeff (const std::string & body_name) double secondary_friction_coeff (size_t body_index) bool self_colliding () const void set_acceleration_lower_limits (const Eigen::VectorXd & accelerations, const std::vector< std::string > & dof_names={}) void set_acceleration_upper_limits (const Eigen::VectorXd & accelerations, const std::vector< std::string > & dof_names={}) void set_accelerations (const Eigen::VectorXd & accelerations, const std::vector< std::string > & dof_names={}) void set_actuator_type (const std::string & type, const std::string & joint_name, bool override_mimic=false, bool override_base=false) void set_actuator_types (const std::string & type, const std::vector< std::string > & joint_names={}, bool override_mimic=false, bool override_base=false) void set_base_pose (const Eigen::Isometry3d & tf) void set_base_pose (const Eigen::Vector6d & pose) set base pose: pose is a 6D vector (first 3D orientation in angle-axis and last 3D translation) void set_body_mass (const std::string & body_name, double mass) void set_body_mass (size_t body_index, double mass) void set_body_name (size_t body_index, const std::string & body_name) void set_cast_shadows (bool cast_shadows=true) void set_color_mode (const std::string & color_mode) void set_color_mode (const std::string & color_mode, const std::string & body_name) void set_commands (const Eigen::VectorXd & commands, const std::vector< std::string > & dof_names={}) void set_coulomb_coeffs (const std::vector< double > & cfrictions, const std::vector< std::string > & dof_names={}) void set_coulomb_coeffs (double cfriction, const std::vector< std::string > & dof_names={}) void set_damping_coeffs (const std::vector< double > & damps, const std::vector< std::string > & dof_names={}) void set_damping_coeffs (double damp, const std::vector< std::string > & dof_names={}) void set_draw_axis (const std::string & body_name, double size=0.25) void set_external_force (const std::string & body_name, const Eigen::Vector3d & force, const Eigen::Vector3d & offset=Eigen::Vector3d::Zero(), bool force_local=false, bool offset_local=true) void set_external_force (size_t body_index, const Eigen::Vector3d & force, const Eigen::Vector3d & offset=Eigen::Vector3d::Zero(), bool force_local=false, bool offset_local=true) void set_external_torque (const std::string & body_name, const Eigen::Vector3d & torque, bool local=false) void set_external_torque (size_t body_index, const Eigen::Vector3d & torque, bool local=false) void set_force_lower_limits (const Eigen::VectorXd & forces, const std::vector< std::string > & dof_names={}) void set_force_upper_limits (const Eigen::VectorXd & forces, const std::vector< std::string > & dof_names={}) void set_forces (const Eigen::VectorXd & forces, const std::vector< std::string > & dof_names={}) void set_friction_coeff (const std::string & body_name, double value) void set_friction_coeff (size_t body_index, double value) void set_friction_coeffs (double value) void set_friction_dir (const std::string & body_name, const Eigen::Vector3d & direction) void set_friction_dir (size_t body_index, const Eigen::Vector3d & direction) void set_ghost (bool ghost=true) void set_joint_name (size_t joint_index, const std::string & joint_name) void set_mimic (const std::string & joint_name, const std::string & mimic_joint_name, double multiplier=1., double offset=0.) void set_position_enforced (const std::vector< bool > & enforced, const std::vector< std::string > & dof_names={}) void set_position_enforced (bool enforced, const std::vector< std::string > & dof_names={}) void set_position_lower_limits (const Eigen::VectorXd & positions, const std::vector< std::string > & dof_names={}) void set_position_upper_limits (const Eigen::VectorXd & positions, const std::vector< std::string > & dof_names={}) void set_positions (const Eigen::VectorXd & positions, const std::vector< std::string > & dof_names={}) void set_restitution_coeff (const std::string & body_name, double value) void set_restitution_coeff (size_t body_index, double value) void set_restitution_coeffs (double value) void set_secondary_friction_coeff (const std::string & body_name, double value) void set_secondary_friction_coeff (size_t body_index, double value) void set_secondary_friction_coeffs (double value) void set_self_collision (bool enable_self_collisions=true, bool enable_adjacent_collisions=false) void set_spring_stiffnesses (const std::vector< double > & stiffnesses, const std::vector< std::string > & dof_names={}) void set_spring_stiffnesses (double stiffness, const std::vector< std::string > & dof_names={}) void set_velocities (const Eigen::VectorXd & velocities, const std::vector< std::string > & dof_names={}) void set_velocity_lower_limits (const Eigen::VectorXd & velocities, const std::vector< std::string > & dof_names={}) void set_velocity_upper_limits (const Eigen::VectorXd & velocities, const std::vector< std::string > & dof_names={}) dart::dynamics::SkeletonPtr skeleton () std::vector< double > spring_stiffnesses (const std::vector< std::string > & dof_names={}) const void update (double t) void update_joint_dof_maps () Eigen::VectorXd vec_dof (const Eigen::VectorXd & vec, const std::vector< std::string > & dof_names) const Eigen::VectorXd velocities (const std::vector< std::string > & dof_names={}) const Eigen::VectorXd velocity_lower_limits (const std::vector< std::string > & dof_names={}) const Eigen::VectorXd velocity_upper_limits (const std::vector< std::string > & dof_names={}) const virtual ~Robot ()"},{"location":"api/classrobot__dart_1_1robots_1_1Pendulum/#public-static-functions-inherited-from-robot_dartrobot","title":"Public Static Functions inherited from robot_dart::Robot","text":"

See robot_dart::Robot

Type Name std::shared_ptr< Robot > create_box (const Eigen::Vector3d & dims, const Eigen::Isometry3d & tf, const std::string & type=\"free\", double mass=1.0, const Eigen::Vector4d & color=dart::Color::Red(1.0), const std::string & box_name=\"box\") std::shared_ptr< Robot > create_box (const Eigen::Vector3d & dims, const Eigen::Vector6d & pose=Eigen::Vector6d::Zero(), const std::string & type=\"free\", double mass=1.0, const Eigen::Vector4d & color=dart::Color::Red(1.0), const std::string & box_name=\"box\") std::shared_ptr< Robot > create_ellipsoid (const Eigen::Vector3d & dims, const Eigen::Isometry3d & tf, const std::string & type=\"free\", double mass=1.0, const Eigen::Vector4d & color=dart::Color::Red(1.0), const std::string & ellipsoid_name=\"ellipsoid\") std::shared_ptr< Robot > create_ellipsoid (const Eigen::Vector3d & dims, const Eigen::Vector6d & pose=Eigen::Vector6d::Zero(), const std::string & type=\"free\", double mass=1.0, const Eigen::Vector4d & color=dart::Color::Red(1.0), const std::string & ellipsoid_name=\"ellipsoid\")"},{"location":"api/classrobot__dart_1_1robots_1_1Pendulum/#protected-attributes-inherited-from-robot_dartrobot","title":"Protected Attributes inherited from robot_dart::Robot","text":"

See robot_dart::Robot

Type Name std::vector< std::pair< dart::dynamics::BodyNode *, double > > _axis_shapes bool _cast_shadows std::vector< std::shared_ptr< control::RobotControl > > _controllers std::unordered_map< std::string, size_t > _dof_map bool _is_ghost std::unordered_map< std::string, size_t > _joint_map std::string _model_filename std::vector< std::pair< std::string, std::string > > _packages std::string _robot_name dart::dynamics::SkeletonPtr _skeleton"},{"location":"api/classrobot__dart_1_1robots_1_1Pendulum/#protected-functions-inherited-from-robot_dartrobot","title":"Protected Functions inherited from robot_dart::Robot","text":"

See robot_dart::Robot

Type Name dart::dynamics::Joint::ActuatorType _actuator_type (size_t joint_index) const std::vector< dart::dynamics::Joint::ActuatorType > _actuator_types () const std::string _get_path (const std::string & filename) const Eigen::MatrixXd _jacobian (const Eigen::MatrixXd & full_jacobian, const std::vector< std::string > & dof_names) const dart::dynamics::SkeletonPtr _load_model (const std::string & filename, const std::vector< std::pair< std::string, std::string > > & packages=std::vector< std::pair< std::string, std::string > >(), bool is_urdf_string=false) Eigen::MatrixXd _mass_matrix (const Eigen::MatrixXd & full_mass_matrix, const std::vector< std::string > & dof_names) const virtual void _post_addition (RobotDARTSimu *) Function called by RobotDARTSimu object when adding the robot to the world. virtual void _post_removal (RobotDARTSimu *) Function called by RobotDARTSimu object when removing the robot to the world. void _set_actuator_type (size_t joint_index, dart::dynamics::Joint::ActuatorType type, bool override_mimic=false, bool override_base=false) void _set_actuator_types (const std::vector< dart::dynamics::Joint::ActuatorType > & types, bool override_mimic=false, bool override_base=false) void _set_actuator_types (dart::dynamics::Joint::ActuatorType type, bool override_mimic=false, bool override_base=false) void _set_color_mode (dart::dynamics::MeshShape::ColorMode color_mode, dart::dynamics::SkeletonPtr skel) void _set_color_mode (dart::dynamics::MeshShape::ColorMode color_mode, dart::dynamics::ShapeNode * sn)"},{"location":"api/classrobot__dart_1_1robots_1_1Pendulum/#public-functions-documentation","title":"Public Functions Documentation","text":""},{"location":"api/classrobot__dart_1_1robots_1_1Pendulum/#function-pendulum","title":"function Pendulum","text":"
inline robot_dart::robots::Pendulum::Pendulum (\nconst std::string & urdf=\"pendulum.urdf\"\n) 

The documentation for this class was generated from the following file robot_dart/robots/pendulum.hpp

"},{"location":"api/classrobot__dart_1_1robots_1_1Talos/","title":"Class robot_dart::robots::Talos","text":"

ClassList > robot_dart > robots > Talos

datasheet: https://pal-robotics.com/wp-content/uploads/2019/07/Datasheet_TALOS.pdf __

Inherits the following classes: robot_dart::Robot

Inherited by the following classes: robot_dart::robots::TalosFastCollision, robot_dart::robots::TalosLight

"},{"location":"api/classrobot__dart_1_1robots_1_1Talos/#public-types","title":"Public Types","text":"Type Name typedef std::unordered_map< std::string, std::shared_ptr< sensor::Torque > > torque_map_t"},{"location":"api/classrobot__dart_1_1robots_1_1Talos/#public-functions","title":"Public Functions","text":"Type Name Talos (size_t frequency=1000, const std::string & urdf=\"talos/talos.urdf\", const std::vector< std::pair< std::string, std::string > > & packages=('talos\\_description', 'talos/talos\\_description')) const sensor::ForceTorque & ft_foot_left () const const sensor::ForceTorque & ft_foot_right () const const sensor::ForceTorque & ft_wrist_left () const const sensor::ForceTorque & ft_wrist_right () const const sensor::IMU & imu () const virtual void reset () override const torque_map_t & torques () const"},{"location":"api/classrobot__dart_1_1robots_1_1Talos/#public-functions-inherited-from-robot_dartrobot","title":"Public Functions inherited from robot_dart::Robot","text":"

See robot_dart::Robot

Type Name Robot (const std::string & model_file, const std::vector< std::pair< std::string, std::string > > & packages, const std::string & robot_name=\"robot\", bool is_urdf_string=false, bool cast_shadows=true) Robot (const std::string & model_file, const std::string & robot_name=\"robot\", bool is_urdf_string=false, bool cast_shadows=true) Robot (dart::dynamics::SkeletonPtr skeleton, const std::string & robot_name=\"robot\", bool cast_shadows=true) Eigen::VectorXd acceleration_lower_limits (const std::vector< std::string > & dof_names={}) const Eigen::VectorXd acceleration_upper_limits (const std::vector< std::string > & dof_names={}) const Eigen::VectorXd accelerations (const std::vector< std::string > & dof_names={}) const std::vector< std::shared_ptr< control::RobotControl > > active_controllers () const std::string actuator_type (const std::string & joint_name) const std::vector< std::string > actuator_types (const std::vector< std::string > & joint_names={}) const void add_body_mass (const std::string & body_name, double mass) void add_body_mass (size_t body_index, double mass) void add_controller (const std::shared_ptr< control::RobotControl > & controller, double weight=1.0) void add_external_force (const std::string & body_name, const Eigen::Vector3d & force, const Eigen::Vector3d & offset=Eigen::Vector3d::Zero(), bool force_local=false, bool offset_local=true) void add_external_force (size_t body_index, const Eigen::Vector3d & force, const Eigen::Vector3d & offset=Eigen::Vector3d::Zero(), bool force_local=false, bool offset_local=true) void add_external_torque (const std::string & body_name, const Eigen::Vector3d & torque, bool local=false) void add_external_torque (size_t body_index, const Eigen::Vector3d & torque, bool local=false) bool adjacent_colliding () const Eigen::MatrixXd aug_mass_matrix (const std::vector< std::string > & dof_names={}) const Eigen::Isometry3d base_pose () const Eigen::Vector6d base_pose_vec () const Eigen::Vector6d body_acceleration (const std::string & body_name) const Eigen::Vector6d body_acceleration (size_t body_index) const size_t body_index (const std::string & body_name) const double body_mass (const std::string & body_name) const double body_mass (size_t body_index) const std::string body_name (size_t body_index) const std::vector< std::string > body_names () const dart::dynamics::BodyNode * body_node (const std::string & body_name) dart::dynamics::BodyNode * body_node (size_t body_index) Eigen::Isometry3d body_pose (const std::string & body_name) const Eigen::Isometry3d body_pose (size_t body_index) const Eigen::Vector6d body_pose_vec (const std::string & body_name) const Eigen::Vector6d body_pose_vec (size_t body_index) const Eigen::Vector6d body_velocity (const std::string & body_name) const Eigen::Vector6d body_velocity (size_t body_index) const bool cast_shadows () const void clear_controllers () void clear_external_forces () void clear_internal_forces () std::shared_ptr< Robot > clone () const std::shared_ptr< Robot > clone_ghost (const std::string & ghost_name=\"ghost\", const Eigen::Vector4d & ghost_color={0.3, 0.3, 0.3, 0.7}) const Eigen::Vector3d com () const Eigen::Vector6d com_acceleration () const Eigen::MatrixXd com_jacobian (const std::vector< std::string > & dof_names={}) const Eigen::MatrixXd com_jacobian_deriv (const std::vector< std::string > & dof_names={}) const Eigen::Vector6d com_velocity () const Eigen::VectorXd commands (const std::vector< std::string > & dof_names={}) const Eigen::VectorXd constraint_forces (const std::vector< std::string > & dof_names={}) const std::shared_ptr< control::RobotControl > controller (size_t index) const std::vector< std::shared_ptr< control::RobotControl > > controllers () const Eigen::VectorXd coriolis_forces (const std::vector< std::string > & dof_names={}) const Eigen::VectorXd coriolis_gravity_forces (const std::vector< std::string > & dof_names={}) const std::vector< double > coulomb_coeffs (const std::vector< std::string > & dof_names={}) const std::vector< double > damping_coeffs (const std::vector< std::string > & dof_names={}) const dart::dynamics::DegreeOfFreedom * dof (const std::string & dof_name) dart::dynamics::DegreeOfFreedom * dof (size_t dof_index) size_t dof_index (const std::string & dof_name) const const std::unordered_map< std::string, size_t > & dof_map () const std::string dof_name (size_t dof_index) const std::vector< std::string > dof_names (bool filter_mimics=false, bool filter_locked=false, bool filter_passive=false) const const std::vector< std::pair< dart::dynamics::BodyNode *, double > > & drawing_axes () const Eigen::Vector6d external_forces (const std::string & body_name) const Eigen::Vector6d external_forces (size_t body_index) const void fix_to_world () bool fixed () const Eigen::VectorXd force_lower_limits (const std::vector< std::string > & dof_names={}) const void force_position_bounds () std::pair< Eigen::Vector6d, Eigen::Vector6d > force_torque (size_t joint_index) const Eigen::VectorXd force_upper_limits (const std::vector< std::string > & dof_names={}) const Eigen::VectorXd forces (const std::vector< std::string > & dof_names={}) const bool free () const void free_from_world (const Eigen::Vector6d & pose=Eigen::Vector6d::Zero()) double friction_coeff (const std::string & body_name) double friction_coeff (size_t body_index) Eigen::Vector3d friction_dir (const std::string & body_name) Eigen::Vector3d friction_dir (size_t body_index) bool ghost () const Eigen::VectorXd gravity_forces (const std::vector< std::string > & dof_names={}) const Eigen::MatrixXd inv_aug_mass_matrix (const std::vector< std::string > & dof_names={}) const Eigen::MatrixXd inv_mass_matrix (const std::vector< std::string > & dof_names={}) const Eigen::MatrixXd jacobian (const std::string & body_name, const std::vector< std::string > & dof_names={}) const Eigen::MatrixXd jacobian_deriv (const std::string & body_name, const std::vector< std::string > & dof_names={}) const dart::dynamics::Joint * joint (const std::string & joint_name) dart::dynamics::Joint * joint (size_t joint_index) size_t joint_index (const std::string & joint_name) const const std::unordered_map< std::string, size_t > & joint_map () const std::string joint_name (size_t joint_index) const std::vector< std::string > joint_names () const std::vector< std::string > locked_dof_names () const Eigen::MatrixXd mass_matrix (const std::vector< std::string > & dof_names={}) const std::vector< std::string > mimic_dof_names () const const std::string & model_filename () const const std::vector< std::pair< std::string, std::string > > & model_packages () const const std::string & name () const size_t num_bodies () const size_t num_controllers () const size_t num_dofs () const size_t num_joints () const std::vector< std::string > passive_dof_names () const std::vector< bool > position_enforced (const std::vector< std::string > & dof_names={}) const Eigen::VectorXd position_lower_limits (const std::vector< std::string > & dof_names={}) const Eigen::VectorXd position_upper_limits (const std::vector< std::string > & dof_names={}) const Eigen::VectorXd positions (const std::vector< std::string > & dof_names={}) const void reinit_controllers () void remove_all_drawing_axis () void remove_controller (const std::shared_ptr< control::RobotControl > & controller) void remove_controller (size_t index) virtual void reset () void reset_commands () double restitution_coeff (const std::string & body_name) double restitution_coeff (size_t body_index) double secondary_friction_coeff (const std::string & body_name) double secondary_friction_coeff (size_t body_index) bool self_colliding () const void set_acceleration_lower_limits (const Eigen::VectorXd & accelerations, const std::vector< std::string > & dof_names={}) void set_acceleration_upper_limits (const Eigen::VectorXd & accelerations, const std::vector< std::string > & dof_names={}) void set_accelerations (const Eigen::VectorXd & accelerations, const std::vector< std::string > & dof_names={}) void set_actuator_type (const std::string & type, const std::string & joint_name, bool override_mimic=false, bool override_base=false) void set_actuator_types (const std::string & type, const std::vector< std::string > & joint_names={}, bool override_mimic=false, bool override_base=false) void set_base_pose (const Eigen::Isometry3d & tf) void set_base_pose (const Eigen::Vector6d & pose) set base pose: pose is a 6D vector (first 3D orientation in angle-axis and last 3D translation) void set_body_mass (const std::string & body_name, double mass) void set_body_mass (size_t body_index, double mass) void set_body_name (size_t body_index, const std::string & body_name) void set_cast_shadows (bool cast_shadows=true) void set_color_mode (const std::string & color_mode) void set_color_mode (const std::string & color_mode, const std::string & body_name) void set_commands (const Eigen::VectorXd & commands, const std::vector< std::string > & dof_names={}) void set_coulomb_coeffs (const std::vector< double > & cfrictions, const std::vector< std::string > & dof_names={}) void set_coulomb_coeffs (double cfriction, const std::vector< std::string > & dof_names={}) void set_damping_coeffs (const std::vector< double > & damps, const std::vector< std::string > & dof_names={}) void set_damping_coeffs (double damp, const std::vector< std::string > & dof_names={}) void set_draw_axis (const std::string & body_name, double size=0.25) void set_external_force (const std::string & body_name, const Eigen::Vector3d & force, const Eigen::Vector3d & offset=Eigen::Vector3d::Zero(), bool force_local=false, bool offset_local=true) void set_external_force (size_t body_index, const Eigen::Vector3d & force, const Eigen::Vector3d & offset=Eigen::Vector3d::Zero(), bool force_local=false, bool offset_local=true) void set_external_torque (const std::string & body_name, const Eigen::Vector3d & torque, bool local=false) void set_external_torque (size_t body_index, const Eigen::Vector3d & torque, bool local=false) void set_force_lower_limits (const Eigen::VectorXd & forces, const std::vector< std::string > & dof_names={}) void set_force_upper_limits (const Eigen::VectorXd & forces, const std::vector< std::string > & dof_names={}) void set_forces (const Eigen::VectorXd & forces, const std::vector< std::string > & dof_names={}) void set_friction_coeff (const std::string & body_name, double value) void set_friction_coeff (size_t body_index, double value) void set_friction_coeffs (double value) void set_friction_dir (const std::string & body_name, const Eigen::Vector3d & direction) void set_friction_dir (size_t body_index, const Eigen::Vector3d & direction) void set_ghost (bool ghost=true) void set_joint_name (size_t joint_index, const std::string & joint_name) void set_mimic (const std::string & joint_name, const std::string & mimic_joint_name, double multiplier=1., double offset=0.) void set_position_enforced (const std::vector< bool > & enforced, const std::vector< std::string > & dof_names={}) void set_position_enforced (bool enforced, const std::vector< std::string > & dof_names={}) void set_position_lower_limits (const Eigen::VectorXd & positions, const std::vector< std::string > & dof_names={}) void set_position_upper_limits (const Eigen::VectorXd & positions, const std::vector< std::string > & dof_names={}) void set_positions (const Eigen::VectorXd & positions, const std::vector< std::string > & dof_names={}) void set_restitution_coeff (const std::string & body_name, double value) void set_restitution_coeff (size_t body_index, double value) void set_restitution_coeffs (double value) void set_secondary_friction_coeff (const std::string & body_name, double value) void set_secondary_friction_coeff (size_t body_index, double value) void set_secondary_friction_coeffs (double value) void set_self_collision (bool enable_self_collisions=true, bool enable_adjacent_collisions=false) void set_spring_stiffnesses (const std::vector< double > & stiffnesses, const std::vector< std::string > & dof_names={}) void set_spring_stiffnesses (double stiffness, const std::vector< std::string > & dof_names={}) void set_velocities (const Eigen::VectorXd & velocities, const std::vector< std::string > & dof_names={}) void set_velocity_lower_limits (const Eigen::VectorXd & velocities, const std::vector< std::string > & dof_names={}) void set_velocity_upper_limits (const Eigen::VectorXd & velocities, const std::vector< std::string > & dof_names={}) dart::dynamics::SkeletonPtr skeleton () std::vector< double > spring_stiffnesses (const std::vector< std::string > & dof_names={}) const void update (double t) void update_joint_dof_maps () Eigen::VectorXd vec_dof (const Eigen::VectorXd & vec, const std::vector< std::string > & dof_names) const Eigen::VectorXd velocities (const std::vector< std::string > & dof_names={}) const Eigen::VectorXd velocity_lower_limits (const std::vector< std::string > & dof_names={}) const Eigen::VectorXd velocity_upper_limits (const std::vector< std::string > & dof_names={}) const virtual ~Robot ()"},{"location":"api/classrobot__dart_1_1robots_1_1Talos/#public-static-functions-inherited-from-robot_dartrobot","title":"Public Static Functions inherited from robot_dart::Robot","text":"

See robot_dart::Robot

Type Name std::shared_ptr< Robot > create_box (const Eigen::Vector3d & dims, const Eigen::Isometry3d & tf, const std::string & type=\"free\", double mass=1.0, const Eigen::Vector4d & color=dart::Color::Red(1.0), const std::string & box_name=\"box\") std::shared_ptr< Robot > create_box (const Eigen::Vector3d & dims, const Eigen::Vector6d & pose=Eigen::Vector6d::Zero(), const std::string & type=\"free\", double mass=1.0, const Eigen::Vector4d & color=dart::Color::Red(1.0), const std::string & box_name=\"box\") std::shared_ptr< Robot > create_ellipsoid (const Eigen::Vector3d & dims, const Eigen::Isometry3d & tf, const std::string & type=\"free\", double mass=1.0, const Eigen::Vector4d & color=dart::Color::Red(1.0), const std::string & ellipsoid_name=\"ellipsoid\") std::shared_ptr< Robot > create_ellipsoid (const Eigen::Vector3d & dims, const Eigen::Vector6d & pose=Eigen::Vector6d::Zero(), const std::string & type=\"free\", double mass=1.0, const Eigen::Vector4d & color=dart::Color::Red(1.0), const std::string & ellipsoid_name=\"ellipsoid\")"},{"location":"api/classrobot__dart_1_1robots_1_1Talos/#protected-attributes","title":"Protected Attributes","text":"Type Name size_t _frequency std::shared_ptr< sensor::ForceTorque > _ft_foot_left std::shared_ptr< sensor::ForceTorque > _ft_foot_right std::shared_ptr< sensor::ForceTorque > _ft_wrist_left std::shared_ptr< sensor::ForceTorque > _ft_wrist_right std::shared_ptr< sensor::IMU > _imu torque_map_t _torques"},{"location":"api/classrobot__dart_1_1robots_1_1Talos/#protected-attributes-inherited-from-robot_dartrobot","title":"Protected Attributes inherited from robot_dart::Robot","text":"

See robot_dart::Robot

Type Name std::vector< std::pair< dart::dynamics::BodyNode *, double > > _axis_shapes bool _cast_shadows std::vector< std::shared_ptr< control::RobotControl > > _controllers std::unordered_map< std::string, size_t > _dof_map bool _is_ghost std::unordered_map< std::string, size_t > _joint_map std::string _model_filename std::vector< std::pair< std::string, std::string > > _packages std::string _robot_name dart::dynamics::SkeletonPtr _skeleton"},{"location":"api/classrobot__dart_1_1robots_1_1Talos/#protected-functions","title":"Protected Functions","text":"Type Name virtual void _post_addition (RobotDARTSimu *) overrideFunction called by RobotDARTSimu object when adding the robot to the world. virtual void _post_removal (RobotDARTSimu *) overrideFunction called by RobotDARTSimu object when removing the robot to the world."},{"location":"api/classrobot__dart_1_1robots_1_1Talos/#protected-functions-inherited-from-robot_dartrobot","title":"Protected Functions inherited from robot_dart::Robot","text":"

See robot_dart::Robot

Type Name dart::dynamics::Joint::ActuatorType _actuator_type (size_t joint_index) const std::vector< dart::dynamics::Joint::ActuatorType > _actuator_types () const std::string _get_path (const std::string & filename) const Eigen::MatrixXd _jacobian (const Eigen::MatrixXd & full_jacobian, const std::vector< std::string > & dof_names) const dart::dynamics::SkeletonPtr _load_model (const std::string & filename, const std::vector< std::pair< std::string, std::string > > & packages=std::vector< std::pair< std::string, std::string > >(), bool is_urdf_string=false) Eigen::MatrixXd _mass_matrix (const Eigen::MatrixXd & full_mass_matrix, const std::vector< std::string > & dof_names) const virtual void _post_addition (RobotDARTSimu *) Function called by RobotDARTSimu object when adding the robot to the world. virtual void _post_removal (RobotDARTSimu *) Function called by RobotDARTSimu object when removing the robot to the world. void _set_actuator_type (size_t joint_index, dart::dynamics::Joint::ActuatorType type, bool override_mimic=false, bool override_base=false) void _set_actuator_types (const std::vector< dart::dynamics::Joint::ActuatorType > & types, bool override_mimic=false, bool override_base=false) void _set_actuator_types (dart::dynamics::Joint::ActuatorType type, bool override_mimic=false, bool override_base=false) void _set_color_mode (dart::dynamics::MeshShape::ColorMode color_mode, dart::dynamics::SkeletonPtr skel) void _set_color_mode (dart::dynamics::MeshShape::ColorMode color_mode, dart::dynamics::ShapeNode * sn)"},{"location":"api/classrobot__dart_1_1robots_1_1Talos/#public-types-documentation","title":"Public Types Documentation","text":""},{"location":"api/classrobot__dart_1_1robots_1_1Talos/#typedef-torque_map_t","title":"typedef torque_map_t","text":"
using robot_dart::robots::Talos::torque_map_t =  std::unordered_map<std::string, std::shared_ptr<sensor::Torque> >;\n
"},{"location":"api/classrobot__dart_1_1robots_1_1Talos/#public-functions-documentation","title":"Public Functions Documentation","text":""},{"location":"api/classrobot__dart_1_1robots_1_1Talos/#function-talos","title":"function Talos","text":"
robot_dart::robots::Talos::Talos (\nsize_t frequency=1000,\nconst std::string & urdf=\"talos/talos.urdf\",\nconst std::vector< std::pair< std::string, std::string > > & packages=('talos_description', 'talos/talos_description')\n) 
"},{"location":"api/classrobot__dart_1_1robots_1_1Talos/#function-ft_foot_left","title":"function ft_foot_left","text":"
inline const sensor::ForceTorque & robot_dart::robots::Talos::ft_foot_left () const\n
"},{"location":"api/classrobot__dart_1_1robots_1_1Talos/#function-ft_foot_right","title":"function ft_foot_right","text":"
inline const sensor::ForceTorque & robot_dart::robots::Talos::ft_foot_right () const\n
"},{"location":"api/classrobot__dart_1_1robots_1_1Talos/#function-ft_wrist_left","title":"function ft_wrist_left","text":"
inline const sensor::ForceTorque & robot_dart::robots::Talos::ft_wrist_left () const\n
"},{"location":"api/classrobot__dart_1_1robots_1_1Talos/#function-ft_wrist_right","title":"function ft_wrist_right","text":"
inline const sensor::ForceTorque & robot_dart::robots::Talos::ft_wrist_right () const\n
"},{"location":"api/classrobot__dart_1_1robots_1_1Talos/#function-imu","title":"function imu","text":"
inline const sensor::IMU & robot_dart::robots::Talos::imu () const\n
"},{"location":"api/classrobot__dart_1_1robots_1_1Talos/#function-reset","title":"function reset","text":"
virtual void robot_dart::robots::Talos::reset () override\n

Implements robot_dart::Robot::reset

"},{"location":"api/classrobot__dart_1_1robots_1_1Talos/#function-torques","title":"function torques","text":"
inline const torque_map_t & robot_dart::robots::Talos::torques () const\n
"},{"location":"api/classrobot__dart_1_1robots_1_1Talos/#protected-attributes-documentation","title":"Protected Attributes Documentation","text":""},{"location":"api/classrobot__dart_1_1robots_1_1Talos/#variable-_frequency","title":"variable _frequency","text":"
size_t robot_dart::robots::Talos::_frequency;\n
"},{"location":"api/classrobot__dart_1_1robots_1_1Talos/#variable-_ft_foot_left","title":"variable _ft_foot_left","text":"
std::shared_ptr<sensor::ForceTorque> robot_dart::robots::Talos::_ft_foot_left;\n
"},{"location":"api/classrobot__dart_1_1robots_1_1Talos/#variable-_ft_foot_right","title":"variable _ft_foot_right","text":"
std::shared_ptr<sensor::ForceTorque> robot_dart::robots::Talos::_ft_foot_right;\n
"},{"location":"api/classrobot__dart_1_1robots_1_1Talos/#variable-_ft_wrist_left","title":"variable _ft_wrist_left","text":"
std::shared_ptr<sensor::ForceTorque> robot_dart::robots::Talos::_ft_wrist_left;\n
"},{"location":"api/classrobot__dart_1_1robots_1_1Talos/#variable-_ft_wrist_right","title":"variable _ft_wrist_right","text":"
std::shared_ptr<sensor::ForceTorque> robot_dart::robots::Talos::_ft_wrist_right;\n
"},{"location":"api/classrobot__dart_1_1robots_1_1Talos/#variable-_imu","title":"variable _imu","text":"
std::shared_ptr<sensor::IMU> robot_dart::robots::Talos::_imu;\n
"},{"location":"api/classrobot__dart_1_1robots_1_1Talos/#variable-_torques","title":"variable _torques","text":"
torque_map_t robot_dart::robots::Talos::_torques;\n
"},{"location":"api/classrobot__dart_1_1robots_1_1Talos/#protected-functions-documentation","title":"Protected Functions Documentation","text":""},{"location":"api/classrobot__dart_1_1robots_1_1Talos/#function-_post_addition","title":"function _post_addition","text":"
virtual void robot_dart::robots::Talos::_post_addition (\nRobotDARTSimu *\n) override\n

Implements robot_dart::Robot::_post_addition

"},{"location":"api/classrobot__dart_1_1robots_1_1Talos/#function-_post_removal","title":"function _post_removal","text":"
virtual void robot_dart::robots::Talos::_post_removal (\nRobotDARTSimu *\n) override\n

Implements robot_dart::Robot::_post_removal

The documentation for this class was generated from the following file robot_dart/robots/talos.hpp

"},{"location":"api/classrobot__dart_1_1robots_1_1TalosFastCollision/","title":"Class robot_dart::robots::TalosFastCollision","text":"

ClassList > robot_dart > robots > TalosFastCollision

Inherits the following classes: robot_dart::robots::Talos

"},{"location":"api/classrobot__dart_1_1robots_1_1TalosFastCollision/#public-types-inherited-from-robot_dartrobotstalos","title":"Public Types inherited from robot_dart::robots::Talos","text":"

See robot_dart::robots::Talos

Type Name typedef std::unordered_map< std::string, std::shared_ptr< sensor::Torque > > torque_map_t"},{"location":"api/classrobot__dart_1_1robots_1_1TalosFastCollision/#public-functions","title":"Public Functions","text":"Type Name TalosFastCollision (size_t frequency=1000, const std::string & urdf=\"talos/talos_fast_collision.urdf\", const std::vector< std::pair< std::string, std::string > > & packages=('talos\\_description', 'talos/talos\\_description'))"},{"location":"api/classrobot__dart_1_1robots_1_1TalosFastCollision/#public-functions-inherited-from-robot_dartrobotstalos","title":"Public Functions inherited from robot_dart::robots::Talos","text":"

See robot_dart::robots::Talos

Type Name Talos (size_t frequency=1000, const std::string & urdf=\"talos/talos.urdf\", const std::vector< std::pair< std::string, std::string > > & packages=('talos\\_description', 'talos/talos\\_description')) const sensor::ForceTorque & ft_foot_left () const const sensor::ForceTorque & ft_foot_right () const const sensor::ForceTorque & ft_wrist_left () const const sensor::ForceTorque & ft_wrist_right () const const sensor::IMU & imu () const virtual void reset () override const torque_map_t & torques () const"},{"location":"api/classrobot__dart_1_1robots_1_1TalosFastCollision/#public-functions-inherited-from-robot_dartrobot","title":"Public Functions inherited from robot_dart::Robot","text":"

See robot_dart::Robot

Type Name Robot (const std::string & model_file, const std::vector< std::pair< std::string, std::string > > & packages, const std::string & robot_name=\"robot\", bool is_urdf_string=false, bool cast_shadows=true) Robot (const std::string & model_file, const std::string & robot_name=\"robot\", bool is_urdf_string=false, bool cast_shadows=true) Robot (dart::dynamics::SkeletonPtr skeleton, const std::string & robot_name=\"robot\", bool cast_shadows=true) Eigen::VectorXd acceleration_lower_limits (const std::vector< std::string > & dof_names={}) const Eigen::VectorXd acceleration_upper_limits (const std::vector< std::string > & dof_names={}) const Eigen::VectorXd accelerations (const std::vector< std::string > & dof_names={}) const std::vector< std::shared_ptr< control::RobotControl > > active_controllers () const std::string actuator_type (const std::string & joint_name) const std::vector< std::string > actuator_types (const std::vector< std::string > & joint_names={}) const void add_body_mass (const std::string & body_name, double mass) void add_body_mass (size_t body_index, double mass) void add_controller (const std::shared_ptr< control::RobotControl > & controller, double weight=1.0) void add_external_force (const std::string & body_name, const Eigen::Vector3d & force, const Eigen::Vector3d & offset=Eigen::Vector3d::Zero(), bool force_local=false, bool offset_local=true) void add_external_force (size_t body_index, const Eigen::Vector3d & force, const Eigen::Vector3d & offset=Eigen::Vector3d::Zero(), bool force_local=false, bool offset_local=true) void add_external_torque (const std::string & body_name, const Eigen::Vector3d & torque, bool local=false) void add_external_torque (size_t body_index, const Eigen::Vector3d & torque, bool local=false) bool adjacent_colliding () const Eigen::MatrixXd aug_mass_matrix (const std::vector< std::string > & dof_names={}) const Eigen::Isometry3d base_pose () const Eigen::Vector6d base_pose_vec () const Eigen::Vector6d body_acceleration (const std::string & body_name) const Eigen::Vector6d body_acceleration (size_t body_index) const size_t body_index (const std::string & body_name) const double body_mass (const std::string & body_name) const double body_mass (size_t body_index) const std::string body_name (size_t body_index) const std::vector< std::string > body_names () const dart::dynamics::BodyNode * body_node (const std::string & body_name) dart::dynamics::BodyNode * body_node (size_t body_index) Eigen::Isometry3d body_pose (const std::string & body_name) const Eigen::Isometry3d body_pose (size_t body_index) const Eigen::Vector6d body_pose_vec (const std::string & body_name) const Eigen::Vector6d body_pose_vec (size_t body_index) const Eigen::Vector6d body_velocity (const std::string & body_name) const Eigen::Vector6d body_velocity (size_t body_index) const bool cast_shadows () const void clear_controllers () void clear_external_forces () void clear_internal_forces () std::shared_ptr< Robot > clone () const std::shared_ptr< Robot > clone_ghost (const std::string & ghost_name=\"ghost\", const Eigen::Vector4d & ghost_color={0.3, 0.3, 0.3, 0.7}) const Eigen::Vector3d com () const Eigen::Vector6d com_acceleration () const Eigen::MatrixXd com_jacobian (const std::vector< std::string > & dof_names={}) const Eigen::MatrixXd com_jacobian_deriv (const std::vector< std::string > & dof_names={}) const Eigen::Vector6d com_velocity () const Eigen::VectorXd commands (const std::vector< std::string > & dof_names={}) const Eigen::VectorXd constraint_forces (const std::vector< std::string > & dof_names={}) const std::shared_ptr< control::RobotControl > controller (size_t index) const std::vector< std::shared_ptr< control::RobotControl > > controllers () const Eigen::VectorXd coriolis_forces (const std::vector< std::string > & dof_names={}) const Eigen::VectorXd coriolis_gravity_forces (const std::vector< std::string > & dof_names={}) const std::vector< double > coulomb_coeffs (const std::vector< std::string > & dof_names={}) const std::vector< double > damping_coeffs (const std::vector< std::string > & dof_names={}) const dart::dynamics::DegreeOfFreedom * dof (const std::string & dof_name) dart::dynamics::DegreeOfFreedom * dof (size_t dof_index) size_t dof_index (const std::string & dof_name) const const std::unordered_map< std::string, size_t > & dof_map () const std::string dof_name (size_t dof_index) const std::vector< std::string > dof_names (bool filter_mimics=false, bool filter_locked=false, bool filter_passive=false) const const std::vector< std::pair< dart::dynamics::BodyNode *, double > > & drawing_axes () const Eigen::Vector6d external_forces (const std::string & body_name) const Eigen::Vector6d external_forces (size_t body_index) const void fix_to_world () bool fixed () const Eigen::VectorXd force_lower_limits (const std::vector< std::string > & dof_names={}) const void force_position_bounds () std::pair< Eigen::Vector6d, Eigen::Vector6d > force_torque (size_t joint_index) const Eigen::VectorXd force_upper_limits (const std::vector< std::string > & dof_names={}) const Eigen::VectorXd forces (const std::vector< std::string > & dof_names={}) const bool free () const void free_from_world (const Eigen::Vector6d & pose=Eigen::Vector6d::Zero()) double friction_coeff (const std::string & body_name) double friction_coeff (size_t body_index) Eigen::Vector3d friction_dir (const std::string & body_name) Eigen::Vector3d friction_dir (size_t body_index) bool ghost () const Eigen::VectorXd gravity_forces (const std::vector< std::string > & dof_names={}) const Eigen::MatrixXd inv_aug_mass_matrix (const std::vector< std::string > & dof_names={}) const Eigen::MatrixXd inv_mass_matrix (const std::vector< std::string > & dof_names={}) const Eigen::MatrixXd jacobian (const std::string & body_name, const std::vector< std::string > & dof_names={}) const Eigen::MatrixXd jacobian_deriv (const std::string & body_name, const std::vector< std::string > & dof_names={}) const dart::dynamics::Joint * joint (const std::string & joint_name) dart::dynamics::Joint * joint (size_t joint_index) size_t joint_index (const std::string & joint_name) const const std::unordered_map< std::string, size_t > & joint_map () const std::string joint_name (size_t joint_index) const std::vector< std::string > joint_names () const std::vector< std::string > locked_dof_names () const Eigen::MatrixXd mass_matrix (const std::vector< std::string > & dof_names={}) const std::vector< std::string > mimic_dof_names () const const std::string & model_filename () const const std::vector< std::pair< std::string, std::string > > & model_packages () const const std::string & name () const size_t num_bodies () const size_t num_controllers () const size_t num_dofs () const size_t num_joints () const std::vector< std::string > passive_dof_names () const std::vector< bool > position_enforced (const std::vector< std::string > & dof_names={}) const Eigen::VectorXd position_lower_limits (const std::vector< std::string > & dof_names={}) const Eigen::VectorXd position_upper_limits (const std::vector< std::string > & dof_names={}) const Eigen::VectorXd positions (const std::vector< std::string > & dof_names={}) const void reinit_controllers () void remove_all_drawing_axis () void remove_controller (const std::shared_ptr< control::RobotControl > & controller) void remove_controller (size_t index) virtual void reset () void reset_commands () double restitution_coeff (const std::string & body_name) double restitution_coeff (size_t body_index) double secondary_friction_coeff (const std::string & body_name) double secondary_friction_coeff (size_t body_index) bool self_colliding () const void set_acceleration_lower_limits (const Eigen::VectorXd & accelerations, const std::vector< std::string > & dof_names={}) void set_acceleration_upper_limits (const Eigen::VectorXd & accelerations, const std::vector< std::string > & dof_names={}) void set_accelerations (const Eigen::VectorXd & accelerations, const std::vector< std::string > & dof_names={}) void set_actuator_type (const std::string & type, const std::string & joint_name, bool override_mimic=false, bool override_base=false) void set_actuator_types (const std::string & type, const std::vector< std::string > & joint_names={}, bool override_mimic=false, bool override_base=false) void set_base_pose (const Eigen::Isometry3d & tf) void set_base_pose (const Eigen::Vector6d & pose) set base pose: pose is a 6D vector (first 3D orientation in angle-axis and last 3D translation) void set_body_mass (const std::string & body_name, double mass) void set_body_mass (size_t body_index, double mass) void set_body_name (size_t body_index, const std::string & body_name) void set_cast_shadows (bool cast_shadows=true) void set_color_mode (const std::string & color_mode) void set_color_mode (const std::string & color_mode, const std::string & body_name) void set_commands (const Eigen::VectorXd & commands, const std::vector< std::string > & dof_names={}) void set_coulomb_coeffs (const std::vector< double > & cfrictions, const std::vector< std::string > & dof_names={}) void set_coulomb_coeffs (double cfriction, const std::vector< std::string > & dof_names={}) void set_damping_coeffs (const std::vector< double > & damps, const std::vector< std::string > & dof_names={}) void set_damping_coeffs (double damp, const std::vector< std::string > & dof_names={}) void set_draw_axis (const std::string & body_name, double size=0.25) void set_external_force (const std::string & body_name, const Eigen::Vector3d & force, const Eigen::Vector3d & offset=Eigen::Vector3d::Zero(), bool force_local=false, bool offset_local=true) void set_external_force (size_t body_index, const Eigen::Vector3d & force, const Eigen::Vector3d & offset=Eigen::Vector3d::Zero(), bool force_local=false, bool offset_local=true) void set_external_torque (const std::string & body_name, const Eigen::Vector3d & torque, bool local=false) void set_external_torque (size_t body_index, const Eigen::Vector3d & torque, bool local=false) void set_force_lower_limits (const Eigen::VectorXd & forces, const std::vector< std::string > & dof_names={}) void set_force_upper_limits (const Eigen::VectorXd & forces, const std::vector< std::string > & dof_names={}) void set_forces (const Eigen::VectorXd & forces, const std::vector< std::string > & dof_names={}) void set_friction_coeff (const std::string & body_name, double value) void set_friction_coeff (size_t body_index, double value) void set_friction_coeffs (double value) void set_friction_dir (const std::string & body_name, const Eigen::Vector3d & direction) void set_friction_dir (size_t body_index, const Eigen::Vector3d & direction) void set_ghost (bool ghost=true) void set_joint_name (size_t joint_index, const std::string & joint_name) void set_mimic (const std::string & joint_name, const std::string & mimic_joint_name, double multiplier=1., double offset=0.) void set_position_enforced (const std::vector< bool > & enforced, const std::vector< std::string > & dof_names={}) void set_position_enforced (bool enforced, const std::vector< std::string > & dof_names={}) void set_position_lower_limits (const Eigen::VectorXd & positions, const std::vector< std::string > & dof_names={}) void set_position_upper_limits (const Eigen::VectorXd & positions, const std::vector< std::string > & dof_names={}) void set_positions (const Eigen::VectorXd & positions, const std::vector< std::string > & dof_names={}) void set_restitution_coeff (const std::string & body_name, double value) void set_restitution_coeff (size_t body_index, double value) void set_restitution_coeffs (double value) void set_secondary_friction_coeff (const std::string & body_name, double value) void set_secondary_friction_coeff (size_t body_index, double value) void set_secondary_friction_coeffs (double value) void set_self_collision (bool enable_self_collisions=true, bool enable_adjacent_collisions=false) void set_spring_stiffnesses (const std::vector< double > & stiffnesses, const std::vector< std::string > & dof_names={}) void set_spring_stiffnesses (double stiffness, const std::vector< std::string > & dof_names={}) void set_velocities (const Eigen::VectorXd & velocities, const std::vector< std::string > & dof_names={}) void set_velocity_lower_limits (const Eigen::VectorXd & velocities, const std::vector< std::string > & dof_names={}) void set_velocity_upper_limits (const Eigen::VectorXd & velocities, const std::vector< std::string > & dof_names={}) dart::dynamics::SkeletonPtr skeleton () std::vector< double > spring_stiffnesses (const std::vector< std::string > & dof_names={}) const void update (double t) void update_joint_dof_maps () Eigen::VectorXd vec_dof (const Eigen::VectorXd & vec, const std::vector< std::string > & dof_names) const Eigen::VectorXd velocities (const std::vector< std::string > & dof_names={}) const Eigen::VectorXd velocity_lower_limits (const std::vector< std::string > & dof_names={}) const Eigen::VectorXd velocity_upper_limits (const std::vector< std::string > & dof_names={}) const virtual ~Robot ()"},{"location":"api/classrobot__dart_1_1robots_1_1TalosFastCollision/#public-static-functions","title":"Public Static Functions","text":"Type Name std::vector< std::tuple< std::string, uint32_t, uint32_t > > collision_vec ()"},{"location":"api/classrobot__dart_1_1robots_1_1TalosFastCollision/#public-static-functions-inherited-from-robot_dartrobot","title":"Public Static Functions inherited from robot_dart::Robot","text":"

See robot_dart::Robot

Type Name std::shared_ptr< Robot > create_box (const Eigen::Vector3d & dims, const Eigen::Isometry3d & tf, const std::string & type=\"free\", double mass=1.0, const Eigen::Vector4d & color=dart::Color::Red(1.0), const std::string & box_name=\"box\") std::shared_ptr< Robot > create_box (const Eigen::Vector3d & dims, const Eigen::Vector6d & pose=Eigen::Vector6d::Zero(), const std::string & type=\"free\", double mass=1.0, const Eigen::Vector4d & color=dart::Color::Red(1.0), const std::string & box_name=\"box\") std::shared_ptr< Robot > create_ellipsoid (const Eigen::Vector3d & dims, const Eigen::Isometry3d & tf, const std::string & type=\"free\", double mass=1.0, const Eigen::Vector4d & color=dart::Color::Red(1.0), const std::string & ellipsoid_name=\"ellipsoid\") std::shared_ptr< Robot > create_ellipsoid (const Eigen::Vector3d & dims, const Eigen::Vector6d & pose=Eigen::Vector6d::Zero(), const std::string & type=\"free\", double mass=1.0, const Eigen::Vector4d & color=dart::Color::Red(1.0), const std::string & ellipsoid_name=\"ellipsoid\")"},{"location":"api/classrobot__dart_1_1robots_1_1TalosFastCollision/#protected-attributes-inherited-from-robot_dartrobotstalos","title":"Protected Attributes inherited from robot_dart::robots::Talos","text":"

See robot_dart::robots::Talos

Type Name size_t _frequency std::shared_ptr< sensor::ForceTorque > _ft_foot_left std::shared_ptr< sensor::ForceTorque > _ft_foot_right std::shared_ptr< sensor::ForceTorque > _ft_wrist_left std::shared_ptr< sensor::ForceTorque > _ft_wrist_right std::shared_ptr< sensor::IMU > _imu torque_map_t _torques"},{"location":"api/classrobot__dart_1_1robots_1_1TalosFastCollision/#protected-attributes-inherited-from-robot_dartrobot","title":"Protected Attributes inherited from robot_dart::Robot","text":"

See robot_dart::Robot

Type Name std::vector< std::pair< dart::dynamics::BodyNode *, double > > _axis_shapes bool _cast_shadows std::vector< std::shared_ptr< control::RobotControl > > _controllers std::unordered_map< std::string, size_t > _dof_map bool _is_ghost std::unordered_map< std::string, size_t > _joint_map std::string _model_filename std::vector< std::pair< std::string, std::string > > _packages std::string _robot_name dart::dynamics::SkeletonPtr _skeleton"},{"location":"api/classrobot__dart_1_1robots_1_1TalosFastCollision/#protected-functions","title":"Protected Functions","text":"Type Name virtual void _post_addition (RobotDARTSimu *) overrideFunction called by RobotDARTSimu object when adding the robot to the world."},{"location":"api/classrobot__dart_1_1robots_1_1TalosFastCollision/#protected-functions-inherited-from-robot_dartrobotstalos","title":"Protected Functions inherited from robot_dart::robots::Talos","text":"

See robot_dart::robots::Talos

Type Name virtual void _post_addition (RobotDARTSimu *) overrideFunction called by RobotDARTSimu object when adding the robot to the world. virtual void _post_removal (RobotDARTSimu *) overrideFunction called by RobotDARTSimu object when removing the robot to the world."},{"location":"api/classrobot__dart_1_1robots_1_1TalosFastCollision/#protected-functions-inherited-from-robot_dartrobot","title":"Protected Functions inherited from robot_dart::Robot","text":"

See robot_dart::Robot

Type Name dart::dynamics::Joint::ActuatorType _actuator_type (size_t joint_index) const std::vector< dart::dynamics::Joint::ActuatorType > _actuator_types () const std::string _get_path (const std::string & filename) const Eigen::MatrixXd _jacobian (const Eigen::MatrixXd & full_jacobian, const std::vector< std::string > & dof_names) const dart::dynamics::SkeletonPtr _load_model (const std::string & filename, const std::vector< std::pair< std::string, std::string > > & packages=std::vector< std::pair< std::string, std::string > >(), bool is_urdf_string=false) Eigen::MatrixXd _mass_matrix (const Eigen::MatrixXd & full_mass_matrix, const std::vector< std::string > & dof_names) const virtual void _post_addition (RobotDARTSimu *) Function called by RobotDARTSimu object when adding the robot to the world. virtual void _post_removal (RobotDARTSimu *) Function called by RobotDARTSimu object when removing the robot to the world. void _set_actuator_type (size_t joint_index, dart::dynamics::Joint::ActuatorType type, bool override_mimic=false, bool override_base=false) void _set_actuator_types (const std::vector< dart::dynamics::Joint::ActuatorType > & types, bool override_mimic=false, bool override_base=false) void _set_actuator_types (dart::dynamics::Joint::ActuatorType type, bool override_mimic=false, bool override_base=false) void _set_color_mode (dart::dynamics::MeshShape::ColorMode color_mode, dart::dynamics::SkeletonPtr skel) void _set_color_mode (dart::dynamics::MeshShape::ColorMode color_mode, dart::dynamics::ShapeNode * sn)"},{"location":"api/classrobot__dart_1_1robots_1_1TalosFastCollision/#public-functions-documentation","title":"Public Functions Documentation","text":""},{"location":"api/classrobot__dart_1_1robots_1_1TalosFastCollision/#function-talosfastcollision","title":"function TalosFastCollision","text":"
inline robot_dart::robots::TalosFastCollision::TalosFastCollision (\nsize_t frequency=1000,\nconst std::string & urdf=\"talos/talos_fast_collision.urdf\",\nconst std::vector< std::pair< std::string, std::string > > & packages=('talos_description', 'talos/talos_description')\n) 
"},{"location":"api/classrobot__dart_1_1robots_1_1TalosFastCollision/#public-static-functions-documentation","title":"Public Static Functions Documentation","text":""},{"location":"api/classrobot__dart_1_1robots_1_1TalosFastCollision/#function-collision_vec","title":"function collision_vec","text":"
static std::vector< std::tuple< std::string, uint32_t, uint32_t > > robot_dart::robots::TalosFastCollision::collision_vec () 
"},{"location":"api/classrobot__dart_1_1robots_1_1TalosFastCollision/#protected-functions-documentation","title":"Protected Functions Documentation","text":""},{"location":"api/classrobot__dart_1_1robots_1_1TalosFastCollision/#function-_post_addition","title":"function _post_addition","text":"
virtual void robot_dart::robots::TalosFastCollision::_post_addition (\nRobotDARTSimu *\n) override\n

Implements robot_dart::robots::Talos::_post_addition

The documentation for this class was generated from the following file robot_dart/robots/talos.hpp

"},{"location":"api/classrobot__dart_1_1robots_1_1TalosLight/","title":"Class robot_dart::robots::TalosLight","text":"

ClassList > robot_dart > robots > TalosLight

Inherits the following classes: robot_dart::robots::Talos

"},{"location":"api/classrobot__dart_1_1robots_1_1TalosLight/#public-types-inherited-from-robot_dartrobotstalos","title":"Public Types inherited from robot_dart::robots::Talos","text":"

See robot_dart::robots::Talos

Type Name typedef std::unordered_map< std::string, std::shared_ptr< sensor::Torque > > torque_map_t"},{"location":"api/classrobot__dart_1_1robots_1_1TalosLight/#public-functions","title":"Public Functions","text":"Type Name TalosLight (size_t frequency=1000, const std::string & urdf=\"talos/talos_fast.urdf\", const std::vector< std::pair< std::string, std::string > > & packages=('talos\\_description', 'talos/talos\\_description'))"},{"location":"api/classrobot__dart_1_1robots_1_1TalosLight/#public-functions-inherited-from-robot_dartrobotstalos","title":"Public Functions inherited from robot_dart::robots::Talos","text":"

See robot_dart::robots::Talos

Type Name Talos (size_t frequency=1000, const std::string & urdf=\"talos/talos.urdf\", const std::vector< std::pair< std::string, std::string > > & packages=('talos\\_description', 'talos/talos\\_description')) const sensor::ForceTorque & ft_foot_left () const const sensor::ForceTorque & ft_foot_right () const const sensor::ForceTorque & ft_wrist_left () const const sensor::ForceTorque & ft_wrist_right () const const sensor::IMU & imu () const virtual void reset () override const torque_map_t & torques () const"},{"location":"api/classrobot__dart_1_1robots_1_1TalosLight/#public-functions-inherited-from-robot_dartrobot","title":"Public Functions inherited from robot_dart::Robot","text":"

See robot_dart::Robot

Type Name Robot (const std::string & model_file, const std::vector< std::pair< std::string, std::string > > & packages, const std::string & robot_name=\"robot\", bool is_urdf_string=false, bool cast_shadows=true) Robot (const std::string & model_file, const std::string & robot_name=\"robot\", bool is_urdf_string=false, bool cast_shadows=true) Robot (dart::dynamics::SkeletonPtr skeleton, const std::string & robot_name=\"robot\", bool cast_shadows=true) Eigen::VectorXd acceleration_lower_limits (const std::vector< std::string > & dof_names={}) const Eigen::VectorXd acceleration_upper_limits (const std::vector< std::string > & dof_names={}) const Eigen::VectorXd accelerations (const std::vector< std::string > & dof_names={}) const std::vector< std::shared_ptr< control::RobotControl > > active_controllers () const std::string actuator_type (const std::string & joint_name) const std::vector< std::string > actuator_types (const std::vector< std::string > & joint_names={}) const void add_body_mass (const std::string & body_name, double mass) void add_body_mass (size_t body_index, double mass) void add_controller (const std::shared_ptr< control::RobotControl > & controller, double weight=1.0) void add_external_force (const std::string & body_name, const Eigen::Vector3d & force, const Eigen::Vector3d & offset=Eigen::Vector3d::Zero(), bool force_local=false, bool offset_local=true) void add_external_force (size_t body_index, const Eigen::Vector3d & force, const Eigen::Vector3d & offset=Eigen::Vector3d::Zero(), bool force_local=false, bool offset_local=true) void add_external_torque (const std::string & body_name, const Eigen::Vector3d & torque, bool local=false) void add_external_torque (size_t body_index, const Eigen::Vector3d & torque, bool local=false) bool adjacent_colliding () const Eigen::MatrixXd aug_mass_matrix (const std::vector< std::string > & dof_names={}) const Eigen::Isometry3d base_pose () const Eigen::Vector6d base_pose_vec () const Eigen::Vector6d body_acceleration (const std::string & body_name) const Eigen::Vector6d body_acceleration (size_t body_index) const size_t body_index (const std::string & body_name) const double body_mass (const std::string & body_name) const double body_mass (size_t body_index) const std::string body_name (size_t body_index) const std::vector< std::string > body_names () const dart::dynamics::BodyNode * body_node (const std::string & body_name) dart::dynamics::BodyNode * body_node (size_t body_index) Eigen::Isometry3d body_pose (const std::string & body_name) const Eigen::Isometry3d body_pose (size_t body_index) const Eigen::Vector6d body_pose_vec (const std::string & body_name) const Eigen::Vector6d body_pose_vec (size_t body_index) const Eigen::Vector6d body_velocity (const std::string & body_name) const Eigen::Vector6d body_velocity (size_t body_index) const bool cast_shadows () const void clear_controllers () void clear_external_forces () void clear_internal_forces () std::shared_ptr< Robot > clone () const std::shared_ptr< Robot > clone_ghost (const std::string & ghost_name=\"ghost\", const Eigen::Vector4d & ghost_color={0.3, 0.3, 0.3, 0.7}) const Eigen::Vector3d com () const Eigen::Vector6d com_acceleration () const Eigen::MatrixXd com_jacobian (const std::vector< std::string > & dof_names={}) const Eigen::MatrixXd com_jacobian_deriv (const std::vector< std::string > & dof_names={}) const Eigen::Vector6d com_velocity () const Eigen::VectorXd commands (const std::vector< std::string > & dof_names={}) const Eigen::VectorXd constraint_forces (const std::vector< std::string > & dof_names={}) const std::shared_ptr< control::RobotControl > controller (size_t index) const std::vector< std::shared_ptr< control::RobotControl > > controllers () const Eigen::VectorXd coriolis_forces (const std::vector< std::string > & dof_names={}) const Eigen::VectorXd coriolis_gravity_forces (const std::vector< std::string > & dof_names={}) const std::vector< double > coulomb_coeffs (const std::vector< std::string > & dof_names={}) const std::vector< double > damping_coeffs (const std::vector< std::string > & dof_names={}) const dart::dynamics::DegreeOfFreedom * dof (const std::string & dof_name) dart::dynamics::DegreeOfFreedom * dof (size_t dof_index) size_t dof_index (const std::string & dof_name) const const std::unordered_map< std::string, size_t > & dof_map () const std::string dof_name (size_t dof_index) const std::vector< std::string > dof_names (bool filter_mimics=false, bool filter_locked=false, bool filter_passive=false) const const std::vector< std::pair< dart::dynamics::BodyNode *, double > > & drawing_axes () const Eigen::Vector6d external_forces (const std::string & body_name) const Eigen::Vector6d external_forces (size_t body_index) const void fix_to_world () bool fixed () const Eigen::VectorXd force_lower_limits (const std::vector< std::string > & dof_names={}) const void force_position_bounds () std::pair< Eigen::Vector6d, Eigen::Vector6d > force_torque (size_t joint_index) const Eigen::VectorXd force_upper_limits (const std::vector< std::string > & dof_names={}) const Eigen::VectorXd forces (const std::vector< std::string > & dof_names={}) const bool free () const void free_from_world (const Eigen::Vector6d & pose=Eigen::Vector6d::Zero()) double friction_coeff (const std::string & body_name) double friction_coeff (size_t body_index) Eigen::Vector3d friction_dir (const std::string & body_name) Eigen::Vector3d friction_dir (size_t body_index) bool ghost () const Eigen::VectorXd gravity_forces (const std::vector< std::string > & dof_names={}) const Eigen::MatrixXd inv_aug_mass_matrix (const std::vector< std::string > & dof_names={}) const Eigen::MatrixXd inv_mass_matrix (const std::vector< std::string > & dof_names={}) const Eigen::MatrixXd jacobian (const std::string & body_name, const std::vector< std::string > & dof_names={}) const Eigen::MatrixXd jacobian_deriv (const std::string & body_name, const std::vector< std::string > & dof_names={}) const dart::dynamics::Joint * joint (const std::string & joint_name) dart::dynamics::Joint * joint (size_t joint_index) size_t joint_index (const std::string & joint_name) const const std::unordered_map< std::string, size_t > & joint_map () const std::string joint_name (size_t joint_index) const std::vector< std::string > joint_names () const std::vector< std::string > locked_dof_names () const Eigen::MatrixXd mass_matrix (const std::vector< std::string > & dof_names={}) const std::vector< std::string > mimic_dof_names () const const std::string & model_filename () const const std::vector< std::pair< std::string, std::string > > & model_packages () const const std::string & name () const size_t num_bodies () const size_t num_controllers () const size_t num_dofs () const size_t num_joints () const std::vector< std::string > passive_dof_names () const std::vector< bool > position_enforced (const std::vector< std::string > & dof_names={}) const Eigen::VectorXd position_lower_limits (const std::vector< std::string > & dof_names={}) const Eigen::VectorXd position_upper_limits (const std::vector< std::string > & dof_names={}) const Eigen::VectorXd positions (const std::vector< std::string > & dof_names={}) const void reinit_controllers () void remove_all_drawing_axis () void remove_controller (const std::shared_ptr< control::RobotControl > & controller) void remove_controller (size_t index) virtual void reset () void reset_commands () double restitution_coeff (const std::string & body_name) double restitution_coeff (size_t body_index) double secondary_friction_coeff (const std::string & body_name) double secondary_friction_coeff (size_t body_index) bool self_colliding () const void set_acceleration_lower_limits (const Eigen::VectorXd & accelerations, const std::vector< std::string > & dof_names={}) void set_acceleration_upper_limits (const Eigen::VectorXd & accelerations, const std::vector< std::string > & dof_names={}) void set_accelerations (const Eigen::VectorXd & accelerations, const std::vector< std::string > & dof_names={}) void set_actuator_type (const std::string & type, const std::string & joint_name, bool override_mimic=false, bool override_base=false) void set_actuator_types (const std::string & type, const std::vector< std::string > & joint_names={}, bool override_mimic=false, bool override_base=false) void set_base_pose (const Eigen::Isometry3d & tf) void set_base_pose (const Eigen::Vector6d & pose) set base pose: pose is a 6D vector (first 3D orientation in angle-axis and last 3D translation) void set_body_mass (const std::string & body_name, double mass) void set_body_mass (size_t body_index, double mass) void set_body_name (size_t body_index, const std::string & body_name) void set_cast_shadows (bool cast_shadows=true) void set_color_mode (const std::string & color_mode) void set_color_mode (const std::string & color_mode, const std::string & body_name) void set_commands (const Eigen::VectorXd & commands, const std::vector< std::string > & dof_names={}) void set_coulomb_coeffs (const std::vector< double > & cfrictions, const std::vector< std::string > & dof_names={}) void set_coulomb_coeffs (double cfriction, const std::vector< std::string > & dof_names={}) void set_damping_coeffs (const std::vector< double > & damps, const std::vector< std::string > & dof_names={}) void set_damping_coeffs (double damp, const std::vector< std::string > & dof_names={}) void set_draw_axis (const std::string & body_name, double size=0.25) void set_external_force (const std::string & body_name, const Eigen::Vector3d & force, const Eigen::Vector3d & offset=Eigen::Vector3d::Zero(), bool force_local=false, bool offset_local=true) void set_external_force (size_t body_index, const Eigen::Vector3d & force, const Eigen::Vector3d & offset=Eigen::Vector3d::Zero(), bool force_local=false, bool offset_local=true) void set_external_torque (const std::string & body_name, const Eigen::Vector3d & torque, bool local=false) void set_external_torque (size_t body_index, const Eigen::Vector3d & torque, bool local=false) void set_force_lower_limits (const Eigen::VectorXd & forces, const std::vector< std::string > & dof_names={}) void set_force_upper_limits (const Eigen::VectorXd & forces, const std::vector< std::string > & dof_names={}) void set_forces (const Eigen::VectorXd & forces, const std::vector< std::string > & dof_names={}) void set_friction_coeff (const std::string & body_name, double value) void set_friction_coeff (size_t body_index, double value) void set_friction_coeffs (double value) void set_friction_dir (const std::string & body_name, const Eigen::Vector3d & direction) void set_friction_dir (size_t body_index, const Eigen::Vector3d & direction) void set_ghost (bool ghost=true) void set_joint_name (size_t joint_index, const std::string & joint_name) void set_mimic (const std::string & joint_name, const std::string & mimic_joint_name, double multiplier=1., double offset=0.) void set_position_enforced (const std::vector< bool > & enforced, const std::vector< std::string > & dof_names={}) void set_position_enforced (bool enforced, const std::vector< std::string > & dof_names={}) void set_position_lower_limits (const Eigen::VectorXd & positions, const std::vector< std::string > & dof_names={}) void set_position_upper_limits (const Eigen::VectorXd & positions, const std::vector< std::string > & dof_names={}) void set_positions (const Eigen::VectorXd & positions, const std::vector< std::string > & dof_names={}) void set_restitution_coeff (const std::string & body_name, double value) void set_restitution_coeff (size_t body_index, double value) void set_restitution_coeffs (double value) void set_secondary_friction_coeff (const std::string & body_name, double value) void set_secondary_friction_coeff (size_t body_index, double value) void set_secondary_friction_coeffs (double value) void set_self_collision (bool enable_self_collisions=true, bool enable_adjacent_collisions=false) void set_spring_stiffnesses (const std::vector< double > & stiffnesses, const std::vector< std::string > & dof_names={}) void set_spring_stiffnesses (double stiffness, const std::vector< std::string > & dof_names={}) void set_velocities (const Eigen::VectorXd & velocities, const std::vector< std::string > & dof_names={}) void set_velocity_lower_limits (const Eigen::VectorXd & velocities, const std::vector< std::string > & dof_names={}) void set_velocity_upper_limits (const Eigen::VectorXd & velocities, const std::vector< std::string > & dof_names={}) dart::dynamics::SkeletonPtr skeleton () std::vector< double > spring_stiffnesses (const std::vector< std::string > & dof_names={}) const void update (double t) void update_joint_dof_maps () Eigen::VectorXd vec_dof (const Eigen::VectorXd & vec, const std::vector< std::string > & dof_names) const Eigen::VectorXd velocities (const std::vector< std::string > & dof_names={}) const Eigen::VectorXd velocity_lower_limits (const std::vector< std::string > & dof_names={}) const Eigen::VectorXd velocity_upper_limits (const std::vector< std::string > & dof_names={}) const virtual ~Robot ()"},{"location":"api/classrobot__dart_1_1robots_1_1TalosLight/#public-static-functions-inherited-from-robot_dartrobot","title":"Public Static Functions inherited from robot_dart::Robot","text":"

See robot_dart::Robot

Type Name std::shared_ptr< Robot > create_box (const Eigen::Vector3d & dims, const Eigen::Isometry3d & tf, const std::string & type=\"free\", double mass=1.0, const Eigen::Vector4d & color=dart::Color::Red(1.0), const std::string & box_name=\"box\") std::shared_ptr< Robot > create_box (const Eigen::Vector3d & dims, const Eigen::Vector6d & pose=Eigen::Vector6d::Zero(), const std::string & type=\"free\", double mass=1.0, const Eigen::Vector4d & color=dart::Color::Red(1.0), const std::string & box_name=\"box\") std::shared_ptr< Robot > create_ellipsoid (const Eigen::Vector3d & dims, const Eigen::Isometry3d & tf, const std::string & type=\"free\", double mass=1.0, const Eigen::Vector4d & color=dart::Color::Red(1.0), const std::string & ellipsoid_name=\"ellipsoid\") std::shared_ptr< Robot > create_ellipsoid (const Eigen::Vector3d & dims, const Eigen::Vector6d & pose=Eigen::Vector6d::Zero(), const std::string & type=\"free\", double mass=1.0, const Eigen::Vector4d & color=dart::Color::Red(1.0), const std::string & ellipsoid_name=\"ellipsoid\")"},{"location":"api/classrobot__dart_1_1robots_1_1TalosLight/#protected-attributes-inherited-from-robot_dartrobotstalos","title":"Protected Attributes inherited from robot_dart::robots::Talos","text":"

See robot_dart::robots::Talos

Type Name size_t _frequency std::shared_ptr< sensor::ForceTorque > _ft_foot_left std::shared_ptr< sensor::ForceTorque > _ft_foot_right std::shared_ptr< sensor::ForceTorque > _ft_wrist_left std::shared_ptr< sensor::ForceTorque > _ft_wrist_right std::shared_ptr< sensor::IMU > _imu torque_map_t _torques"},{"location":"api/classrobot__dart_1_1robots_1_1TalosLight/#protected-attributes-inherited-from-robot_dartrobot","title":"Protected Attributes inherited from robot_dart::Robot","text":"

See robot_dart::Robot

Type Name std::vector< std::pair< dart::dynamics::BodyNode *, double > > _axis_shapes bool _cast_shadows std::vector< std::shared_ptr< control::RobotControl > > _controllers std::unordered_map< std::string, size_t > _dof_map bool _is_ghost std::unordered_map< std::string, size_t > _joint_map std::string _model_filename std::vector< std::pair< std::string, std::string > > _packages std::string _robot_name dart::dynamics::SkeletonPtr _skeleton"},{"location":"api/classrobot__dart_1_1robots_1_1TalosLight/#protected-functions-inherited-from-robot_dartrobotstalos","title":"Protected Functions inherited from robot_dart::robots::Talos","text":"

See robot_dart::robots::Talos

Type Name virtual void _post_addition (RobotDARTSimu *) overrideFunction called by RobotDARTSimu object when adding the robot to the world. virtual void _post_removal (RobotDARTSimu *) overrideFunction called by RobotDARTSimu object when removing the robot to the world."},{"location":"api/classrobot__dart_1_1robots_1_1TalosLight/#protected-functions-inherited-from-robot_dartrobot","title":"Protected Functions inherited from robot_dart::Robot","text":"

See robot_dart::Robot

Type Name dart::dynamics::Joint::ActuatorType _actuator_type (size_t joint_index) const std::vector< dart::dynamics::Joint::ActuatorType > _actuator_types () const std::string _get_path (const std::string & filename) const Eigen::MatrixXd _jacobian (const Eigen::MatrixXd & full_jacobian, const std::vector< std::string > & dof_names) const dart::dynamics::SkeletonPtr _load_model (const std::string & filename, const std::vector< std::pair< std::string, std::string > > & packages=std::vector< std::pair< std::string, std::string > >(), bool is_urdf_string=false) Eigen::MatrixXd _mass_matrix (const Eigen::MatrixXd & full_mass_matrix, const std::vector< std::string > & dof_names) const virtual void _post_addition (RobotDARTSimu *) Function called by RobotDARTSimu object when adding the robot to the world. virtual void _post_removal (RobotDARTSimu *) Function called by RobotDARTSimu object when removing the robot to the world. void _set_actuator_type (size_t joint_index, dart::dynamics::Joint::ActuatorType type, bool override_mimic=false, bool override_base=false) void _set_actuator_types (const std::vector< dart::dynamics::Joint::ActuatorType > & types, bool override_mimic=false, bool override_base=false) void _set_actuator_types (dart::dynamics::Joint::ActuatorType type, bool override_mimic=false, bool override_base=false) void _set_color_mode (dart::dynamics::MeshShape::ColorMode color_mode, dart::dynamics::SkeletonPtr skel) void _set_color_mode (dart::dynamics::MeshShape::ColorMode color_mode, dart::dynamics::ShapeNode * sn)"},{"location":"api/classrobot__dart_1_1robots_1_1TalosLight/#public-functions-documentation","title":"Public Functions Documentation","text":""},{"location":"api/classrobot__dart_1_1robots_1_1TalosLight/#function-taloslight","title":"function TalosLight","text":"
inline robot_dart::robots::TalosLight::TalosLight (\nsize_t frequency=1000,\nconst std::string & urdf=\"talos/talos_fast.urdf\",\nconst std::vector< std::pair< std::string, std::string > > & packages=('talos_description', 'talos/talos_description')\n) 

The documentation for this class was generated from the following file robot_dart/robots/talos.hpp

"},{"location":"api/classrobot__dart_1_1robots_1_1Tiago/","title":"Class robot_dart::robots::Tiago","text":"

ClassList > robot_dart > robots > Tiago

datasheet: https://pal-robotics.com/wp-content/uploads/2021/07/Datasheet-complete_TIAGo-2021.pdf __

Inherits the following classes: robot_dart::Robot

"},{"location":"api/classrobot__dart_1_1robots_1_1Tiago/#public-functions","title":"Public Functions","text":"Type Name Tiago (size_t frequency=1000, const std::string & urdf=\"tiago/tiago_steel.urdf\", const std::vector< std::pair< std::string, std::string > > & packages=('tiago\\_description', 'tiago/tiago\\_description')) std::vector< std::string > caster_joints () const const sensor::ForceTorque & ft_wrist () const virtual void reset () override void set_actuator_type (const std::string & type, const std::string & joint_name, bool override_mimic=false, bool override_base=false, bool override_caster=false) void set_actuator_types (const std::string & type, const std::vector< std::string > & joint_names={}, bool override_mimic=false, bool override_base=false, bool override_caster=false)"},{"location":"api/classrobot__dart_1_1robots_1_1Tiago/#public-functions-inherited-from-robot_dartrobot","title":"Public Functions inherited from robot_dart::Robot","text":"

See robot_dart::Robot

Type Name Robot (const std::string & model_file, const std::vector< std::pair< std::string, std::string > > & packages, const std::string & robot_name=\"robot\", bool is_urdf_string=false, bool cast_shadows=true) Robot (const std::string & model_file, const std::string & robot_name=\"robot\", bool is_urdf_string=false, bool cast_shadows=true) Robot (dart::dynamics::SkeletonPtr skeleton, const std::string & robot_name=\"robot\", bool cast_shadows=true) Eigen::VectorXd acceleration_lower_limits (const std::vector< std::string > & dof_names={}) const Eigen::VectorXd acceleration_upper_limits (const std::vector< std::string > & dof_names={}) const Eigen::VectorXd accelerations (const std::vector< std::string > & dof_names={}) const std::vector< std::shared_ptr< control::RobotControl > > active_controllers () const std::string actuator_type (const std::string & joint_name) const std::vector< std::string > actuator_types (const std::vector< std::string > & joint_names={}) const void add_body_mass (const std::string & body_name, double mass) void add_body_mass (size_t body_index, double mass) void add_controller (const std::shared_ptr< control::RobotControl > & controller, double weight=1.0) void add_external_force (const std::string & body_name, const Eigen::Vector3d & force, const Eigen::Vector3d & offset=Eigen::Vector3d::Zero(), bool force_local=false, bool offset_local=true) void add_external_force (size_t body_index, const Eigen::Vector3d & force, const Eigen::Vector3d & offset=Eigen::Vector3d::Zero(), bool force_local=false, bool offset_local=true) void add_external_torque (const std::string & body_name, const Eigen::Vector3d & torque, bool local=false) void add_external_torque (size_t body_index, const Eigen::Vector3d & torque, bool local=false) bool adjacent_colliding () const Eigen::MatrixXd aug_mass_matrix (const std::vector< std::string > & dof_names={}) const Eigen::Isometry3d base_pose () const Eigen::Vector6d base_pose_vec () const Eigen::Vector6d body_acceleration (const std::string & body_name) const Eigen::Vector6d body_acceleration (size_t body_index) const size_t body_index (const std::string & body_name) const double body_mass (const std::string & body_name) const double body_mass (size_t body_index) const std::string body_name (size_t body_index) const std::vector< std::string > body_names () const dart::dynamics::BodyNode * body_node (const std::string & body_name) dart::dynamics::BodyNode * body_node (size_t body_index) Eigen::Isometry3d body_pose (const std::string & body_name) const Eigen::Isometry3d body_pose (size_t body_index) const Eigen::Vector6d body_pose_vec (const std::string & body_name) const Eigen::Vector6d body_pose_vec (size_t body_index) const Eigen::Vector6d body_velocity (const std::string & body_name) const Eigen::Vector6d body_velocity (size_t body_index) const bool cast_shadows () const void clear_controllers () void clear_external_forces () void clear_internal_forces () std::shared_ptr< Robot > clone () const std::shared_ptr< Robot > clone_ghost (const std::string & ghost_name=\"ghost\", const Eigen::Vector4d & ghost_color={0.3, 0.3, 0.3, 0.7}) const Eigen::Vector3d com () const Eigen::Vector6d com_acceleration () const Eigen::MatrixXd com_jacobian (const std::vector< std::string > & dof_names={}) const Eigen::MatrixXd com_jacobian_deriv (const std::vector< std::string > & dof_names={}) const Eigen::Vector6d com_velocity () const Eigen::VectorXd commands (const std::vector< std::string > & dof_names={}) const Eigen::VectorXd constraint_forces (const std::vector< std::string > & dof_names={}) const std::shared_ptr< control::RobotControl > controller (size_t index) const std::vector< std::shared_ptr< control::RobotControl > > controllers () const Eigen::VectorXd coriolis_forces (const std::vector< std::string > & dof_names={}) const Eigen::VectorXd coriolis_gravity_forces (const std::vector< std::string > & dof_names={}) const std::vector< double > coulomb_coeffs (const std::vector< std::string > & dof_names={}) const std::vector< double > damping_coeffs (const std::vector< std::string > & dof_names={}) const dart::dynamics::DegreeOfFreedom * dof (const std::string & dof_name) dart::dynamics::DegreeOfFreedom * dof (size_t dof_index) size_t dof_index (const std::string & dof_name) const const std::unordered_map< std::string, size_t > & dof_map () const std::string dof_name (size_t dof_index) const std::vector< std::string > dof_names (bool filter_mimics=false, bool filter_locked=false, bool filter_passive=false) const const std::vector< std::pair< dart::dynamics::BodyNode *, double > > & drawing_axes () const Eigen::Vector6d external_forces (const std::string & body_name) const Eigen::Vector6d external_forces (size_t body_index) const void fix_to_world () bool fixed () const Eigen::VectorXd force_lower_limits (const std::vector< std::string > & dof_names={}) const void force_position_bounds () std::pair< Eigen::Vector6d, Eigen::Vector6d > force_torque (size_t joint_index) const Eigen::VectorXd force_upper_limits (const std::vector< std::string > & dof_names={}) const Eigen::VectorXd forces (const std::vector< std::string > & dof_names={}) const bool free () const void free_from_world (const Eigen::Vector6d & pose=Eigen::Vector6d::Zero()) double friction_coeff (const std::string & body_name) double friction_coeff (size_t body_index) Eigen::Vector3d friction_dir (const std::string & body_name) Eigen::Vector3d friction_dir (size_t body_index) bool ghost () const Eigen::VectorXd gravity_forces (const std::vector< std::string > & dof_names={}) const Eigen::MatrixXd inv_aug_mass_matrix (const std::vector< std::string > & dof_names={}) const Eigen::MatrixXd inv_mass_matrix (const std::vector< std::string > & dof_names={}) const Eigen::MatrixXd jacobian (const std::string & body_name, const std::vector< std::string > & dof_names={}) const Eigen::MatrixXd jacobian_deriv (const std::string & body_name, const std::vector< std::string > & dof_names={}) const dart::dynamics::Joint * joint (const std::string & joint_name) dart::dynamics::Joint * joint (size_t joint_index) size_t joint_index (const std::string & joint_name) const const std::unordered_map< std::string, size_t > & joint_map () const std::string joint_name (size_t joint_index) const std::vector< std::string > joint_names () const std::vector< std::string > locked_dof_names () const Eigen::MatrixXd mass_matrix (const std::vector< std::string > & dof_names={}) const std::vector< std::string > mimic_dof_names () const const std::string & model_filename () const const std::vector< std::pair< std::string, std::string > > & model_packages () const const std::string & name () const size_t num_bodies () const size_t num_controllers () const size_t num_dofs () const size_t num_joints () const std::vector< std::string > passive_dof_names () const std::vector< bool > position_enforced (const std::vector< std::string > & dof_names={}) const Eigen::VectorXd position_lower_limits (const std::vector< std::string > & dof_names={}) const Eigen::VectorXd position_upper_limits (const std::vector< std::string > & dof_names={}) const Eigen::VectorXd positions (const std::vector< std::string > & dof_names={}) const void reinit_controllers () void remove_all_drawing_axis () void remove_controller (const std::shared_ptr< control::RobotControl > & controller) void remove_controller (size_t index) virtual void reset () void reset_commands () double restitution_coeff (const std::string & body_name) double restitution_coeff (size_t body_index) double secondary_friction_coeff (const std::string & body_name) double secondary_friction_coeff (size_t body_index) bool self_colliding () const void set_acceleration_lower_limits (const Eigen::VectorXd & accelerations, const std::vector< std::string > & dof_names={}) void set_acceleration_upper_limits (const Eigen::VectorXd & accelerations, const std::vector< std::string > & dof_names={}) void set_accelerations (const Eigen::VectorXd & accelerations, const std::vector< std::string > & dof_names={}) void set_actuator_type (const std::string & type, const std::string & joint_name, bool override_mimic=false, bool override_base=false) void set_actuator_types (const std::string & type, const std::vector< std::string > & joint_names={}, bool override_mimic=false, bool override_base=false) void set_base_pose (const Eigen::Isometry3d & tf) void set_base_pose (const Eigen::Vector6d & pose) set base pose: pose is a 6D vector (first 3D orientation in angle-axis and last 3D translation) void set_body_mass (const std::string & body_name, double mass) void set_body_mass (size_t body_index, double mass) void set_body_name (size_t body_index, const std::string & body_name) void set_cast_shadows (bool cast_shadows=true) void set_color_mode (const std::string & color_mode) void set_color_mode (const std::string & color_mode, const std::string & body_name) void set_commands (const Eigen::VectorXd & commands, const std::vector< std::string > & dof_names={}) void set_coulomb_coeffs (const std::vector< double > & cfrictions, const std::vector< std::string > & dof_names={}) void set_coulomb_coeffs (double cfriction, const std::vector< std::string > & dof_names={}) void set_damping_coeffs (const std::vector< double > & damps, const std::vector< std::string > & dof_names={}) void set_damping_coeffs (double damp, const std::vector< std::string > & dof_names={}) void set_draw_axis (const std::string & body_name, double size=0.25) void set_external_force (const std::string & body_name, const Eigen::Vector3d & force, const Eigen::Vector3d & offset=Eigen::Vector3d::Zero(), bool force_local=false, bool offset_local=true) void set_external_force (size_t body_index, const Eigen::Vector3d & force, const Eigen::Vector3d & offset=Eigen::Vector3d::Zero(), bool force_local=false, bool offset_local=true) void set_external_torque (const std::string & body_name, const Eigen::Vector3d & torque, bool local=false) void set_external_torque (size_t body_index, const Eigen::Vector3d & torque, bool local=false) void set_force_lower_limits (const Eigen::VectorXd & forces, const std::vector< std::string > & dof_names={}) void set_force_upper_limits (const Eigen::VectorXd & forces, const std::vector< std::string > & dof_names={}) void set_forces (const Eigen::VectorXd & forces, const std::vector< std::string > & dof_names={}) void set_friction_coeff (const std::string & body_name, double value) void set_friction_coeff (size_t body_index, double value) void set_friction_coeffs (double value) void set_friction_dir (const std::string & body_name, const Eigen::Vector3d & direction) void set_friction_dir (size_t body_index, const Eigen::Vector3d & direction) void set_ghost (bool ghost=true) void set_joint_name (size_t joint_index, const std::string & joint_name) void set_mimic (const std::string & joint_name, const std::string & mimic_joint_name, double multiplier=1., double offset=0.) void set_position_enforced (const std::vector< bool > & enforced, const std::vector< std::string > & dof_names={}) void set_position_enforced (bool enforced, const std::vector< std::string > & dof_names={}) void set_position_lower_limits (const Eigen::VectorXd & positions, const std::vector< std::string > & dof_names={}) void set_position_upper_limits (const Eigen::VectorXd & positions, const std::vector< std::string > & dof_names={}) void set_positions (const Eigen::VectorXd & positions, const std::vector< std::string > & dof_names={}) void set_restitution_coeff (const std::string & body_name, double value) void set_restitution_coeff (size_t body_index, double value) void set_restitution_coeffs (double value) void set_secondary_friction_coeff (const std::string & body_name, double value) void set_secondary_friction_coeff (size_t body_index, double value) void set_secondary_friction_coeffs (double value) void set_self_collision (bool enable_self_collisions=true, bool enable_adjacent_collisions=false) void set_spring_stiffnesses (const std::vector< double > & stiffnesses, const std::vector< std::string > & dof_names={}) void set_spring_stiffnesses (double stiffness, const std::vector< std::string > & dof_names={}) void set_velocities (const Eigen::VectorXd & velocities, const std::vector< std::string > & dof_names={}) void set_velocity_lower_limits (const Eigen::VectorXd & velocities, const std::vector< std::string > & dof_names={}) void set_velocity_upper_limits (const Eigen::VectorXd & velocities, const std::vector< std::string > & dof_names={}) dart::dynamics::SkeletonPtr skeleton () std::vector< double > spring_stiffnesses (const std::vector< std::string > & dof_names={}) const void update (double t) void update_joint_dof_maps () Eigen::VectorXd vec_dof (const Eigen::VectorXd & vec, const std::vector< std::string > & dof_names) const Eigen::VectorXd velocities (const std::vector< std::string > & dof_names={}) const Eigen::VectorXd velocity_lower_limits (const std::vector< std::string > & dof_names={}) const Eigen::VectorXd velocity_upper_limits (const std::vector< std::string > & dof_names={}) const virtual ~Robot ()"},{"location":"api/classrobot__dart_1_1robots_1_1Tiago/#public-static-functions-inherited-from-robot_dartrobot","title":"Public Static Functions inherited from robot_dart::Robot","text":"

See robot_dart::Robot

Type Name std::shared_ptr< Robot > create_box (const Eigen::Vector3d & dims, const Eigen::Isometry3d & tf, const std::string & type=\"free\", double mass=1.0, const Eigen::Vector4d & color=dart::Color::Red(1.0), const std::string & box_name=\"box\") std::shared_ptr< Robot > create_box (const Eigen::Vector3d & dims, const Eigen::Vector6d & pose=Eigen::Vector6d::Zero(), const std::string & type=\"free\", double mass=1.0, const Eigen::Vector4d & color=dart::Color::Red(1.0), const std::string & box_name=\"box\") std::shared_ptr< Robot > create_ellipsoid (const Eigen::Vector3d & dims, const Eigen::Isometry3d & tf, const std::string & type=\"free\", double mass=1.0, const Eigen::Vector4d & color=dart::Color::Red(1.0), const std::string & ellipsoid_name=\"ellipsoid\") std::shared_ptr< Robot > create_ellipsoid (const Eigen::Vector3d & dims, const Eigen::Vector6d & pose=Eigen::Vector6d::Zero(), const std::string & type=\"free\", double mass=1.0, const Eigen::Vector4d & color=dart::Color::Red(1.0), const std::string & ellipsoid_name=\"ellipsoid\")"},{"location":"api/classrobot__dart_1_1robots_1_1Tiago/#protected-attributes","title":"Protected Attributes","text":"Type Name std::shared_ptr< sensor::ForceTorque > _ft_wrist"},{"location":"api/classrobot__dart_1_1robots_1_1Tiago/#protected-attributes-inherited-from-robot_dartrobot","title":"Protected Attributes inherited from robot_dart::Robot","text":"

See robot_dart::Robot

Type Name std::vector< std::pair< dart::dynamics::BodyNode *, double > > _axis_shapes bool _cast_shadows std::vector< std::shared_ptr< control::RobotControl > > _controllers std::unordered_map< std::string, size_t > _dof_map bool _is_ghost std::unordered_map< std::string, size_t > _joint_map std::string _model_filename std::vector< std::pair< std::string, std::string > > _packages std::string _robot_name dart::dynamics::SkeletonPtr _skeleton"},{"location":"api/classrobot__dart_1_1robots_1_1Tiago/#protected-functions","title":"Protected Functions","text":"Type Name virtual void _post_addition (RobotDARTSimu *) overrideFunction called by RobotDARTSimu object when adding the robot to the world. virtual void _post_removal (RobotDARTSimu *) overrideFunction called by RobotDARTSimu object when removing the robot to the world."},{"location":"api/classrobot__dart_1_1robots_1_1Tiago/#protected-functions-inherited-from-robot_dartrobot","title":"Protected Functions inherited from robot_dart::Robot","text":"

See robot_dart::Robot

Type Name dart::dynamics::Joint::ActuatorType _actuator_type (size_t joint_index) const std::vector< dart::dynamics::Joint::ActuatorType > _actuator_types () const std::string _get_path (const std::string & filename) const Eigen::MatrixXd _jacobian (const Eigen::MatrixXd & full_jacobian, const std::vector< std::string > & dof_names) const dart::dynamics::SkeletonPtr _load_model (const std::string & filename, const std::vector< std::pair< std::string, std::string > > & packages=std::vector< std::pair< std::string, std::string > >(), bool is_urdf_string=false) Eigen::MatrixXd _mass_matrix (const Eigen::MatrixXd & full_mass_matrix, const std::vector< std::string > & dof_names) const virtual void _post_addition (RobotDARTSimu *) Function called by RobotDARTSimu object when adding the robot to the world. virtual void _post_removal (RobotDARTSimu *) Function called by RobotDARTSimu object when removing the robot to the world. void _set_actuator_type (size_t joint_index, dart::dynamics::Joint::ActuatorType type, bool override_mimic=false, bool override_base=false) void _set_actuator_types (const std::vector< dart::dynamics::Joint::ActuatorType > & types, bool override_mimic=false, bool override_base=false) void _set_actuator_types (dart::dynamics::Joint::ActuatorType type, bool override_mimic=false, bool override_base=false) void _set_color_mode (dart::dynamics::MeshShape::ColorMode color_mode, dart::dynamics::SkeletonPtr skel) void _set_color_mode (dart::dynamics::MeshShape::ColorMode color_mode, dart::dynamics::ShapeNode * sn)"},{"location":"api/classrobot__dart_1_1robots_1_1Tiago/#public-functions-documentation","title":"Public Functions Documentation","text":""},{"location":"api/classrobot__dart_1_1robots_1_1Tiago/#function-tiago","title":"function Tiago","text":"
robot_dart::robots::Tiago::Tiago (\nsize_t frequency=1000,\nconst std::string & urdf=\"tiago/tiago_steel.urdf\",\nconst std::vector< std::pair< std::string, std::string > > & packages=('tiago_description', 'tiago/tiago_description')\n) 
"},{"location":"api/classrobot__dart_1_1robots_1_1Tiago/#function-caster_joints","title":"function caster_joints","text":"
inline std::vector< std::string > robot_dart::robots::Tiago::caster_joints () const\n
"},{"location":"api/classrobot__dart_1_1robots_1_1Tiago/#function-ft_wrist","title":"function ft_wrist","text":"
inline const sensor::ForceTorque & robot_dart::robots::Tiago::ft_wrist () const\n
"},{"location":"api/classrobot__dart_1_1robots_1_1Tiago/#function-reset","title":"function reset","text":"
virtual void robot_dart::robots::Tiago::reset () override\n

Implements robot_dart::Robot::reset

"},{"location":"api/classrobot__dart_1_1robots_1_1Tiago/#function-set_actuator_type","title":"function set_actuator_type","text":"
void robot_dart::robots::Tiago::set_actuator_type (\nconst std::string & type,\nconst std::string & joint_name,\nbool override_mimic=false,\nbool override_base=false,\nbool override_caster=false\n) 
"},{"location":"api/classrobot__dart_1_1robots_1_1Tiago/#function-set_actuator_types","title":"function set_actuator_types","text":"
void robot_dart::robots::Tiago::set_actuator_types (\nconst std::string & type,\nconst std::vector< std::string > & joint_names={},\nbool override_mimic=false,\nbool override_base=false,\nbool override_caster=false\n) 
"},{"location":"api/classrobot__dart_1_1robots_1_1Tiago/#protected-attributes-documentation","title":"Protected Attributes Documentation","text":""},{"location":"api/classrobot__dart_1_1robots_1_1Tiago/#variable-_ft_wrist","title":"variable _ft_wrist","text":"
std::shared_ptr<sensor::ForceTorque> robot_dart::robots::Tiago::_ft_wrist;\n
"},{"location":"api/classrobot__dart_1_1robots_1_1Tiago/#protected-functions-documentation","title":"Protected Functions Documentation","text":""},{"location":"api/classrobot__dart_1_1robots_1_1Tiago/#function-_post_addition","title":"function _post_addition","text":"
virtual void robot_dart::robots::Tiago::_post_addition (\nRobotDARTSimu *\n) override\n

Implements robot_dart::Robot::_post_addition

"},{"location":"api/classrobot__dart_1_1robots_1_1Tiago/#function-_post_removal","title":"function _post_removal","text":"
virtual void robot_dart::robots::Tiago::_post_removal (\nRobotDARTSimu *\n) override\n

Implements robot_dart::Robot::_post_removal

The documentation for this class was generated from the following file robot_dart/robots/tiago.hpp

"},{"location":"api/classrobot__dart_1_1robots_1_1Ur3e/","title":"Class robot_dart::robots::Ur3e","text":"

ClassList > robot_dart > robots > Ur3e

Inherits the following classes: robot_dart::Robot

Inherited by the following classes: robot_dart::robots::Ur3eHand

"},{"location":"api/classrobot__dart_1_1robots_1_1Ur3e/#public-functions","title":"Public Functions","text":"Type Name Ur3e (size_t frequency=1000, const std::string & urdf=\"ur3e/ur3e.urdf\", const std::vector< std::pair< std::string, std::string > > & packages=('ur3e\\_description', 'ur3e/ur3e\\_description')) const sensor::ForceTorque & ft_wrist () const"},{"location":"api/classrobot__dart_1_1robots_1_1Ur3e/#public-functions-inherited-from-robot_dartrobot","title":"Public Functions inherited from robot_dart::Robot","text":"

See robot_dart::Robot

Type Name Robot (const std::string & model_file, const std::vector< std::pair< std::string, std::string > > & packages, const std::string & robot_name=\"robot\", bool is_urdf_string=false, bool cast_shadows=true) Robot (const std::string & model_file, const std::string & robot_name=\"robot\", bool is_urdf_string=false, bool cast_shadows=true) Robot (dart::dynamics::SkeletonPtr skeleton, const std::string & robot_name=\"robot\", bool cast_shadows=true) Eigen::VectorXd acceleration_lower_limits (const std::vector< std::string > & dof_names={}) const Eigen::VectorXd acceleration_upper_limits (const std::vector< std::string > & dof_names={}) const Eigen::VectorXd accelerations (const std::vector< std::string > & dof_names={}) const std::vector< std::shared_ptr< control::RobotControl > > active_controllers () const std::string actuator_type (const std::string & joint_name) const std::vector< std::string > actuator_types (const std::vector< std::string > & joint_names={}) const void add_body_mass (const std::string & body_name, double mass) void add_body_mass (size_t body_index, double mass) void add_controller (const std::shared_ptr< control::RobotControl > & controller, double weight=1.0) void add_external_force (const std::string & body_name, const Eigen::Vector3d & force, const Eigen::Vector3d & offset=Eigen::Vector3d::Zero(), bool force_local=false, bool offset_local=true) void add_external_force (size_t body_index, const Eigen::Vector3d & force, const Eigen::Vector3d & offset=Eigen::Vector3d::Zero(), bool force_local=false, bool offset_local=true) void add_external_torque (const std::string & body_name, const Eigen::Vector3d & torque, bool local=false) void add_external_torque (size_t body_index, const Eigen::Vector3d & torque, bool local=false) bool adjacent_colliding () const Eigen::MatrixXd aug_mass_matrix (const std::vector< std::string > & dof_names={}) const Eigen::Isometry3d base_pose () const Eigen::Vector6d base_pose_vec () const Eigen::Vector6d body_acceleration (const std::string & body_name) const Eigen::Vector6d body_acceleration (size_t body_index) const size_t body_index (const std::string & body_name) const double body_mass (const std::string & body_name) const double body_mass (size_t body_index) const std::string body_name (size_t body_index) const std::vector< std::string > body_names () const dart::dynamics::BodyNode * body_node (const std::string & body_name) dart::dynamics::BodyNode * body_node (size_t body_index) Eigen::Isometry3d body_pose (const std::string & body_name) const Eigen::Isometry3d body_pose (size_t body_index) const Eigen::Vector6d body_pose_vec (const std::string & body_name) const Eigen::Vector6d body_pose_vec (size_t body_index) const Eigen::Vector6d body_velocity (const std::string & body_name) const Eigen::Vector6d body_velocity (size_t body_index) const bool cast_shadows () const void clear_controllers () void clear_external_forces () void clear_internal_forces () std::shared_ptr< Robot > clone () const std::shared_ptr< Robot > clone_ghost (const std::string & ghost_name=\"ghost\", const Eigen::Vector4d & ghost_color={0.3, 0.3, 0.3, 0.7}) const Eigen::Vector3d com () const Eigen::Vector6d com_acceleration () const Eigen::MatrixXd com_jacobian (const std::vector< std::string > & dof_names={}) const Eigen::MatrixXd com_jacobian_deriv (const std::vector< std::string > & dof_names={}) const Eigen::Vector6d com_velocity () const Eigen::VectorXd commands (const std::vector< std::string > & dof_names={}) const Eigen::VectorXd constraint_forces (const std::vector< std::string > & dof_names={}) const std::shared_ptr< control::RobotControl > controller (size_t index) const std::vector< std::shared_ptr< control::RobotControl > > controllers () const Eigen::VectorXd coriolis_forces (const std::vector< std::string > & dof_names={}) const Eigen::VectorXd coriolis_gravity_forces (const std::vector< std::string > & dof_names={}) const std::vector< double > coulomb_coeffs (const std::vector< std::string > & dof_names={}) const std::vector< double > damping_coeffs (const std::vector< std::string > & dof_names={}) const dart::dynamics::DegreeOfFreedom * dof (const std::string & dof_name) dart::dynamics::DegreeOfFreedom * dof (size_t dof_index) size_t dof_index (const std::string & dof_name) const const std::unordered_map< std::string, size_t > & dof_map () const std::string dof_name (size_t dof_index) const std::vector< std::string > dof_names (bool filter_mimics=false, bool filter_locked=false, bool filter_passive=false) const const std::vector< std::pair< dart::dynamics::BodyNode *, double > > & drawing_axes () const Eigen::Vector6d external_forces (const std::string & body_name) const Eigen::Vector6d external_forces (size_t body_index) const void fix_to_world () bool fixed () const Eigen::VectorXd force_lower_limits (const std::vector< std::string > & dof_names={}) const void force_position_bounds () std::pair< Eigen::Vector6d, Eigen::Vector6d > force_torque (size_t joint_index) const Eigen::VectorXd force_upper_limits (const std::vector< std::string > & dof_names={}) const Eigen::VectorXd forces (const std::vector< std::string > & dof_names={}) const bool free () const void free_from_world (const Eigen::Vector6d & pose=Eigen::Vector6d::Zero()) double friction_coeff (const std::string & body_name) double friction_coeff (size_t body_index) Eigen::Vector3d friction_dir (const std::string & body_name) Eigen::Vector3d friction_dir (size_t body_index) bool ghost () const Eigen::VectorXd gravity_forces (const std::vector< std::string > & dof_names={}) const Eigen::MatrixXd inv_aug_mass_matrix (const std::vector< std::string > & dof_names={}) const Eigen::MatrixXd inv_mass_matrix (const std::vector< std::string > & dof_names={}) const Eigen::MatrixXd jacobian (const std::string & body_name, const std::vector< std::string > & dof_names={}) const Eigen::MatrixXd jacobian_deriv (const std::string & body_name, const std::vector< std::string > & dof_names={}) const dart::dynamics::Joint * joint (const std::string & joint_name) dart::dynamics::Joint * joint (size_t joint_index) size_t joint_index (const std::string & joint_name) const const std::unordered_map< std::string, size_t > & joint_map () const std::string joint_name (size_t joint_index) const std::vector< std::string > joint_names () const std::vector< std::string > locked_dof_names () const Eigen::MatrixXd mass_matrix (const std::vector< std::string > & dof_names={}) const std::vector< std::string > mimic_dof_names () const const std::string & model_filename () const const std::vector< std::pair< std::string, std::string > > & model_packages () const const std::string & name () const size_t num_bodies () const size_t num_controllers () const size_t num_dofs () const size_t num_joints () const std::vector< std::string > passive_dof_names () const std::vector< bool > position_enforced (const std::vector< std::string > & dof_names={}) const Eigen::VectorXd position_lower_limits (const std::vector< std::string > & dof_names={}) const Eigen::VectorXd position_upper_limits (const std::vector< std::string > & dof_names={}) const Eigen::VectorXd positions (const std::vector< std::string > & dof_names={}) const void reinit_controllers () void remove_all_drawing_axis () void remove_controller (const std::shared_ptr< control::RobotControl > & controller) void remove_controller (size_t index) virtual void reset () void reset_commands () double restitution_coeff (const std::string & body_name) double restitution_coeff (size_t body_index) double secondary_friction_coeff (const std::string & body_name) double secondary_friction_coeff (size_t body_index) bool self_colliding () const void set_acceleration_lower_limits (const Eigen::VectorXd & accelerations, const std::vector< std::string > & dof_names={}) void set_acceleration_upper_limits (const Eigen::VectorXd & accelerations, const std::vector< std::string > & dof_names={}) void set_accelerations (const Eigen::VectorXd & accelerations, const std::vector< std::string > & dof_names={}) void set_actuator_type (const std::string & type, const std::string & joint_name, bool override_mimic=false, bool override_base=false) void set_actuator_types (const std::string & type, const std::vector< std::string > & joint_names={}, bool override_mimic=false, bool override_base=false) void set_base_pose (const Eigen::Isometry3d & tf) void set_base_pose (const Eigen::Vector6d & pose) set base pose: pose is a 6D vector (first 3D orientation in angle-axis and last 3D translation) void set_body_mass (const std::string & body_name, double mass) void set_body_mass (size_t body_index, double mass) void set_body_name (size_t body_index, const std::string & body_name) void set_cast_shadows (bool cast_shadows=true) void set_color_mode (const std::string & color_mode) void set_color_mode (const std::string & color_mode, const std::string & body_name) void set_commands (const Eigen::VectorXd & commands, const std::vector< std::string > & dof_names={}) void set_coulomb_coeffs (const std::vector< double > & cfrictions, const std::vector< std::string > & dof_names={}) void set_coulomb_coeffs (double cfriction, const std::vector< std::string > & dof_names={}) void set_damping_coeffs (const std::vector< double > & damps, const std::vector< std::string > & dof_names={}) void set_damping_coeffs (double damp, const std::vector< std::string > & dof_names={}) void set_draw_axis (const std::string & body_name, double size=0.25) void set_external_force (const std::string & body_name, const Eigen::Vector3d & force, const Eigen::Vector3d & offset=Eigen::Vector3d::Zero(), bool force_local=false, bool offset_local=true) void set_external_force (size_t body_index, const Eigen::Vector3d & force, const Eigen::Vector3d & offset=Eigen::Vector3d::Zero(), bool force_local=false, bool offset_local=true) void set_external_torque (const std::string & body_name, const Eigen::Vector3d & torque, bool local=false) void set_external_torque (size_t body_index, const Eigen::Vector3d & torque, bool local=false) void set_force_lower_limits (const Eigen::VectorXd & forces, const std::vector< std::string > & dof_names={}) void set_force_upper_limits (const Eigen::VectorXd & forces, const std::vector< std::string > & dof_names={}) void set_forces (const Eigen::VectorXd & forces, const std::vector< std::string > & dof_names={}) void set_friction_coeff (const std::string & body_name, double value) void set_friction_coeff (size_t body_index, double value) void set_friction_coeffs (double value) void set_friction_dir (const std::string & body_name, const Eigen::Vector3d & direction) void set_friction_dir (size_t body_index, const Eigen::Vector3d & direction) void set_ghost (bool ghost=true) void set_joint_name (size_t joint_index, const std::string & joint_name) void set_mimic (const std::string & joint_name, const std::string & mimic_joint_name, double multiplier=1., double offset=0.) void set_position_enforced (const std::vector< bool > & enforced, const std::vector< std::string > & dof_names={}) void set_position_enforced (bool enforced, const std::vector< std::string > & dof_names={}) void set_position_lower_limits (const Eigen::VectorXd & positions, const std::vector< std::string > & dof_names={}) void set_position_upper_limits (const Eigen::VectorXd & positions, const std::vector< std::string > & dof_names={}) void set_positions (const Eigen::VectorXd & positions, const std::vector< std::string > & dof_names={}) void set_restitution_coeff (const std::string & body_name, double value) void set_restitution_coeff (size_t body_index, double value) void set_restitution_coeffs (double value) void set_secondary_friction_coeff (const std::string & body_name, double value) void set_secondary_friction_coeff (size_t body_index, double value) void set_secondary_friction_coeffs (double value) void set_self_collision (bool enable_self_collisions=true, bool enable_adjacent_collisions=false) void set_spring_stiffnesses (const std::vector< double > & stiffnesses, const std::vector< std::string > & dof_names={}) void set_spring_stiffnesses (double stiffness, const std::vector< std::string > & dof_names={}) void set_velocities (const Eigen::VectorXd & velocities, const std::vector< std::string > & dof_names={}) void set_velocity_lower_limits (const Eigen::VectorXd & velocities, const std::vector< std::string > & dof_names={}) void set_velocity_upper_limits (const Eigen::VectorXd & velocities, const std::vector< std::string > & dof_names={}) dart::dynamics::SkeletonPtr skeleton () std::vector< double > spring_stiffnesses (const std::vector< std::string > & dof_names={}) const void update (double t) void update_joint_dof_maps () Eigen::VectorXd vec_dof (const Eigen::VectorXd & vec, const std::vector< std::string > & dof_names) const Eigen::VectorXd velocities (const std::vector< std::string > & dof_names={}) const Eigen::VectorXd velocity_lower_limits (const std::vector< std::string > & dof_names={}) const Eigen::VectorXd velocity_upper_limits (const std::vector< std::string > & dof_names={}) const virtual ~Robot ()"},{"location":"api/classrobot__dart_1_1robots_1_1Ur3e/#public-static-functions-inherited-from-robot_dartrobot","title":"Public Static Functions inherited from robot_dart::Robot","text":"

See robot_dart::Robot

Type Name std::shared_ptr< Robot > create_box (const Eigen::Vector3d & dims, const Eigen::Isometry3d & tf, const std::string & type=\"free\", double mass=1.0, const Eigen::Vector4d & color=dart::Color::Red(1.0), const std::string & box_name=\"box\") std::shared_ptr< Robot > create_box (const Eigen::Vector3d & dims, const Eigen::Vector6d & pose=Eigen::Vector6d::Zero(), const std::string & type=\"free\", double mass=1.0, const Eigen::Vector4d & color=dart::Color::Red(1.0), const std::string & box_name=\"box\") std::shared_ptr< Robot > create_ellipsoid (const Eigen::Vector3d & dims, const Eigen::Isometry3d & tf, const std::string & type=\"free\", double mass=1.0, const Eigen::Vector4d & color=dart::Color::Red(1.0), const std::string & ellipsoid_name=\"ellipsoid\") std::shared_ptr< Robot > create_ellipsoid (const Eigen::Vector3d & dims, const Eigen::Vector6d & pose=Eigen::Vector6d::Zero(), const std::string & type=\"free\", double mass=1.0, const Eigen::Vector4d & color=dart::Color::Red(1.0), const std::string & ellipsoid_name=\"ellipsoid\")"},{"location":"api/classrobot__dart_1_1robots_1_1Ur3e/#protected-attributes","title":"Protected Attributes","text":"Type Name std::shared_ptr< sensor::ForceTorque > _ft_wrist"},{"location":"api/classrobot__dart_1_1robots_1_1Ur3e/#protected-attributes-inherited-from-robot_dartrobot","title":"Protected Attributes inherited from robot_dart::Robot","text":"

See robot_dart::Robot

Type Name std::vector< std::pair< dart::dynamics::BodyNode *, double > > _axis_shapes bool _cast_shadows std::vector< std::shared_ptr< control::RobotControl > > _controllers std::unordered_map< std::string, size_t > _dof_map bool _is_ghost std::unordered_map< std::string, size_t > _joint_map std::string _model_filename std::vector< std::pair< std::string, std::string > > _packages std::string _robot_name dart::dynamics::SkeletonPtr _skeleton"},{"location":"api/classrobot__dart_1_1robots_1_1Ur3e/#protected-functions","title":"Protected Functions","text":"Type Name virtual void _post_addition (RobotDARTSimu *) overrideFunction called by RobotDARTSimu object when adding the robot to the world. virtual void _post_removal (RobotDARTSimu *) overrideFunction called by RobotDARTSimu object when removing the robot to the world."},{"location":"api/classrobot__dart_1_1robots_1_1Ur3e/#protected-functions-inherited-from-robot_dartrobot","title":"Protected Functions inherited from robot_dart::Robot","text":"

See robot_dart::Robot

Type Name dart::dynamics::Joint::ActuatorType _actuator_type (size_t joint_index) const std::vector< dart::dynamics::Joint::ActuatorType > _actuator_types () const std::string _get_path (const std::string & filename) const Eigen::MatrixXd _jacobian (const Eigen::MatrixXd & full_jacobian, const std::vector< std::string > & dof_names) const dart::dynamics::SkeletonPtr _load_model (const std::string & filename, const std::vector< std::pair< std::string, std::string > > & packages=std::vector< std::pair< std::string, std::string > >(), bool is_urdf_string=false) Eigen::MatrixXd _mass_matrix (const Eigen::MatrixXd & full_mass_matrix, const std::vector< std::string > & dof_names) const virtual void _post_addition (RobotDARTSimu *) Function called by RobotDARTSimu object when adding the robot to the world. virtual void _post_removal (RobotDARTSimu *) Function called by RobotDARTSimu object when removing the robot to the world. void _set_actuator_type (size_t joint_index, dart::dynamics::Joint::ActuatorType type, bool override_mimic=false, bool override_base=false) void _set_actuator_types (const std::vector< dart::dynamics::Joint::ActuatorType > & types, bool override_mimic=false, bool override_base=false) void _set_actuator_types (dart::dynamics::Joint::ActuatorType type, bool override_mimic=false, bool override_base=false) void _set_color_mode (dart::dynamics::MeshShape::ColorMode color_mode, dart::dynamics::SkeletonPtr skel) void _set_color_mode (dart::dynamics::MeshShape::ColorMode color_mode, dart::dynamics::ShapeNode * sn)"},{"location":"api/classrobot__dart_1_1robots_1_1Ur3e/#public-functions-documentation","title":"Public Functions Documentation","text":""},{"location":"api/classrobot__dart_1_1robots_1_1Ur3e/#function-ur3e","title":"function Ur3e","text":"
robot_dart::robots::Ur3e::Ur3e (\nsize_t frequency=1000,\nconst std::string & urdf=\"ur3e/ur3e.urdf\",\nconst std::vector< std::pair< std::string, std::string > > & packages=('ur3e_description', 'ur3e/ur3e_description')\n) 
"},{"location":"api/classrobot__dart_1_1robots_1_1Ur3e/#function-ft_wrist","title":"function ft_wrist","text":"
inline const sensor::ForceTorque & robot_dart::robots::Ur3e::ft_wrist () const\n
"},{"location":"api/classrobot__dart_1_1robots_1_1Ur3e/#protected-attributes-documentation","title":"Protected Attributes Documentation","text":""},{"location":"api/classrobot__dart_1_1robots_1_1Ur3e/#variable-_ft_wrist","title":"variable _ft_wrist","text":"
std::shared_ptr<sensor::ForceTorque> robot_dart::robots::Ur3e::_ft_wrist;\n
"},{"location":"api/classrobot__dart_1_1robots_1_1Ur3e/#protected-functions-documentation","title":"Protected Functions Documentation","text":""},{"location":"api/classrobot__dart_1_1robots_1_1Ur3e/#function-_post_addition","title":"function _post_addition","text":"
virtual void robot_dart::robots::Ur3e::_post_addition (\nRobotDARTSimu *\n) override\n

Implements robot_dart::Robot::_post_addition

"},{"location":"api/classrobot__dart_1_1robots_1_1Ur3e/#function-_post_removal","title":"function _post_removal","text":"
virtual void robot_dart::robots::Ur3e::_post_removal (\nRobotDARTSimu *\n) override\n

Implements robot_dart::Robot::_post_removal

The documentation for this class was generated from the following file robot_dart/robots/ur3e.hpp

"},{"location":"api/classrobot__dart_1_1robots_1_1Ur3eHand/","title":"Class robot_dart::robots::Ur3eHand","text":"

ClassList > robot_dart > robots > Ur3eHand

Inherits the following classes: robot_dart::robots::Ur3e

"},{"location":"api/classrobot__dart_1_1robots_1_1Ur3eHand/#public-functions","title":"Public Functions","text":"Type Name Ur3eHand (size_t frequency=1000, const std::string & urdf=\"ur3e/ur3e_with_schunk_hand.urdf\", const std::vector< std::pair< std::string, std::string > > & packages=('ur3e\\_description', 'ur3e/ur3e\\_description'))"},{"location":"api/classrobot__dart_1_1robots_1_1Ur3eHand/#public-functions-inherited-from-robot_dartrobotsur3e","title":"Public Functions inherited from robot_dart::robots::Ur3e","text":"

See robot_dart::robots::Ur3e

Type Name Ur3e (size_t frequency=1000, const std::string & urdf=\"ur3e/ur3e.urdf\", const std::vector< std::pair< std::string, std::string > > & packages=('ur3e\\_description', 'ur3e/ur3e\\_description')) const sensor::ForceTorque & ft_wrist () const"},{"location":"api/classrobot__dart_1_1robots_1_1Ur3eHand/#public-functions-inherited-from-robot_dartrobot","title":"Public Functions inherited from robot_dart::Robot","text":"

See robot_dart::Robot

Type Name Robot (const std::string & model_file, const std::vector< std::pair< std::string, std::string > > & packages, const std::string & robot_name=\"robot\", bool is_urdf_string=false, bool cast_shadows=true) Robot (const std::string & model_file, const std::string & robot_name=\"robot\", bool is_urdf_string=false, bool cast_shadows=true) Robot (dart::dynamics::SkeletonPtr skeleton, const std::string & robot_name=\"robot\", bool cast_shadows=true) Eigen::VectorXd acceleration_lower_limits (const std::vector< std::string > & dof_names={}) const Eigen::VectorXd acceleration_upper_limits (const std::vector< std::string > & dof_names={}) const Eigen::VectorXd accelerations (const std::vector< std::string > & dof_names={}) const std::vector< std::shared_ptr< control::RobotControl > > active_controllers () const std::string actuator_type (const std::string & joint_name) const std::vector< std::string > actuator_types (const std::vector< std::string > & joint_names={}) const void add_body_mass (const std::string & body_name, double mass) void add_body_mass (size_t body_index, double mass) void add_controller (const std::shared_ptr< control::RobotControl > & controller, double weight=1.0) void add_external_force (const std::string & body_name, const Eigen::Vector3d & force, const Eigen::Vector3d & offset=Eigen::Vector3d::Zero(), bool force_local=false, bool offset_local=true) void add_external_force (size_t body_index, const Eigen::Vector3d & force, const Eigen::Vector3d & offset=Eigen::Vector3d::Zero(), bool force_local=false, bool offset_local=true) void add_external_torque (const std::string & body_name, const Eigen::Vector3d & torque, bool local=false) void add_external_torque (size_t body_index, const Eigen::Vector3d & torque, bool local=false) bool adjacent_colliding () const Eigen::MatrixXd aug_mass_matrix (const std::vector< std::string > & dof_names={}) const Eigen::Isometry3d base_pose () const Eigen::Vector6d base_pose_vec () const Eigen::Vector6d body_acceleration (const std::string & body_name) const Eigen::Vector6d body_acceleration (size_t body_index) const size_t body_index (const std::string & body_name) const double body_mass (const std::string & body_name) const double body_mass (size_t body_index) const std::string body_name (size_t body_index) const std::vector< std::string > body_names () const dart::dynamics::BodyNode * body_node (const std::string & body_name) dart::dynamics::BodyNode * body_node (size_t body_index) Eigen::Isometry3d body_pose (const std::string & body_name) const Eigen::Isometry3d body_pose (size_t body_index) const Eigen::Vector6d body_pose_vec (const std::string & body_name) const Eigen::Vector6d body_pose_vec (size_t body_index) const Eigen::Vector6d body_velocity (const std::string & body_name) const Eigen::Vector6d body_velocity (size_t body_index) const bool cast_shadows () const void clear_controllers () void clear_external_forces () void clear_internal_forces () std::shared_ptr< Robot > clone () const std::shared_ptr< Robot > clone_ghost (const std::string & ghost_name=\"ghost\", const Eigen::Vector4d & ghost_color={0.3, 0.3, 0.3, 0.7}) const Eigen::Vector3d com () const Eigen::Vector6d com_acceleration () const Eigen::MatrixXd com_jacobian (const std::vector< std::string > & dof_names={}) const Eigen::MatrixXd com_jacobian_deriv (const std::vector< std::string > & dof_names={}) const Eigen::Vector6d com_velocity () const Eigen::VectorXd commands (const std::vector< std::string > & dof_names={}) const Eigen::VectorXd constraint_forces (const std::vector< std::string > & dof_names={}) const std::shared_ptr< control::RobotControl > controller (size_t index) const std::vector< std::shared_ptr< control::RobotControl > > controllers () const Eigen::VectorXd coriolis_forces (const std::vector< std::string > & dof_names={}) const Eigen::VectorXd coriolis_gravity_forces (const std::vector< std::string > & dof_names={}) const std::vector< double > coulomb_coeffs (const std::vector< std::string > & dof_names={}) const std::vector< double > damping_coeffs (const std::vector< std::string > & dof_names={}) const dart::dynamics::DegreeOfFreedom * dof (const std::string & dof_name) dart::dynamics::DegreeOfFreedom * dof (size_t dof_index) size_t dof_index (const std::string & dof_name) const const std::unordered_map< std::string, size_t > & dof_map () const std::string dof_name (size_t dof_index) const std::vector< std::string > dof_names (bool filter_mimics=false, bool filter_locked=false, bool filter_passive=false) const const std::vector< std::pair< dart::dynamics::BodyNode *, double > > & drawing_axes () const Eigen::Vector6d external_forces (const std::string & body_name) const Eigen::Vector6d external_forces (size_t body_index) const void fix_to_world () bool fixed () const Eigen::VectorXd force_lower_limits (const std::vector< std::string > & dof_names={}) const void force_position_bounds () std::pair< Eigen::Vector6d, Eigen::Vector6d > force_torque (size_t joint_index) const Eigen::VectorXd force_upper_limits (const std::vector< std::string > & dof_names={}) const Eigen::VectorXd forces (const std::vector< std::string > & dof_names={}) const bool free () const void free_from_world (const Eigen::Vector6d & pose=Eigen::Vector6d::Zero()) double friction_coeff (const std::string & body_name) double friction_coeff (size_t body_index) Eigen::Vector3d friction_dir (const std::string & body_name) Eigen::Vector3d friction_dir (size_t body_index) bool ghost () const Eigen::VectorXd gravity_forces (const std::vector< std::string > & dof_names={}) const Eigen::MatrixXd inv_aug_mass_matrix (const std::vector< std::string > & dof_names={}) const Eigen::MatrixXd inv_mass_matrix (const std::vector< std::string > & dof_names={}) const Eigen::MatrixXd jacobian (const std::string & body_name, const std::vector< std::string > & dof_names={}) const Eigen::MatrixXd jacobian_deriv (const std::string & body_name, const std::vector< std::string > & dof_names={}) const dart::dynamics::Joint * joint (const std::string & joint_name) dart::dynamics::Joint * joint (size_t joint_index) size_t joint_index (const std::string & joint_name) const const std::unordered_map< std::string, size_t > & joint_map () const std::string joint_name (size_t joint_index) const std::vector< std::string > joint_names () const std::vector< std::string > locked_dof_names () const Eigen::MatrixXd mass_matrix (const std::vector< std::string > & dof_names={}) const std::vector< std::string > mimic_dof_names () const const std::string & model_filename () const const std::vector< std::pair< std::string, std::string > > & model_packages () const const std::string & name () const size_t num_bodies () const size_t num_controllers () const size_t num_dofs () const size_t num_joints () const std::vector< std::string > passive_dof_names () const std::vector< bool > position_enforced (const std::vector< std::string > & dof_names={}) const Eigen::VectorXd position_lower_limits (const std::vector< std::string > & dof_names={}) const Eigen::VectorXd position_upper_limits (const std::vector< std::string > & dof_names={}) const Eigen::VectorXd positions (const std::vector< std::string > & dof_names={}) const void reinit_controllers () void remove_all_drawing_axis () void remove_controller (const std::shared_ptr< control::RobotControl > & controller) void remove_controller (size_t index) virtual void reset () void reset_commands () double restitution_coeff (const std::string & body_name) double restitution_coeff (size_t body_index) double secondary_friction_coeff (const std::string & body_name) double secondary_friction_coeff (size_t body_index) bool self_colliding () const void set_acceleration_lower_limits (const Eigen::VectorXd & accelerations, const std::vector< std::string > & dof_names={}) void set_acceleration_upper_limits (const Eigen::VectorXd & accelerations, const std::vector< std::string > & dof_names={}) void set_accelerations (const Eigen::VectorXd & accelerations, const std::vector< std::string > & dof_names={}) void set_actuator_type (const std::string & type, const std::string & joint_name, bool override_mimic=false, bool override_base=false) void set_actuator_types (const std::string & type, const std::vector< std::string > & joint_names={}, bool override_mimic=false, bool override_base=false) void set_base_pose (const Eigen::Isometry3d & tf) void set_base_pose (const Eigen::Vector6d & pose) set base pose: pose is a 6D vector (first 3D orientation in angle-axis and last 3D translation) void set_body_mass (const std::string & body_name, double mass) void set_body_mass (size_t body_index, double mass) void set_body_name (size_t body_index, const std::string & body_name) void set_cast_shadows (bool cast_shadows=true) void set_color_mode (const std::string & color_mode) void set_color_mode (const std::string & color_mode, const std::string & body_name) void set_commands (const Eigen::VectorXd & commands, const std::vector< std::string > & dof_names={}) void set_coulomb_coeffs (const std::vector< double > & cfrictions, const std::vector< std::string > & dof_names={}) void set_coulomb_coeffs (double cfriction, const std::vector< std::string > & dof_names={}) void set_damping_coeffs (const std::vector< double > & damps, const std::vector< std::string > & dof_names={}) void set_damping_coeffs (double damp, const std::vector< std::string > & dof_names={}) void set_draw_axis (const std::string & body_name, double size=0.25) void set_external_force (const std::string & body_name, const Eigen::Vector3d & force, const Eigen::Vector3d & offset=Eigen::Vector3d::Zero(), bool force_local=false, bool offset_local=true) void set_external_force (size_t body_index, const Eigen::Vector3d & force, const Eigen::Vector3d & offset=Eigen::Vector3d::Zero(), bool force_local=false, bool offset_local=true) void set_external_torque (const std::string & body_name, const Eigen::Vector3d & torque, bool local=false) void set_external_torque (size_t body_index, const Eigen::Vector3d & torque, bool local=false) void set_force_lower_limits (const Eigen::VectorXd & forces, const std::vector< std::string > & dof_names={}) void set_force_upper_limits (const Eigen::VectorXd & forces, const std::vector< std::string > & dof_names={}) void set_forces (const Eigen::VectorXd & forces, const std::vector< std::string > & dof_names={}) void set_friction_coeff (const std::string & body_name, double value) void set_friction_coeff (size_t body_index, double value) void set_friction_coeffs (double value) void set_friction_dir (const std::string & body_name, const Eigen::Vector3d & direction) void set_friction_dir (size_t body_index, const Eigen::Vector3d & direction) void set_ghost (bool ghost=true) void set_joint_name (size_t joint_index, const std::string & joint_name) void set_mimic (const std::string & joint_name, const std::string & mimic_joint_name, double multiplier=1., double offset=0.) void set_position_enforced (const std::vector< bool > & enforced, const std::vector< std::string > & dof_names={}) void set_position_enforced (bool enforced, const std::vector< std::string > & dof_names={}) void set_position_lower_limits (const Eigen::VectorXd & positions, const std::vector< std::string > & dof_names={}) void set_position_upper_limits (const Eigen::VectorXd & positions, const std::vector< std::string > & dof_names={}) void set_positions (const Eigen::VectorXd & positions, const std::vector< std::string > & dof_names={}) void set_restitution_coeff (const std::string & body_name, double value) void set_restitution_coeff (size_t body_index, double value) void set_restitution_coeffs (double value) void set_secondary_friction_coeff (const std::string & body_name, double value) void set_secondary_friction_coeff (size_t body_index, double value) void set_secondary_friction_coeffs (double value) void set_self_collision (bool enable_self_collisions=true, bool enable_adjacent_collisions=false) void set_spring_stiffnesses (const std::vector< double > & stiffnesses, const std::vector< std::string > & dof_names={}) void set_spring_stiffnesses (double stiffness, const std::vector< std::string > & dof_names={}) void set_velocities (const Eigen::VectorXd & velocities, const std::vector< std::string > & dof_names={}) void set_velocity_lower_limits (const Eigen::VectorXd & velocities, const std::vector< std::string > & dof_names={}) void set_velocity_upper_limits (const Eigen::VectorXd & velocities, const std::vector< std::string > & dof_names={}) dart::dynamics::SkeletonPtr skeleton () std::vector< double > spring_stiffnesses (const std::vector< std::string > & dof_names={}) const void update (double t) void update_joint_dof_maps () Eigen::VectorXd vec_dof (const Eigen::VectorXd & vec, const std::vector< std::string > & dof_names) const Eigen::VectorXd velocities (const std::vector< std::string > & dof_names={}) const Eigen::VectorXd velocity_lower_limits (const std::vector< std::string > & dof_names={}) const Eigen::VectorXd velocity_upper_limits (const std::vector< std::string > & dof_names={}) const virtual ~Robot ()"},{"location":"api/classrobot__dart_1_1robots_1_1Ur3eHand/#public-static-functions-inherited-from-robot_dartrobot","title":"Public Static Functions inherited from robot_dart::Robot","text":"

See robot_dart::Robot

Type Name std::shared_ptr< Robot > create_box (const Eigen::Vector3d & dims, const Eigen::Isometry3d & tf, const std::string & type=\"free\", double mass=1.0, const Eigen::Vector4d & color=dart::Color::Red(1.0), const std::string & box_name=\"box\") std::shared_ptr< Robot > create_box (const Eigen::Vector3d & dims, const Eigen::Vector6d & pose=Eigen::Vector6d::Zero(), const std::string & type=\"free\", double mass=1.0, const Eigen::Vector4d & color=dart::Color::Red(1.0), const std::string & box_name=\"box\") std::shared_ptr< Robot > create_ellipsoid (const Eigen::Vector3d & dims, const Eigen::Isometry3d & tf, const std::string & type=\"free\", double mass=1.0, const Eigen::Vector4d & color=dart::Color::Red(1.0), const std::string & ellipsoid_name=\"ellipsoid\") std::shared_ptr< Robot > create_ellipsoid (const Eigen::Vector3d & dims, const Eigen::Vector6d & pose=Eigen::Vector6d::Zero(), const std::string & type=\"free\", double mass=1.0, const Eigen::Vector4d & color=dart::Color::Red(1.0), const std::string & ellipsoid_name=\"ellipsoid\")"},{"location":"api/classrobot__dart_1_1robots_1_1Ur3eHand/#protected-attributes-inherited-from-robot_dartrobotsur3e","title":"Protected Attributes inherited from robot_dart::robots::Ur3e","text":"

See robot_dart::robots::Ur3e

Type Name std::shared_ptr< sensor::ForceTorque > _ft_wrist"},{"location":"api/classrobot__dart_1_1robots_1_1Ur3eHand/#protected-attributes-inherited-from-robot_dartrobot","title":"Protected Attributes inherited from robot_dart::Robot","text":"

See robot_dart::Robot

Type Name std::vector< std::pair< dart::dynamics::BodyNode *, double > > _axis_shapes bool _cast_shadows std::vector< std::shared_ptr< control::RobotControl > > _controllers std::unordered_map< std::string, size_t > _dof_map bool _is_ghost std::unordered_map< std::string, size_t > _joint_map std::string _model_filename std::vector< std::pair< std::string, std::string > > _packages std::string _robot_name dart::dynamics::SkeletonPtr _skeleton"},{"location":"api/classrobot__dart_1_1robots_1_1Ur3eHand/#protected-functions-inherited-from-robot_dartrobotsur3e","title":"Protected Functions inherited from robot_dart::robots::Ur3e","text":"

See robot_dart::robots::Ur3e

Type Name virtual void _post_addition (RobotDARTSimu *) overrideFunction called by RobotDARTSimu object when adding the robot to the world. virtual void _post_removal (RobotDARTSimu *) overrideFunction called by RobotDARTSimu object when removing the robot to the world."},{"location":"api/classrobot__dart_1_1robots_1_1Ur3eHand/#protected-functions-inherited-from-robot_dartrobot","title":"Protected Functions inherited from robot_dart::Robot","text":"

See robot_dart::Robot

Type Name dart::dynamics::Joint::ActuatorType _actuator_type (size_t joint_index) const std::vector< dart::dynamics::Joint::ActuatorType > _actuator_types () const std::string _get_path (const std::string & filename) const Eigen::MatrixXd _jacobian (const Eigen::MatrixXd & full_jacobian, const std::vector< std::string > & dof_names) const dart::dynamics::SkeletonPtr _load_model (const std::string & filename, const std::vector< std::pair< std::string, std::string > > & packages=std::vector< std::pair< std::string, std::string > >(), bool is_urdf_string=false) Eigen::MatrixXd _mass_matrix (const Eigen::MatrixXd & full_mass_matrix, const std::vector< std::string > & dof_names) const virtual void _post_addition (RobotDARTSimu *) Function called by RobotDARTSimu object when adding the robot to the world. virtual void _post_removal (RobotDARTSimu *) Function called by RobotDARTSimu object when removing the robot to the world. void _set_actuator_type (size_t joint_index, dart::dynamics::Joint::ActuatorType type, bool override_mimic=false, bool override_base=false) void _set_actuator_types (const std::vector< dart::dynamics::Joint::ActuatorType > & types, bool override_mimic=false, bool override_base=false) void _set_actuator_types (dart::dynamics::Joint::ActuatorType type, bool override_mimic=false, bool override_base=false) void _set_color_mode (dart::dynamics::MeshShape::ColorMode color_mode, dart::dynamics::SkeletonPtr skel) void _set_color_mode (dart::dynamics::MeshShape::ColorMode color_mode, dart::dynamics::ShapeNode * sn)"},{"location":"api/classrobot__dart_1_1robots_1_1Ur3eHand/#public-functions-documentation","title":"Public Functions Documentation","text":""},{"location":"api/classrobot__dart_1_1robots_1_1Ur3eHand/#function-ur3ehand","title":"function Ur3eHand","text":"
inline robot_dart::robots::Ur3eHand::Ur3eHand (\nsize_t frequency=1000,\nconst std::string & urdf=\"ur3e/ur3e_with_schunk_hand.urdf\",\nconst std::vector< std::pair< std::string, std::string > > & packages=('ur3e_description', 'ur3e/ur3e_description')\n) 

The documentation for this class was generated from the following file robot_dart/robots/ur3e.hpp

"},{"location":"api/classrobot__dart_1_1robots_1_1Vx300/","title":"Class robot_dart::robots::Vx300","text":"

ClassList > robot_dart > robots > Vx300

Inherits the following classes: robot_dart::Robot

"},{"location":"api/classrobot__dart_1_1robots_1_1Vx300/#public-functions","title":"Public Functions","text":"Type Name Vx300 (const std::string & urdf=\"vx300/vx300.urdf\", const std::vector< std::pair< std::string, std::string > > & packages=('interbotix\\_xsarm\\_descriptions', 'vx300'))"},{"location":"api/classrobot__dart_1_1robots_1_1Vx300/#public-functions-inherited-from-robot_dartrobot","title":"Public Functions inherited from robot_dart::Robot","text":"

See robot_dart::Robot

Type Name Robot (const std::string & model_file, const std::vector< std::pair< std::string, std::string > > & packages, const std::string & robot_name=\"robot\", bool is_urdf_string=false, bool cast_shadows=true) Robot (const std::string & model_file, const std::string & robot_name=\"robot\", bool is_urdf_string=false, bool cast_shadows=true) Robot (dart::dynamics::SkeletonPtr skeleton, const std::string & robot_name=\"robot\", bool cast_shadows=true) Eigen::VectorXd acceleration_lower_limits (const std::vector< std::string > & dof_names={}) const Eigen::VectorXd acceleration_upper_limits (const std::vector< std::string > & dof_names={}) const Eigen::VectorXd accelerations (const std::vector< std::string > & dof_names={}) const std::vector< std::shared_ptr< control::RobotControl > > active_controllers () const std::string actuator_type (const std::string & joint_name) const std::vector< std::string > actuator_types (const std::vector< std::string > & joint_names={}) const void add_body_mass (const std::string & body_name, double mass) void add_body_mass (size_t body_index, double mass) void add_controller (const std::shared_ptr< control::RobotControl > & controller, double weight=1.0) void add_external_force (const std::string & body_name, const Eigen::Vector3d & force, const Eigen::Vector3d & offset=Eigen::Vector3d::Zero(), bool force_local=false, bool offset_local=true) void add_external_force (size_t body_index, const Eigen::Vector3d & force, const Eigen::Vector3d & offset=Eigen::Vector3d::Zero(), bool force_local=false, bool offset_local=true) void add_external_torque (const std::string & body_name, const Eigen::Vector3d & torque, bool local=false) void add_external_torque (size_t body_index, const Eigen::Vector3d & torque, bool local=false) bool adjacent_colliding () const Eigen::MatrixXd aug_mass_matrix (const std::vector< std::string > & dof_names={}) const Eigen::Isometry3d base_pose () const Eigen::Vector6d base_pose_vec () const Eigen::Vector6d body_acceleration (const std::string & body_name) const Eigen::Vector6d body_acceleration (size_t body_index) const size_t body_index (const std::string & body_name) const double body_mass (const std::string & body_name) const double body_mass (size_t body_index) const std::string body_name (size_t body_index) const std::vector< std::string > body_names () const dart::dynamics::BodyNode * body_node (const std::string & body_name) dart::dynamics::BodyNode * body_node (size_t body_index) Eigen::Isometry3d body_pose (const std::string & body_name) const Eigen::Isometry3d body_pose (size_t body_index) const Eigen::Vector6d body_pose_vec (const std::string & body_name) const Eigen::Vector6d body_pose_vec (size_t body_index) const Eigen::Vector6d body_velocity (const std::string & body_name) const Eigen::Vector6d body_velocity (size_t body_index) const bool cast_shadows () const void clear_controllers () void clear_external_forces () void clear_internal_forces () std::shared_ptr< Robot > clone () const std::shared_ptr< Robot > clone_ghost (const std::string & ghost_name=\"ghost\", const Eigen::Vector4d & ghost_color={0.3, 0.3, 0.3, 0.7}) const Eigen::Vector3d com () const Eigen::Vector6d com_acceleration () const Eigen::MatrixXd com_jacobian (const std::vector< std::string > & dof_names={}) const Eigen::MatrixXd com_jacobian_deriv (const std::vector< std::string > & dof_names={}) const Eigen::Vector6d com_velocity () const Eigen::VectorXd commands (const std::vector< std::string > & dof_names={}) const Eigen::VectorXd constraint_forces (const std::vector< std::string > & dof_names={}) const std::shared_ptr< control::RobotControl > controller (size_t index) const std::vector< std::shared_ptr< control::RobotControl > > controllers () const Eigen::VectorXd coriolis_forces (const std::vector< std::string > & dof_names={}) const Eigen::VectorXd coriolis_gravity_forces (const std::vector< std::string > & dof_names={}) const std::vector< double > coulomb_coeffs (const std::vector< std::string > & dof_names={}) const std::vector< double > damping_coeffs (const std::vector< std::string > & dof_names={}) const dart::dynamics::DegreeOfFreedom * dof (const std::string & dof_name) dart::dynamics::DegreeOfFreedom * dof (size_t dof_index) size_t dof_index (const std::string & dof_name) const const std::unordered_map< std::string, size_t > & dof_map () const std::string dof_name (size_t dof_index) const std::vector< std::string > dof_names (bool filter_mimics=false, bool filter_locked=false, bool filter_passive=false) const const std::vector< std::pair< dart::dynamics::BodyNode *, double > > & drawing_axes () const Eigen::Vector6d external_forces (const std::string & body_name) const Eigen::Vector6d external_forces (size_t body_index) const void fix_to_world () bool fixed () const Eigen::VectorXd force_lower_limits (const std::vector< std::string > & dof_names={}) const void force_position_bounds () std::pair< Eigen::Vector6d, Eigen::Vector6d > force_torque (size_t joint_index) const Eigen::VectorXd force_upper_limits (const std::vector< std::string > & dof_names={}) const Eigen::VectorXd forces (const std::vector< std::string > & dof_names={}) const bool free () const void free_from_world (const Eigen::Vector6d & pose=Eigen::Vector6d::Zero()) double friction_coeff (const std::string & body_name) double friction_coeff (size_t body_index) Eigen::Vector3d friction_dir (const std::string & body_name) Eigen::Vector3d friction_dir (size_t body_index) bool ghost () const Eigen::VectorXd gravity_forces (const std::vector< std::string > & dof_names={}) const Eigen::MatrixXd inv_aug_mass_matrix (const std::vector< std::string > & dof_names={}) const Eigen::MatrixXd inv_mass_matrix (const std::vector< std::string > & dof_names={}) const Eigen::MatrixXd jacobian (const std::string & body_name, const std::vector< std::string > & dof_names={}) const Eigen::MatrixXd jacobian_deriv (const std::string & body_name, const std::vector< std::string > & dof_names={}) const dart::dynamics::Joint * joint (const std::string & joint_name) dart::dynamics::Joint * joint (size_t joint_index) size_t joint_index (const std::string & joint_name) const const std::unordered_map< std::string, size_t > & joint_map () const std::string joint_name (size_t joint_index) const std::vector< std::string > joint_names () const std::vector< std::string > locked_dof_names () const Eigen::MatrixXd mass_matrix (const std::vector< std::string > & dof_names={}) const std::vector< std::string > mimic_dof_names () const const std::string & model_filename () const const std::vector< std::pair< std::string, std::string > > & model_packages () const const std::string & name () const size_t num_bodies () const size_t num_controllers () const size_t num_dofs () const size_t num_joints () const std::vector< std::string > passive_dof_names () const std::vector< bool > position_enforced (const std::vector< std::string > & dof_names={}) const Eigen::VectorXd position_lower_limits (const std::vector< std::string > & dof_names={}) const Eigen::VectorXd position_upper_limits (const std::vector< std::string > & dof_names={}) const Eigen::VectorXd positions (const std::vector< std::string > & dof_names={}) const void reinit_controllers () void remove_all_drawing_axis () void remove_controller (const std::shared_ptr< control::RobotControl > & controller) void remove_controller (size_t index) virtual void reset () void reset_commands () double restitution_coeff (const std::string & body_name) double restitution_coeff (size_t body_index) double secondary_friction_coeff (const std::string & body_name) double secondary_friction_coeff (size_t body_index) bool self_colliding () const void set_acceleration_lower_limits (const Eigen::VectorXd & accelerations, const std::vector< std::string > & dof_names={}) void set_acceleration_upper_limits (const Eigen::VectorXd & accelerations, const std::vector< std::string > & dof_names={}) void set_accelerations (const Eigen::VectorXd & accelerations, const std::vector< std::string > & dof_names={}) void set_actuator_type (const std::string & type, const std::string & joint_name, bool override_mimic=false, bool override_base=false) void set_actuator_types (const std::string & type, const std::vector< std::string > & joint_names={}, bool override_mimic=false, bool override_base=false) void set_base_pose (const Eigen::Isometry3d & tf) void set_base_pose (const Eigen::Vector6d & pose) set base pose: pose is a 6D vector (first 3D orientation in angle-axis and last 3D translation) void set_body_mass (const std::string & body_name, double mass) void set_body_mass (size_t body_index, double mass) void set_body_name (size_t body_index, const std::string & body_name) void set_cast_shadows (bool cast_shadows=true) void set_color_mode (const std::string & color_mode) void set_color_mode (const std::string & color_mode, const std::string & body_name) void set_commands (const Eigen::VectorXd & commands, const std::vector< std::string > & dof_names={}) void set_coulomb_coeffs (const std::vector< double > & cfrictions, const std::vector< std::string > & dof_names={}) void set_coulomb_coeffs (double cfriction, const std::vector< std::string > & dof_names={}) void set_damping_coeffs (const std::vector< double > & damps, const std::vector< std::string > & dof_names={}) void set_damping_coeffs (double damp, const std::vector< std::string > & dof_names={}) void set_draw_axis (const std::string & body_name, double size=0.25) void set_external_force (const std::string & body_name, const Eigen::Vector3d & force, const Eigen::Vector3d & offset=Eigen::Vector3d::Zero(), bool force_local=false, bool offset_local=true) void set_external_force (size_t body_index, const Eigen::Vector3d & force, const Eigen::Vector3d & offset=Eigen::Vector3d::Zero(), bool force_local=false, bool offset_local=true) void set_external_torque (const std::string & body_name, const Eigen::Vector3d & torque, bool local=false) void set_external_torque (size_t body_index, const Eigen::Vector3d & torque, bool local=false) void set_force_lower_limits (const Eigen::VectorXd & forces, const std::vector< std::string > & dof_names={}) void set_force_upper_limits (const Eigen::VectorXd & forces, const std::vector< std::string > & dof_names={}) void set_forces (const Eigen::VectorXd & forces, const std::vector< std::string > & dof_names={}) void set_friction_coeff (const std::string & body_name, double value) void set_friction_coeff (size_t body_index, double value) void set_friction_coeffs (double value) void set_friction_dir (const std::string & body_name, const Eigen::Vector3d & direction) void set_friction_dir (size_t body_index, const Eigen::Vector3d & direction) void set_ghost (bool ghost=true) void set_joint_name (size_t joint_index, const std::string & joint_name) void set_mimic (const std::string & joint_name, const std::string & mimic_joint_name, double multiplier=1., double offset=0.) void set_position_enforced (const std::vector< bool > & enforced, const std::vector< std::string > & dof_names={}) void set_position_enforced (bool enforced, const std::vector< std::string > & dof_names={}) void set_position_lower_limits (const Eigen::VectorXd & positions, const std::vector< std::string > & dof_names={}) void set_position_upper_limits (const Eigen::VectorXd & positions, const std::vector< std::string > & dof_names={}) void set_positions (const Eigen::VectorXd & positions, const std::vector< std::string > & dof_names={}) void set_restitution_coeff (const std::string & body_name, double value) void set_restitution_coeff (size_t body_index, double value) void set_restitution_coeffs (double value) void set_secondary_friction_coeff (const std::string & body_name, double value) void set_secondary_friction_coeff (size_t body_index, double value) void set_secondary_friction_coeffs (double value) void set_self_collision (bool enable_self_collisions=true, bool enable_adjacent_collisions=false) void set_spring_stiffnesses (const std::vector< double > & stiffnesses, const std::vector< std::string > & dof_names={}) void set_spring_stiffnesses (double stiffness, const std::vector< std::string > & dof_names={}) void set_velocities (const Eigen::VectorXd & velocities, const std::vector< std::string > & dof_names={}) void set_velocity_lower_limits (const Eigen::VectorXd & velocities, const std::vector< std::string > & dof_names={}) void set_velocity_upper_limits (const Eigen::VectorXd & velocities, const std::vector< std::string > & dof_names={}) dart::dynamics::SkeletonPtr skeleton () std::vector< double > spring_stiffnesses (const std::vector< std::string > & dof_names={}) const void update (double t) void update_joint_dof_maps () Eigen::VectorXd vec_dof (const Eigen::VectorXd & vec, const std::vector< std::string > & dof_names) const Eigen::VectorXd velocities (const std::vector< std::string > & dof_names={}) const Eigen::VectorXd velocity_lower_limits (const std::vector< std::string > & dof_names={}) const Eigen::VectorXd velocity_upper_limits (const std::vector< std::string > & dof_names={}) const virtual ~Robot ()"},{"location":"api/classrobot__dart_1_1robots_1_1Vx300/#public-static-functions-inherited-from-robot_dartrobot","title":"Public Static Functions inherited from robot_dart::Robot","text":"

See robot_dart::Robot

Type Name std::shared_ptr< Robot > create_box (const Eigen::Vector3d & dims, const Eigen::Isometry3d & tf, const std::string & type=\"free\", double mass=1.0, const Eigen::Vector4d & color=dart::Color::Red(1.0), const std::string & box_name=\"box\") std::shared_ptr< Robot > create_box (const Eigen::Vector3d & dims, const Eigen::Vector6d & pose=Eigen::Vector6d::Zero(), const std::string & type=\"free\", double mass=1.0, const Eigen::Vector4d & color=dart::Color::Red(1.0), const std::string & box_name=\"box\") std::shared_ptr< Robot > create_ellipsoid (const Eigen::Vector3d & dims, const Eigen::Isometry3d & tf, const std::string & type=\"free\", double mass=1.0, const Eigen::Vector4d & color=dart::Color::Red(1.0), const std::string & ellipsoid_name=\"ellipsoid\") std::shared_ptr< Robot > create_ellipsoid (const Eigen::Vector3d & dims, const Eigen::Vector6d & pose=Eigen::Vector6d::Zero(), const std::string & type=\"free\", double mass=1.0, const Eigen::Vector4d & color=dart::Color::Red(1.0), const std::string & ellipsoid_name=\"ellipsoid\")"},{"location":"api/classrobot__dart_1_1robots_1_1Vx300/#protected-attributes-inherited-from-robot_dartrobot","title":"Protected Attributes inherited from robot_dart::Robot","text":"

See robot_dart::Robot

Type Name std::vector< std::pair< dart::dynamics::BodyNode *, double > > _axis_shapes bool _cast_shadows std::vector< std::shared_ptr< control::RobotControl > > _controllers std::unordered_map< std::string, size_t > _dof_map bool _is_ghost std::unordered_map< std::string, size_t > _joint_map std::string _model_filename std::vector< std::pair< std::string, std::string > > _packages std::string _robot_name dart::dynamics::SkeletonPtr _skeleton"},{"location":"api/classrobot__dart_1_1robots_1_1Vx300/#protected-functions-inherited-from-robot_dartrobot","title":"Protected Functions inherited from robot_dart::Robot","text":"

See robot_dart::Robot

Type Name dart::dynamics::Joint::ActuatorType _actuator_type (size_t joint_index) const std::vector< dart::dynamics::Joint::ActuatorType > _actuator_types () const std::string _get_path (const std::string & filename) const Eigen::MatrixXd _jacobian (const Eigen::MatrixXd & full_jacobian, const std::vector< std::string > & dof_names) const dart::dynamics::SkeletonPtr _load_model (const std::string & filename, const std::vector< std::pair< std::string, std::string > > & packages=std::vector< std::pair< std::string, std::string > >(), bool is_urdf_string=false) Eigen::MatrixXd _mass_matrix (const Eigen::MatrixXd & full_mass_matrix, const std::vector< std::string > & dof_names) const virtual void _post_addition (RobotDARTSimu *) Function called by RobotDARTSimu object when adding the robot to the world. virtual void _post_removal (RobotDARTSimu *) Function called by RobotDARTSimu object when removing the robot to the world. void _set_actuator_type (size_t joint_index, dart::dynamics::Joint::ActuatorType type, bool override_mimic=false, bool override_base=false) void _set_actuator_types (const std::vector< dart::dynamics::Joint::ActuatorType > & types, bool override_mimic=false, bool override_base=false) void _set_actuator_types (dart::dynamics::Joint::ActuatorType type, bool override_mimic=false, bool override_base=false) void _set_color_mode (dart::dynamics::MeshShape::ColorMode color_mode, dart::dynamics::SkeletonPtr skel) void _set_color_mode (dart::dynamics::MeshShape::ColorMode color_mode, dart::dynamics::ShapeNode * sn)"},{"location":"api/classrobot__dart_1_1robots_1_1Vx300/#public-functions-documentation","title":"Public Functions Documentation","text":""},{"location":"api/classrobot__dart_1_1robots_1_1Vx300/#function-vx300","title":"function Vx300","text":"
inline robot_dart::robots::Vx300::Vx300 (\nconst std::string & urdf=\"vx300/vx300.urdf\",\nconst std::vector< std::pair< std::string, std::string > > & packages=('interbotix_xsarm_descriptions', 'vx300')\n) 

The documentation for this class was generated from the following file robot_dart/robots/vx300.hpp

"},{"location":"api/namespacerobot__dart_1_1sensor/","title":"Namespace robot_dart::sensor","text":"

Namespace List > robot_dart > sensor

"},{"location":"api/namespacerobot__dart_1_1sensor/#classes","title":"Classes","text":"Type Name class ForceTorque class IMU struct IMUConfig class Sensor class Torque

The documentation for this class was generated from the following file robot_dart/gui/magnum/sensor/camera.hpp

"},{"location":"api/classrobot__dart_1_1sensor_1_1ForceTorque/","title":"Class robot_dart::sensor::ForceTorque","text":"

ClassList > robot_dart > sensor > ForceTorque

Inherits the following classes: robot_dart::sensor::Sensor

"},{"location":"api/classrobot__dart_1_1sensor_1_1ForceTorque/#public-functions","title":"Public Functions","text":"Type Name ForceTorque (dart::dynamics::Joint * joint, size_t frequency=1000, const std::string & direction=\"child_to_parent\") ForceTorque (const std::shared_ptr< Robot > & robot, const std::string & joint_name, size_t frequency=1000, const std::string & direction=\"child_to_parent\") virtual void attach_to_body (dart::dynamics::BodyNode *, const Eigen::Isometry3d &) override virtual void calculate (double) override Eigen::Vector3d force () const virtual void init () override Eigen::Vector3d torque () const virtual std::string type () override const const Eigen::Vector6d & wrench () const"},{"location":"api/classrobot__dart_1_1sensor_1_1ForceTorque/#public-functions-inherited-from-robot_dartsensorsensor","title":"Public Functions inherited from robot_dart::sensor::Sensor","text":"

See robot_dart::sensor::Sensor

Type Name Sensor (size_t freq=40) void activate (bool enable=true) bool active () const virtual void attach_to_body (dart::dynamics::BodyNode * body, const Eigen::Isometry3d & tf=Eigen::Isometry3d::Identity()) void attach_to_body (const std::shared_ptr< Robot > & robot, const std::string & body_name, const Eigen::Isometry3d & tf=Eigen::Isometry3d::Identity()) virtual void attach_to_joint (dart::dynamics::Joint * joint, const Eigen::Isometry3d & tf=Eigen::Isometry3d::Identity()) void attach_to_joint (const std::shared_ptr< Robot > & robot, const std::string & joint_name, const Eigen::Isometry3d & tf=Eigen::Isometry3d::Identity()) const std::string & attached_to () const virtual void calculate (double) = 0 void detach () size_t frequency () const virtual void init () = 0 const Eigen::Isometry3d & pose () const void refresh (double t) void set_frequency (size_t freq) void set_pose (const Eigen::Isometry3d & tf) void set_simu (RobotDARTSimu * simu) const RobotDARTSimu * simu () const virtual std::string type () const = 0 virtual ~Sensor ()"},{"location":"api/classrobot__dart_1_1sensor_1_1ForceTorque/#protected-attributes","title":"Protected Attributes","text":"Type Name std::string _direction Eigen::Vector6d _wrench"},{"location":"api/classrobot__dart_1_1sensor_1_1ForceTorque/#protected-attributes-inherited-from-robot_dartsensorsensor","title":"Protected Attributes inherited from robot_dart::sensor::Sensor","text":"

See robot_dart::sensor::Sensor

Type Name bool _active Eigen::Isometry3d _attached_tf bool _attached_to_body = = false bool _attached_to_joint = = false bool _attaching_to_body = = false bool _attaching_to_joint = = false dart::dynamics::BodyNode * _body_attached size_t _frequency dart::dynamics::Joint * _joint_attached RobotDARTSimu * _simu = = nullptr Eigen::Isometry3d _world_pose"},{"location":"api/classrobot__dart_1_1sensor_1_1ForceTorque/#public-functions-documentation","title":"Public Functions Documentation","text":""},{"location":"api/classrobot__dart_1_1sensor_1_1ForceTorque/#function-forcetorque-12","title":"function ForceTorque [\u00bd]","text":"
robot_dart::sensor::ForceTorque::ForceTorque (\ndart::dynamics::Joint * joint,\nsize_t frequency=1000,\nconst std::string & direction=\"child_to_parent\"\n) 
"},{"location":"api/classrobot__dart_1_1sensor_1_1ForceTorque/#function-forcetorque-22","title":"function ForceTorque [2/2]","text":"
inline robot_dart::sensor::ForceTorque::ForceTorque (\nconst std::shared_ptr< Robot > & robot,\nconst std::string & joint_name,\nsize_t frequency=1000,\nconst std::string & direction=\"child_to_parent\"\n) 
"},{"location":"api/classrobot__dart_1_1sensor_1_1ForceTorque/#function-attach_to_body","title":"function attach_to_body","text":"
inline virtual void robot_dart::sensor::ForceTorque::attach_to_body (\ndart::dynamics::BodyNode *,\nconst Eigen::Isometry3d &\n) override\n

Implements robot_dart::sensor::Sensor::attach_to_body

"},{"location":"api/classrobot__dart_1_1sensor_1_1ForceTorque/#function-calculate","title":"function calculate","text":"
virtual void robot_dart::sensor::ForceTorque::calculate (\ndouble\n) override\n

Implements robot_dart::sensor::Sensor::calculate

"},{"location":"api/classrobot__dart_1_1sensor_1_1ForceTorque/#function-force","title":"function force","text":"
Eigen::Vector3d robot_dart::sensor::ForceTorque::force () const\n
"},{"location":"api/classrobot__dart_1_1sensor_1_1ForceTorque/#function-init","title":"function init","text":"
virtual void robot_dart::sensor::ForceTorque::init () override\n

Implements robot_dart::sensor::Sensor::init

"},{"location":"api/classrobot__dart_1_1sensor_1_1ForceTorque/#function-torque","title":"function torque","text":"
Eigen::Vector3d robot_dart::sensor::ForceTorque::torque () const\n
"},{"location":"api/classrobot__dart_1_1sensor_1_1ForceTorque/#function-type","title":"function type","text":"
virtual std::string robot_dart::sensor::ForceTorque::type () override const\n

Implements robot_dart::sensor::Sensor::type

"},{"location":"api/classrobot__dart_1_1sensor_1_1ForceTorque/#function-wrench","title":"function wrench","text":"
const Eigen::Vector6d & robot_dart::sensor::ForceTorque::wrench () const\n
"},{"location":"api/classrobot__dart_1_1sensor_1_1ForceTorque/#protected-attributes-documentation","title":"Protected Attributes Documentation","text":""},{"location":"api/classrobot__dart_1_1sensor_1_1ForceTorque/#variable-_direction","title":"variable _direction","text":"
std::string robot_dart::sensor::ForceTorque::_direction;\n
"},{"location":"api/classrobot__dart_1_1sensor_1_1ForceTorque/#variable-_wrench","title":"variable _wrench","text":"
Eigen::Vector6d robot_dart::sensor::ForceTorque::_wrench;\n

The documentation for this class was generated from the following file robot_dart/sensor/force_torque.hpp

"},{"location":"api/classrobot__dart_1_1sensor_1_1IMU/","title":"Class robot_dart::sensor::IMU","text":"

ClassList > robot_dart > sensor > IMU

Inherits the following classes: robot_dart::sensor::Sensor

"},{"location":"api/classrobot__dart_1_1sensor_1_1IMU/#public-functions","title":"Public Functions","text":"Type Name IMU (const IMUConfig & config) const Eigen::AngleAxisd & angular_position () const Eigen::Vector3d angular_position_vec () const const Eigen::Vector3d & angular_velocity () const virtual void attach_to_joint (dart::dynamics::Joint *, const Eigen::Isometry3d &) override virtual void calculate (double) override virtual void init () override const Eigen::Vector3d & linear_acceleration () const virtual std::string type () override const"},{"location":"api/classrobot__dart_1_1sensor_1_1IMU/#public-functions-inherited-from-robot_dartsensorsensor","title":"Public Functions inherited from robot_dart::sensor::Sensor","text":"

See robot_dart::sensor::Sensor

Type Name Sensor (size_t freq=40) void activate (bool enable=true) bool active () const virtual void attach_to_body (dart::dynamics::BodyNode * body, const Eigen::Isometry3d & tf=Eigen::Isometry3d::Identity()) void attach_to_body (const std::shared_ptr< Robot > & robot, const std::string & body_name, const Eigen::Isometry3d & tf=Eigen::Isometry3d::Identity()) virtual void attach_to_joint (dart::dynamics::Joint * joint, const Eigen::Isometry3d & tf=Eigen::Isometry3d::Identity()) void attach_to_joint (const std::shared_ptr< Robot > & robot, const std::string & joint_name, const Eigen::Isometry3d & tf=Eigen::Isometry3d::Identity()) const std::string & attached_to () const virtual void calculate (double) = 0 void detach () size_t frequency () const virtual void init () = 0 const Eigen::Isometry3d & pose () const void refresh (double t) void set_frequency (size_t freq) void set_pose (const Eigen::Isometry3d & tf) void set_simu (RobotDARTSimu * simu) const RobotDARTSimu * simu () const virtual std::string type () const = 0 virtual ~Sensor ()"},{"location":"api/classrobot__dart_1_1sensor_1_1IMU/#protected-attributes","title":"Protected Attributes","text":"Type Name Eigen::AngleAxisd _angular_pos Eigen::Vector3d _angular_vel IMUConfig _config Eigen::Vector3d _linear_accel"},{"location":"api/classrobot__dart_1_1sensor_1_1IMU/#protected-attributes-inherited-from-robot_dartsensorsensor","title":"Protected Attributes inherited from robot_dart::sensor::Sensor","text":"

See robot_dart::sensor::Sensor

Type Name bool _active Eigen::Isometry3d _attached_tf bool _attached_to_body = = false bool _attached_to_joint = = false bool _attaching_to_body = = false bool _attaching_to_joint = = false dart::dynamics::BodyNode * _body_attached size_t _frequency dart::dynamics::Joint * _joint_attached RobotDARTSimu * _simu = = nullptr Eigen::Isometry3d _world_pose"},{"location":"api/classrobot__dart_1_1sensor_1_1IMU/#public-functions-documentation","title":"Public Functions Documentation","text":""},{"location":"api/classrobot__dart_1_1sensor_1_1IMU/#function-imu","title":"function IMU","text":"
robot_dart::sensor::IMU::IMU (\nconst IMUConfig & config\n) 
"},{"location":"api/classrobot__dart_1_1sensor_1_1IMU/#function-angular_position","title":"function angular_position","text":"
const Eigen::AngleAxisd & robot_dart::sensor::IMU::angular_position () const\n
"},{"location":"api/classrobot__dart_1_1sensor_1_1IMU/#function-angular_position_vec","title":"function angular_position_vec","text":"
Eigen::Vector3d robot_dart::sensor::IMU::angular_position_vec () const\n
"},{"location":"api/classrobot__dart_1_1sensor_1_1IMU/#function-angular_velocity","title":"function angular_velocity","text":"
const Eigen::Vector3d & robot_dart::sensor::IMU::angular_velocity () const\n
"},{"location":"api/classrobot__dart_1_1sensor_1_1IMU/#function-attach_to_joint","title":"function attach_to_joint","text":"
inline virtual void robot_dart::sensor::IMU::attach_to_joint (\ndart::dynamics::Joint *,\nconst Eigen::Isometry3d &\n) override\n

Implements robot_dart::sensor::Sensor::attach_to_joint

"},{"location":"api/classrobot__dart_1_1sensor_1_1IMU/#function-calculate","title":"function calculate","text":"
virtual void robot_dart::sensor::IMU::calculate (\ndouble\n) override\n

Implements robot_dart::sensor::Sensor::calculate

"},{"location":"api/classrobot__dart_1_1sensor_1_1IMU/#function-init","title":"function init","text":"
virtual void robot_dart::sensor::IMU::init () override\n

Implements robot_dart::sensor::Sensor::init

"},{"location":"api/classrobot__dart_1_1sensor_1_1IMU/#function-linear_acceleration","title":"function linear_acceleration","text":"
const Eigen::Vector3d & robot_dart::sensor::IMU::linear_acceleration () const\n
"},{"location":"api/classrobot__dart_1_1sensor_1_1IMU/#function-type","title":"function type","text":"
virtual std::string robot_dart::sensor::IMU::type () override const\n

Implements robot_dart::sensor::Sensor::type

"},{"location":"api/classrobot__dart_1_1sensor_1_1IMU/#protected-attributes-documentation","title":"Protected Attributes Documentation","text":""},{"location":"api/classrobot__dart_1_1sensor_1_1IMU/#variable-_angular_pos","title":"variable _angular_pos","text":"
Eigen::AngleAxisd robot_dart::sensor::IMU::_angular_pos;\n
"},{"location":"api/classrobot__dart_1_1sensor_1_1IMU/#variable-_angular_vel","title":"variable _angular_vel","text":"
Eigen::Vector3d robot_dart::sensor::IMU::_angular_vel;\n
"},{"location":"api/classrobot__dart_1_1sensor_1_1IMU/#variable-_config","title":"variable _config","text":"
IMUConfig robot_dart::sensor::IMU::_config;\n
"},{"location":"api/classrobot__dart_1_1sensor_1_1IMU/#variable-_linear_accel","title":"variable _linear_accel","text":"
Eigen::Vector3d robot_dart::sensor::IMU::_linear_accel;\n

The documentation for this class was generated from the following file robot_dart/sensor/imu.hpp

"},{"location":"api/structrobot__dart_1_1sensor_1_1IMUConfig/","title":"Struct robot_dart::sensor::IMUConfig","text":"

ClassList > robot_dart > sensor > IMUConfig

"},{"location":"api/structrobot__dart_1_1sensor_1_1IMUConfig/#public-attributes","title":"Public Attributes","text":"Type Name Eigen::Vector3d accel_bias = = Eigen::Vector3d::Zero() dart::dynamics::BodyNode * body = = nullptr size_t frequency = = 200 Eigen::Vector3d gyro_bias = = Eigen::Vector3d::Zero()"},{"location":"api/structrobot__dart_1_1sensor_1_1IMUConfig/#public-functions","title":"Public Functions","text":"Type Name IMUConfig (dart::dynamics::BodyNode * b, size_t f) IMUConfig (const Eigen::Vector3d & gyro_bias, const Eigen::Vector3d & accel_bias, dart::dynamics::BodyNode * b, size_t f) IMUConfig ()"},{"location":"api/structrobot__dart_1_1sensor_1_1IMUConfig/#public-attributes-documentation","title":"Public Attributes Documentation","text":""},{"location":"api/structrobot__dart_1_1sensor_1_1IMUConfig/#variable-accel_bias","title":"variable accel_bias","text":"
Eigen::Vector3d robot_dart::sensor::IMUConfig::accel_bias;\n
"},{"location":"api/structrobot__dart_1_1sensor_1_1IMUConfig/#variable-body","title":"variable body","text":"
dart::dynamics::BodyNode* robot_dart::sensor::IMUConfig::body;\n
"},{"location":"api/structrobot__dart_1_1sensor_1_1IMUConfig/#variable-frequency","title":"variable frequency","text":"
size_t robot_dart::sensor::IMUConfig::frequency;\n
"},{"location":"api/structrobot__dart_1_1sensor_1_1IMUConfig/#variable-gyro_bias","title":"variable gyro_bias","text":"
Eigen::Vector3d robot_dart::sensor::IMUConfig::gyro_bias;\n
"},{"location":"api/structrobot__dart_1_1sensor_1_1IMUConfig/#public-functions-documentation","title":"Public Functions Documentation","text":""},{"location":"api/structrobot__dart_1_1sensor_1_1IMUConfig/#function-imuconfig-13","title":"function IMUConfig [\u2153]","text":"
inline robot_dart::sensor::IMUConfig::IMUConfig (\ndart::dynamics::BodyNode * b,\nsize_t f\n) 
"},{"location":"api/structrobot__dart_1_1sensor_1_1IMUConfig/#function-imuconfig-23","title":"function IMUConfig [\u2154]","text":"
inline robot_dart::sensor::IMUConfig::IMUConfig (\nconst Eigen::Vector3d & gyro_bias,\nconst Eigen::Vector3d & accel_bias,\ndart::dynamics::BodyNode * b,\nsize_t f\n) 
"},{"location":"api/structrobot__dart_1_1sensor_1_1IMUConfig/#function-imuconfig-33","title":"function IMUConfig [3/3]","text":"
inline robot_dart::sensor::IMUConfig::IMUConfig () 

The documentation for this class was generated from the following file robot_dart/sensor/imu.hpp

"},{"location":"api/classrobot__dart_1_1sensor_1_1Sensor/","title":"Class robot_dart::sensor::Sensor","text":"

ClassList > robot_dart > sensor > Sensor

Inherited by the following classes: robot_dart::gui::magnum::sensor::Camera, robot_dart::sensor::ForceTorque, robot_dart::sensor::IMU, robot_dart::sensor::Torque

"},{"location":"api/classrobot__dart_1_1sensor_1_1Sensor/#public-functions","title":"Public Functions","text":"Type Name Sensor (size_t freq=40) void activate (bool enable=true) bool active () const virtual void attach_to_body (dart::dynamics::BodyNode * body, const Eigen::Isometry3d & tf=Eigen::Isometry3d::Identity()) void attach_to_body (const std::shared_ptr< Robot > & robot, const std::string & body_name, const Eigen::Isometry3d & tf=Eigen::Isometry3d::Identity()) virtual void attach_to_joint (dart::dynamics::Joint * joint, const Eigen::Isometry3d & tf=Eigen::Isometry3d::Identity()) void attach_to_joint (const std::shared_ptr< Robot > & robot, const std::string & joint_name, const Eigen::Isometry3d & tf=Eigen::Isometry3d::Identity()) const std::string & attached_to () const virtual void calculate (double) = 0 void detach () size_t frequency () const virtual void init () = 0 const Eigen::Isometry3d & pose () const void refresh (double t) void set_frequency (size_t freq) void set_pose (const Eigen::Isometry3d & tf) void set_simu (RobotDARTSimu * simu) const RobotDARTSimu * simu () const virtual std::string type () const = 0 virtual ~Sensor ()"},{"location":"api/classrobot__dart_1_1sensor_1_1Sensor/#protected-attributes","title":"Protected Attributes","text":"Type Name bool _active Eigen::Isometry3d _attached_tf bool _attached_to_body = = false bool _attached_to_joint = = false bool _attaching_to_body = = false bool _attaching_to_joint = = false dart::dynamics::BodyNode * _body_attached size_t _frequency dart::dynamics::Joint * _joint_attached RobotDARTSimu * _simu = = nullptr Eigen::Isometry3d _world_pose"},{"location":"api/classrobot__dart_1_1sensor_1_1Sensor/#public-functions-documentation","title":"Public Functions Documentation","text":""},{"location":"api/classrobot__dart_1_1sensor_1_1Sensor/#function-sensor","title":"function Sensor","text":"
robot_dart::sensor::Sensor::Sensor (\nsize_t freq=40\n) 
"},{"location":"api/classrobot__dart_1_1sensor_1_1Sensor/#function-activate","title":"function activate","text":"
void robot_dart::sensor::Sensor::activate (\nbool enable=true\n) 
"},{"location":"api/classrobot__dart_1_1sensor_1_1Sensor/#function-active","title":"function active","text":"
bool robot_dart::sensor::Sensor::active () const\n
"},{"location":"api/classrobot__dart_1_1sensor_1_1Sensor/#function-attach_to_body-12","title":"function attach_to_body [\u00bd]","text":"
virtual void robot_dart::sensor::Sensor::attach_to_body (\ndart::dynamics::BodyNode * body,\nconst Eigen::Isometry3d & tf=Eigen::Isometry3d::Identity()\n) 
"},{"location":"api/classrobot__dart_1_1sensor_1_1Sensor/#function-attach_to_body-22","title":"function attach_to_body [2/2]","text":"
inline void robot_dart::sensor::Sensor::attach_to_body (\nconst std::shared_ptr< Robot > & robot,\nconst std::string & body_name,\nconst Eigen::Isometry3d & tf=Eigen::Isometry3d::Identity()\n) 
"},{"location":"api/classrobot__dart_1_1sensor_1_1Sensor/#function-attach_to_joint-12","title":"function attach_to_joint [\u00bd]","text":"
virtual void robot_dart::sensor::Sensor::attach_to_joint (\ndart::dynamics::Joint * joint,\nconst Eigen::Isometry3d & tf=Eigen::Isometry3d::Identity()\n) 
"},{"location":"api/classrobot__dart_1_1sensor_1_1Sensor/#function-attach_to_joint-22","title":"function attach_to_joint [2/2]","text":"
inline void robot_dart::sensor::Sensor::attach_to_joint (\nconst std::shared_ptr< Robot > & robot,\nconst std::string & joint_name,\nconst Eigen::Isometry3d & tf=Eigen::Isometry3d::Identity()\n) 
"},{"location":"api/classrobot__dart_1_1sensor_1_1Sensor/#function-attached_to","title":"function attached_to","text":"
const std::string & robot_dart::sensor::Sensor::attached_to () const\n
"},{"location":"api/classrobot__dart_1_1sensor_1_1Sensor/#function-calculate","title":"function calculate","text":"
virtual void robot_dart::sensor::Sensor::calculate (\ndouble\n) = 0\n
"},{"location":"api/classrobot__dart_1_1sensor_1_1Sensor/#function-detach","title":"function detach","text":"
void robot_dart::sensor::Sensor::detach () 
"},{"location":"api/classrobot__dart_1_1sensor_1_1Sensor/#function-frequency","title":"function frequency","text":"
size_t robot_dart::sensor::Sensor::frequency () const\n
"},{"location":"api/classrobot__dart_1_1sensor_1_1Sensor/#function-init","title":"function init","text":"
virtual void robot_dart::sensor::Sensor::init () = 0\n
"},{"location":"api/classrobot__dart_1_1sensor_1_1Sensor/#function-pose","title":"function pose","text":"
const Eigen::Isometry3d & robot_dart::sensor::Sensor::pose () const\n
"},{"location":"api/classrobot__dart_1_1sensor_1_1Sensor/#function-refresh","title":"function refresh","text":"
void robot_dart::sensor::Sensor::refresh (\ndouble t\n) 
"},{"location":"api/classrobot__dart_1_1sensor_1_1Sensor/#function-set_frequency","title":"function set_frequency","text":"
void robot_dart::sensor::Sensor::set_frequency (\nsize_t freq\n) 
"},{"location":"api/classrobot__dart_1_1sensor_1_1Sensor/#function-set_pose","title":"function set_pose","text":"
void robot_dart::sensor::Sensor::set_pose (\nconst Eigen::Isometry3d & tf\n) 
"},{"location":"api/classrobot__dart_1_1sensor_1_1Sensor/#function-set_simu","title":"function set_simu","text":"
void robot_dart::sensor::Sensor::set_simu (\nRobotDARTSimu * simu\n) 
"},{"location":"api/classrobot__dart_1_1sensor_1_1Sensor/#function-simu","title":"function simu","text":"
const RobotDARTSimu * robot_dart::sensor::Sensor::simu () const\n
"},{"location":"api/classrobot__dart_1_1sensor_1_1Sensor/#function-type","title":"function type","text":"
virtual std::string robot_dart::sensor::Sensor::type () const = 0\n
"},{"location":"api/classrobot__dart_1_1sensor_1_1Sensor/#function-sensor_1","title":"function ~Sensor","text":"
inline virtual robot_dart::sensor::Sensor::~Sensor () 
"},{"location":"api/classrobot__dart_1_1sensor_1_1Sensor/#protected-attributes-documentation","title":"Protected Attributes Documentation","text":""},{"location":"api/classrobot__dart_1_1sensor_1_1Sensor/#variable-_active","title":"variable _active","text":"
bool robot_dart::sensor::Sensor::_active;\n
"},{"location":"api/classrobot__dart_1_1sensor_1_1Sensor/#variable-_attached_tf","title":"variable _attached_tf","text":"
Eigen::Isometry3d robot_dart::sensor::Sensor::_attached_tf;\n
"},{"location":"api/classrobot__dart_1_1sensor_1_1Sensor/#variable-_attached_to_body","title":"variable _attached_to_body","text":"
bool robot_dart::sensor::Sensor::_attached_to_body;\n
"},{"location":"api/classrobot__dart_1_1sensor_1_1Sensor/#variable-_attached_to_joint","title":"variable _attached_to_joint","text":"
bool robot_dart::sensor::Sensor::_attached_to_joint;\n
"},{"location":"api/classrobot__dart_1_1sensor_1_1Sensor/#variable-_attaching_to_body","title":"variable _attaching_to_body","text":"
bool robot_dart::sensor::Sensor::_attaching_to_body;\n
"},{"location":"api/classrobot__dart_1_1sensor_1_1Sensor/#variable-_attaching_to_joint","title":"variable _attaching_to_joint","text":"
bool robot_dart::sensor::Sensor::_attaching_to_joint;\n
"},{"location":"api/classrobot__dart_1_1sensor_1_1Sensor/#variable-_body_attached","title":"variable _body_attached","text":"
dart::dynamics::BodyNode* robot_dart::sensor::Sensor::_body_attached;\n
"},{"location":"api/classrobot__dart_1_1sensor_1_1Sensor/#variable-_frequency","title":"variable _frequency","text":"
size_t robot_dart::sensor::Sensor::_frequency;\n
"},{"location":"api/classrobot__dart_1_1sensor_1_1Sensor/#variable-_joint_attached","title":"variable _joint_attached","text":"
dart::dynamics::Joint* robot_dart::sensor::Sensor::_joint_attached;\n
"},{"location":"api/classrobot__dart_1_1sensor_1_1Sensor/#variable-_simu","title":"variable _simu","text":"
RobotDARTSimu* robot_dart::sensor::Sensor::_simu;\n
"},{"location":"api/classrobot__dart_1_1sensor_1_1Sensor/#variable-_world_pose","title":"variable _world_pose","text":"
Eigen::Isometry3d robot_dart::sensor::Sensor::_world_pose;\n

The documentation for this class was generated from the following file robot_dart/sensor/sensor.hpp

"},{"location":"api/classrobot__dart_1_1sensor_1_1Torque/","title":"Class robot_dart::sensor::Torque","text":"

ClassList > robot_dart > sensor > Torque

Inherits the following classes: robot_dart::sensor::Sensor

"},{"location":"api/classrobot__dart_1_1sensor_1_1Torque/#public-functions","title":"Public Functions","text":"Type Name Torque (dart::dynamics::Joint * joint, size_t frequency=1000) Torque (const std::shared_ptr< Robot > & robot, const std::string & joint_name, size_t frequency=1000) virtual void attach_to_body (dart::dynamics::BodyNode *, const Eigen::Isometry3d &) override virtual void calculate (double) override virtual void init () override const Eigen::VectorXd & torques () const virtual std::string type () override const"},{"location":"api/classrobot__dart_1_1sensor_1_1Torque/#public-functions-inherited-from-robot_dartsensorsensor","title":"Public Functions inherited from robot_dart::sensor::Sensor","text":"

See robot_dart::sensor::Sensor

Type Name Sensor (size_t freq=40) void activate (bool enable=true) bool active () const virtual void attach_to_body (dart::dynamics::BodyNode * body, const Eigen::Isometry3d & tf=Eigen::Isometry3d::Identity()) void attach_to_body (const std::shared_ptr< Robot > & robot, const std::string & body_name, const Eigen::Isometry3d & tf=Eigen::Isometry3d::Identity()) virtual void attach_to_joint (dart::dynamics::Joint * joint, const Eigen::Isometry3d & tf=Eigen::Isometry3d::Identity()) void attach_to_joint (const std::shared_ptr< Robot > & robot, const std::string & joint_name, const Eigen::Isometry3d & tf=Eigen::Isometry3d::Identity()) const std::string & attached_to () const virtual void calculate (double) = 0 void detach () size_t frequency () const virtual void init () = 0 const Eigen::Isometry3d & pose () const void refresh (double t) void set_frequency (size_t freq) void set_pose (const Eigen::Isometry3d & tf) void set_simu (RobotDARTSimu * simu) const RobotDARTSimu * simu () const virtual std::string type () const = 0 virtual ~Sensor ()"},{"location":"api/classrobot__dart_1_1sensor_1_1Torque/#protected-attributes","title":"Protected Attributes","text":"Type Name Eigen::VectorXd _torques"},{"location":"api/classrobot__dart_1_1sensor_1_1Torque/#protected-attributes-inherited-from-robot_dartsensorsensor","title":"Protected Attributes inherited from robot_dart::sensor::Sensor","text":"

See robot_dart::sensor::Sensor

Type Name bool _active Eigen::Isometry3d _attached_tf bool _attached_to_body = = false bool _attached_to_joint = = false bool _attaching_to_body = = false bool _attaching_to_joint = = false dart::dynamics::BodyNode * _body_attached size_t _frequency dart::dynamics::Joint * _joint_attached RobotDARTSimu * _simu = = nullptr Eigen::Isometry3d _world_pose"},{"location":"api/classrobot__dart_1_1sensor_1_1Torque/#public-functions-documentation","title":"Public Functions Documentation","text":""},{"location":"api/classrobot__dart_1_1sensor_1_1Torque/#function-torque-12","title":"function Torque [\u00bd]","text":"
robot_dart::sensor::Torque::Torque (\ndart::dynamics::Joint * joint,\nsize_t frequency=1000\n) 
"},{"location":"api/classrobot__dart_1_1sensor_1_1Torque/#function-torque-22","title":"function Torque [2/2]","text":"
inline robot_dart::sensor::Torque::Torque (\nconst std::shared_ptr< Robot > & robot,\nconst std::string & joint_name,\nsize_t frequency=1000\n) 
"},{"location":"api/classrobot__dart_1_1sensor_1_1Torque/#function-attach_to_body","title":"function attach_to_body","text":"
inline virtual void robot_dart::sensor::Torque::attach_to_body (\ndart::dynamics::BodyNode *,\nconst Eigen::Isometry3d &\n) override\n

Implements robot_dart::sensor::Sensor::attach_to_body

"},{"location":"api/classrobot__dart_1_1sensor_1_1Torque/#function-calculate","title":"function calculate","text":"
virtual void robot_dart::sensor::Torque::calculate (\ndouble\n) override\n

Implements robot_dart::sensor::Sensor::calculate

"},{"location":"api/classrobot__dart_1_1sensor_1_1Torque/#function-init","title":"function init","text":"
virtual void robot_dart::sensor::Torque::init () override\n

Implements robot_dart::sensor::Sensor::init

"},{"location":"api/classrobot__dart_1_1sensor_1_1Torque/#function-torques","title":"function torques","text":"
const Eigen::VectorXd & robot_dart::sensor::Torque::torques () const\n
"},{"location":"api/classrobot__dart_1_1sensor_1_1Torque/#function-type","title":"function type","text":"
virtual std::string robot_dart::sensor::Torque::type () override const\n

Implements robot_dart::sensor::Sensor::type

"},{"location":"api/classrobot__dart_1_1sensor_1_1Torque/#protected-attributes-documentation","title":"Protected Attributes Documentation","text":""},{"location":"api/classrobot__dart_1_1sensor_1_1Torque/#variable-_torques","title":"variable _torques","text":"
Eigen::VectorXd robot_dart::sensor::Torque::_torques;\n

The documentation for this class was generated from the following file robot_dart/sensor/torque.hpp

"},{"location":"api/namespacerobot__dart_1_1simu/","title":"Namespace robot_dart::simu","text":"

Namespace List > robot_dart > simu

"},{"location":"api/namespacerobot__dart_1_1simu/#classes","title":"Classes","text":"Type Name struct GUIData struct TextData

The documentation for this class was generated from the following file robot_dart/gui_data.hpp

"},{"location":"api/structrobot__dart_1_1simu_1_1GUIData/","title":"Struct robot_dart::simu::GUIData","text":"

ClassList > robot_dart > simu > GUIData

"},{"location":"api/structrobot__dart_1_1simu_1_1GUIData/#public-functions","title":"Public Functions","text":"Type Name std::shared_ptr< simu::TextData > add_text (const std::string & text, const Eigen::Affine2d & tf=Eigen::Affine2d::Identity(), Eigen::Vector4d color=Eigen::Vector4d(1, 1, 1, 1), std::uint8_t alignment=(1|3<< 3), bool draw_bg=false, Eigen::Vector4d bg_color=Eigen::Vector4d(0, 0, 0, 0.75), double font_size=28) bool cast_shadows (dart::dynamics::ShapeNode * shape) const std::vector< std::pair< dart::dynamics::BodyNode *, double > > drawing_axes () const const std::vector< std::shared_ptr< simu::TextData > > & drawing_texts () const bool ghost (dart::dynamics::ShapeNode * shape) const void remove_robot (const std::shared_ptr< Robot > & robot) void remove_text (const std::shared_ptr< simu::TextData > & data) void remove_text (size_t index) void update_robot (const std::shared_ptr< Robot > & robot)"},{"location":"api/structrobot__dart_1_1simu_1_1GUIData/#public-functions-documentation","title":"Public Functions Documentation","text":""},{"location":"api/structrobot__dart_1_1simu_1_1GUIData/#function-add_text","title":"function add_text","text":"
inline std::shared_ptr< simu::TextData > robot_dart::simu::GUIData::add_text (\nconst std::string & text,\nconst Eigen::Affine2d & tf=Eigen::Affine2d::Identity(),\nEigen::Vector4d color=Eigen::Vector4d(1, 1, 1, 1),\nstd::uint8_t alignment=(1|3<< 3),\nbool draw_bg=false,\nEigen::Vector4d bg_color=Eigen::Vector4d(0, 0, 0, 0.75),\ndouble font_size=28\n) 
"},{"location":"api/structrobot__dart_1_1simu_1_1GUIData/#function-cast_shadows","title":"function cast_shadows","text":"
inline bool robot_dart::simu::GUIData::cast_shadows (\ndart::dynamics::ShapeNode * shape\n) const\n
"},{"location":"api/structrobot__dart_1_1simu_1_1GUIData/#function-drawing_axes","title":"function drawing_axes","text":"
inline std::vector< std::pair< dart::dynamics::BodyNode *, double > > robot_dart::simu::GUIData::drawing_axes () const\n
"},{"location":"api/structrobot__dart_1_1simu_1_1GUIData/#function-drawing_texts","title":"function drawing_texts","text":"
inline const std::vector< std::shared_ptr< simu::TextData > > & robot_dart::simu::GUIData::drawing_texts () const\n
"},{"location":"api/structrobot__dart_1_1simu_1_1GUIData/#function-ghost","title":"function ghost","text":"
inline bool robot_dart::simu::GUIData::ghost (\ndart::dynamics::ShapeNode * shape\n) const\n
"},{"location":"api/structrobot__dart_1_1simu_1_1GUIData/#function-remove_robot","title":"function remove_robot","text":"
inline void robot_dart::simu::GUIData::remove_robot (\nconst std::shared_ptr< Robot > & robot\n) 
"},{"location":"api/structrobot__dart_1_1simu_1_1GUIData/#function-remove_text-12","title":"function remove_text [\u00bd]","text":"
inline void robot_dart::simu::GUIData::remove_text (\nconst std::shared_ptr< simu::TextData > & data\n) 
"},{"location":"api/structrobot__dart_1_1simu_1_1GUIData/#function-remove_text-22","title":"function remove_text [2/2]","text":"
inline void robot_dart::simu::GUIData::remove_text (\nsize_t index\n) 
"},{"location":"api/structrobot__dart_1_1simu_1_1GUIData/#function-update_robot","title":"function update_robot","text":"
inline void robot_dart::simu::GUIData::update_robot (\nconst std::shared_ptr< Robot > & robot\n) 

The documentation for this class was generated from the following file robot_dart/gui_data.hpp

"},{"location":"api/structrobot__dart_1_1simu_1_1TextData/","title":"Struct robot_dart::simu::TextData","text":"

ClassList > robot_dart > simu > TextData

"},{"location":"api/structrobot__dart_1_1simu_1_1TextData/#public-attributes","title":"Public Attributes","text":"Type Name std::uint8_t alignment Eigen::Vector4d background_color Eigen::Vector4d color bool draw_background double font_size = = 28. std::string text Eigen::Affine2d transformation"},{"location":"api/structrobot__dart_1_1simu_1_1TextData/#public-attributes-documentation","title":"Public Attributes Documentation","text":""},{"location":"api/structrobot__dart_1_1simu_1_1TextData/#variable-alignment","title":"variable alignment","text":"
std::uint8_t robot_dart::simu::TextData::alignment;\n
"},{"location":"api/structrobot__dart_1_1simu_1_1TextData/#variable-background_color","title":"variable background_color","text":"
Eigen::Vector4d robot_dart::simu::TextData::background_color;\n
"},{"location":"api/structrobot__dart_1_1simu_1_1TextData/#variable-color","title":"variable color","text":"
Eigen::Vector4d robot_dart::simu::TextData::color;\n
"},{"location":"api/structrobot__dart_1_1simu_1_1TextData/#variable-draw_background","title":"variable draw_background","text":"
bool robot_dart::simu::TextData::draw_background;\n
"},{"location":"api/structrobot__dart_1_1simu_1_1TextData/#variable-font_size","title":"variable font_size","text":"
double robot_dart::simu::TextData::font_size;\n
"},{"location":"api/structrobot__dart_1_1simu_1_1TextData/#variable-text","title":"variable text","text":"
std::string robot_dart::simu::TextData::text;\n
"},{"location":"api/structrobot__dart_1_1simu_1_1TextData/#variable-transformation","title":"variable transformation","text":"
Eigen::Affine2d robot_dart::simu::TextData::transformation;\n

The documentation for this class was generated from the following file robot_dart/robot_dart_simu.hpp

"},{"location":"api/namespacerobot__dart_1_1gui_1_1magnum_1_1gs_1_1_0d21/","title":"Namespace robot_dart::gui::magnum::@21","text":"

Namespace List > @21

"},{"location":"api/namespacerobot__dart_1_1gui_1_1magnum_1_1gs_1_1_0d21/#public-types","title":"Public Types","text":"Type Name enum Magnum::Int @0"},{"location":"api/namespacerobot__dart_1_1gui_1_1magnum_1_1gs_1_1_0d21/#public-types-documentation","title":"Public Types Documentation","text":""},{"location":"api/namespacerobot__dart_1_1gui_1_1magnum_1_1gs_1_1_0d21/#enum-0","title":"enum @0","text":"
enum @21::@0;\n

The documentation for this class was generated from the following file robot_dart/gui/magnum/gs/create_compatibility_shader.hpp

"},{"location":"api/structrobot__dart_1_1simu_1_1GUIData_1_1RobotData/","title":"Struct robot_dart::simu::GUIData::RobotData","text":"

ClassList > RobotData

"},{"location":"api/structrobot__dart_1_1simu_1_1GUIData_1_1RobotData/#public-attributes","title":"Public Attributes","text":"Type Name bool casting_shadows bool is_ghost"},{"location":"api/structrobot__dart_1_1simu_1_1GUIData_1_1RobotData/#public-attributes-documentation","title":"Public Attributes Documentation","text":""},{"location":"api/structrobot__dart_1_1simu_1_1GUIData_1_1RobotData/#variable-casting_shadows","title":"variable casting_shadows","text":"
bool robot_dart::simu::GUIData::RobotData::casting_shadows;\n
"},{"location":"api/structrobot__dart_1_1simu_1_1GUIData_1_1RobotData/#variable-is_ghost","title":"variable is_ghost","text":"
bool robot_dart::simu::GUIData::RobotData::is_ghost;\n

The documentation for this class was generated from the following file robot_dart/gui_data.hpp

"},{"location":"api/namespacestd/","title":"Namespace std","text":"

Namespace List > std

The documentation for this class was generated from the following file [generated]

"},{"location":"api/namespacesubprocess/","title":"Namespace subprocess","text":"

Namespace List > subprocess

The documentation for this class was generated from the following file robot_dart/gui/magnum/gs/camera.hpp

"},{"location":"api/dir_166284c5f0440000a6384365f2a45567/","title":"Dir robot_dart","text":"

FileList > robot_dart

"},{"location":"api/dir_166284c5f0440000a6384365f2a45567/#files","title":"Files","text":"Type Name file gui_data.hpp file robot.cpp file robot.hpp file robot_dart_simu.cpp file robot_dart_simu.hpp file robot_pool.cpp file robot_pool.hpp file scheduler.cpp file scheduler.hpp file utils.hpp file utils_headers_dart_collision.hpp file utils_headers_dart_dynamics.hpp file utils_headers_dart_io.hpp file utils_headers_external.hpp file utils_headers_external_gui.hpp"},{"location":"api/dir_166284c5f0440000a6384365f2a45567/#directories","title":"Directories","text":"Type Name dir control dir gui dir robots dir sensor

The documentation for this class was generated from the following file robot_dart/

"},{"location":"api/gui__data_8hpp/","title":"File gui_data.hpp","text":"

FileList > robot_dart > gui_data.hpp

Go to the source code of this file

"},{"location":"api/gui__data_8hpp/#namespaces","title":"Namespaces","text":"Type Name namespace robot_dart namespace simu"},{"location":"api/gui__data_8hpp/#classes","title":"Classes","text":"Type Name struct GUIData

The documentation for this class was generated from the following file robot_dart/gui_data.hpp

"},{"location":"api/gui__data_8hpp_source/","title":"File gui_data.hpp","text":"

File List > robot_dart > gui_data.hpp

Go to the documentation of this file

#ifndef ROBOT_DART_SIMU_GUI_DATA_HPP\n#define ROBOT_DART_SIMU_GUI_DATA_HPP\n#include \"robot_dart_simu.hpp\"\n#include \"utils_headers_dart_dynamics.hpp\"\n#include <unordered_map>\n#include <vector>\nnamespace robot_dart {\nnamespace simu {\nstruct GUIData {\nprivate:\nstruct RobotData {\nbool casting_shadows;\nbool is_ghost;\n};\nstd::unordered_map<dart::dynamics::ShapeNode*, RobotData> robot_data;\nstd::unordered_map<Robot*, std::vector<std::pair<dart::dynamics::BodyNode*, double>>> robot_axes;\nstd::vector<std::shared_ptr<simu::TextData>> text_drawings;\npublic:\nstd::shared_ptr<simu::TextData> add_text(const std::string& text, const Eigen::Affine2d& tf = Eigen::Affine2d::Identity(), Eigen::Vector4d color = Eigen::Vector4d(1, 1, 1, 1), std::uint8_t alignment = (1 | 3 << 3), bool draw_bg = false, Eigen::Vector4d bg_color = Eigen::Vector4d(0, 0, 0, 0.75), double font_size = 28)\n{\ntext_drawings.emplace_back(new TextData{text, tf, color, alignment, draw_bg, bg_color, font_size});\nreturn text_drawings.back();\n}\nvoid remove_text(const std::shared_ptr<simu::TextData>& data)\n{\nfor (size_t i = 0; i < text_drawings.size(); i++) {\nif (text_drawings[i] == data) {\ntext_drawings.erase(text_drawings.begin() + i);\nreturn;\n}\n}\n}\nvoid remove_text(size_t index)\n{\nif (index >= text_drawings.size())\nreturn;\ntext_drawings.erase(text_drawings.begin() + index);\n}\nvoid update_robot(const std::shared_ptr<Robot>& robot)\n{\nauto robot_ptr = &*robot;\nauto skel = robot->skeleton();\nbool cast = robot->cast_shadows();\nbool ghost = robot->ghost();\nfor (size_t i = 0; i < skel->getNumBodyNodes(); ++i) {\nauto bd = skel->getBodyNode(i);\nauto& shapes = bd->getShapeNodesWith<dart::dynamics::VisualAspect>();\nfor (size_t j = 0; j < shapes.size(); j++) {\nrobot_data[shapes[j]] = {cast, ghost};\n}\n}\nauto& axes = robot->drawing_axes();\nif (axes.size() > 0)\nrobot_axes[robot_ptr] = axes;\n}\nvoid remove_robot(const std::shared_ptr<Robot>& robot)\n{\nauto robot_ptr = &*robot;\nauto skel = robot->skeleton();\nfor (size_t i = 0; i < skel->getNumShapeNodes(); ++i) {\nauto shape = skel->getShapeNode(i);\nauto shape_iter = robot_data.find(shape);\nif (shape_iter != robot_data.end())\nrobot_data.erase(shape_iter);\n}\nauto iter = robot_axes.find(robot_ptr);\nif (iter != robot_axes.end())\nrobot_axes.erase(iter);\n}\nbool cast_shadows(dart::dynamics::ShapeNode* shape) const\n{\nauto shape_iter = robot_data.find(shape);\nif (shape_iter != robot_data.end())\nreturn robot_data.at(shape).casting_shadows;\n// if not in the array, cast shadow by default\nreturn true;\n}\nbool ghost(dart::dynamics::ShapeNode* shape) const\n{\nauto shape_iter = robot_data.find(shape);\nif (shape_iter != robot_data.end())\nreturn robot_data.at(shape).is_ghost;\n// if not in the array, the robot is not ghost by default\nreturn false;\n}\nstd::vector<std::pair<dart::dynamics::BodyNode*, double>> drawing_axes() const\n{\nstd::vector<std::pair<dart::dynamics::BodyNode*, double>> axes;\nfor (std::pair<Robot*, std::vector<std::pair<dart::dynamics::BodyNode*, double>>> elem : robot_axes) {\naxes.insert(axes.end(), elem.second.begin(), elem.second.end());\n}\nreturn axes;\n}\nconst std::vector<std::shared_ptr<simu::TextData>>& drawing_texts() const { return text_drawings; }\n};\n} // namespace simu\n} // namespace robot_dart\n#endif\n
"},{"location":"api/robot_8cpp/","title":"File robot.cpp","text":"

FileList > robot_dart > robot.cpp

Go to the source code of this file

"},{"location":"api/robot_8cpp/#namespaces","title":"Namespaces","text":"Type Name namespace robot_dart namespace detail

The documentation for this class was generated from the following file robot_dart/robot.cpp

"},{"location":"api/robot_8cpp_source/","title":"File robot.cpp","text":"

File List > robot_dart > robot.cpp

Go to the documentation of this file

#include <unistd.h>\n#include <robot_dart/robot.hpp>\n#include <robot_dart/utils.hpp>\n#include <robot_dart/utils_headers_dart_dynamics.hpp>\n#include <robot_dart/utils_headers_dart_io.hpp>\n#include <robot_dart/control/robot_control.hpp>\n#include <utheque/utheque.hpp> // library of URDF\nnamespace robot_dart {\nnamespace detail {\ntemplate <int content>\nEigen::VectorXd dof_data(dart::dynamics::SkeletonPtr skeleton, const std::vector<std::string>& dof_names, const std::unordered_map<std::string, size_t>& dof_map)\n{\n// Return all values\nif (dof_names.empty()) {\nif (content == 0)\nreturn skeleton->getPositions();\nelse if (content == 1)\nreturn skeleton->getVelocities();\nelse if (content == 2)\nreturn skeleton->getAccelerations();\nelse if (content == 3)\nreturn skeleton->getForces();\nelse if (content == 4)\nreturn skeleton->getCommands();\nelse if (content == 5)\nreturn skeleton->getPositionLowerLimits();\nelse if (content == 6)\nreturn skeleton->getPositionUpperLimits();\nelse if (content == 7)\nreturn skeleton->getVelocityLowerLimits();\nelse if (content == 8)\nreturn skeleton->getVelocityUpperLimits();\nelse if (content == 9)\nreturn skeleton->getAccelerationLowerLimits();\nelse if (content == 10)\nreturn skeleton->getAccelerationUpperLimits();\nelse if (content == 11)\nreturn skeleton->getForceLowerLimits();\nelse if (content == 12)\nreturn skeleton->getForceUpperLimits();\nelse if (content == 13)\nreturn skeleton->getCoriolisForces();\nelse if (content == 14)\nreturn skeleton->getGravityForces();\nelse if (content == 15)\nreturn skeleton->getCoriolisAndGravityForces();\nelse if (content == 16)\nreturn skeleton->getConstraintForces();\nROBOT_DART_EXCEPTION_ASSERT(false, \"Unknown type of data!\");\n}\nEigen::VectorXd data(dof_names.size());\nEigen::VectorXd tmp;\nif (content == 13)\ntmp = skeleton->getCoriolisForces();\nelse if (content == 14)\ntmp = skeleton->getGravityForces();\nelse if (content == 15)\ntmp = skeleton->getCoriolisAndGravityForces();\nelse if (content == 16)\ntmp = skeleton->getConstraintForces();\nfor (size_t i = 0; i < dof_names.size(); i++) {\nauto it = dof_map.find(dof_names[i]);\nROBOT_DART_ASSERT(it != dof_map.end(), \"dof_data: \" + dof_names[i] + \" is not in dof_map\", Eigen::VectorXd());\nauto dof = skeleton->getDof(it->second);\nif (content == 0)\ndata(i) = dof->getPosition();\nelse if (content == 1)\ndata(i) = dof->getVelocity();\nelse if (content == 2)\ndata(i) = dof->getAcceleration();\nelse if (content == 3)\ndata(i) = dof->getForce();\nelse if (content == 4)\ndata(i) = dof->getCommand();\nelse if (content == 5)\ndata(i) = dof->getPositionLowerLimit();\nelse if (content == 6)\ndata(i) = dof->getPositionUpperLimit();\nelse if (content == 7)\ndata(i) = dof->getVelocityLowerLimit();\nelse if (content == 8)\ndata(i) = dof->getVelocityUpperLimit();\nelse if (content == 9)\ndata(i) = dof->getAccelerationLowerLimit();\nelse if (content == 10)\ndata(i) = dof->getAccelerationUpperLimit();\nelse if (content == 11)\ndata(i) = dof->getForceLowerLimit();\nelse if (content == 12)\ndata(i) = dof->getForceUpperLimit();\nelse if (content == 13 || content == 14 || content == 15 || content == 16)\ndata(i) = tmp(it->second);\nelse\nROBOT_DART_EXCEPTION_ASSERT(false, \"Unknown type of data!\");\n}\nreturn data;\n}\ntemplate <int content>\nvoid set_dof_data(const Eigen::VectorXd& data, dart::dynamics::SkeletonPtr skeleton, const std::vector<std::string>& dof_names, const std::unordered_map<std::string, size_t>& dof_map)\n{\n// Set all values\nif (dof_names.empty()) {\nROBOT_DART_ASSERT(static_cast<size_t>(data.size()) == skeleton->getNumDofs(), \"set_dof_data: size of data is not the same as the DoFs\", );\nif (content == 0)\nreturn skeleton->setPositions(data);\nelse if (content == 1)\nreturn skeleton->setVelocities(data);\nelse if (content == 2)\nreturn skeleton->setAccelerations(data);\nelse if (content == 3)\nreturn skeleton->setForces(data);\nelse if (content == 4)\nreturn skeleton->setCommands(data);\nelse if (content == 5)\nreturn skeleton->setPositionLowerLimits(data);\nelse if (content == 6)\nreturn skeleton->setPositionUpperLimits(data);\nelse if (content == 7)\nreturn skeleton->setVelocityLowerLimits(data);\nelse if (content == 8)\nreturn skeleton->setVelocityUpperLimits(data);\nelse if (content == 9)\nreturn skeleton->setAccelerationLowerLimits(data);\nelse if (content == 10)\nreturn skeleton->setAccelerationUpperLimits(data);\nelse if (content == 11)\nreturn skeleton->setForceLowerLimits(data);\nelse if (content == 12)\nreturn skeleton->setForceUpperLimits(data);\nROBOT_DART_EXCEPTION_ASSERT(false, \"Unknown type of data!\");\n}\nROBOT_DART_ASSERT(static_cast<size_t>(data.size()) == dof_names.size(), \"set_dof_data: size of data is not the same as the dof_names size\", );\nfor (size_t i = 0; i < dof_names.size(); i++) {\nauto it = dof_map.find(dof_names[i]);\nROBOT_DART_ASSERT(it != dof_map.end(), \"dof_data: \" + dof_names[i] + \" is not in dof_map\", );\nauto dof = skeleton->getDof(it->second);\nif (content == 0)\ndof->setPosition(data(i));\nelse if (content == 1)\ndof->setVelocity(data(i));\nelse if (content == 2)\ndof->setAcceleration(data(i));\nelse if (content == 3)\ndof->setForce(data(i));\nelse if (content == 4)\ndof->setCommand(data(i));\nelse if (content == 5)\ndof->setPositionLowerLimit(data(i));\nelse if (content == 6)\ndof->setPositionUpperLimit(data(i));\nelse if (content == 7)\ndof->setVelocityLowerLimit(data(i));\nelse if (content == 8)\ndof->setVelocityUpperLimit(data(i));\nelse if (content == 9)\ndof->setAccelerationLowerLimit(data(i));\nelse if (content == 10)\ndof->setAccelerationUpperLimit(data(i));\nelse if (content == 11)\ndof->setForceLowerLimit(data(i));\nelse if (content == 12)\ndof->setForceUpperLimit(data(i));\nelse\nROBOT_DART_EXCEPTION_ASSERT(false, \"Unknown type of data!\");\n}\n}\ntemplate <int content>\nvoid add_dof_data(const Eigen::VectorXd& data, dart::dynamics::SkeletonPtr skeleton, const std::vector<std::string>& dof_names, const std::unordered_map<std::string, size_t>& dof_map)\n{\n// Set all values\nif (dof_names.empty()) {\nROBOT_DART_ASSERT(static_cast<size_t>(data.size()) == skeleton->getNumDofs(), \"set_dof_data: size of data is not the same as the DoFs\", );\nif (content == 0)\nreturn skeleton->setPositions(skeleton->getPositions() + data);\nelse if (content == 1)\nreturn skeleton->setVelocities(skeleton->getVelocities() + data);\nelse if (content == 2)\nreturn skeleton->setAccelerations(skeleton->getAccelerations() + data);\nelse if (content == 3)\nreturn skeleton->setForces(skeleton->getForces() + data);\nelse if (content == 4)\nreturn skeleton->setCommands(skeleton->getCommands() + data);\nelse if (content == 5)\nreturn skeleton->setPositionLowerLimits(skeleton->getPositionLowerLimits() + data);\nelse if (content == 6)\nreturn skeleton->setPositionUpperLimits(skeleton->getPositionUpperLimits() + data);\nelse if (content == 7)\nreturn skeleton->setVelocityLowerLimits(skeleton->getVelocityLowerLimits() + data);\nelse if (content == 8)\nreturn skeleton->setVelocityUpperLimits(skeleton->getVelocityUpperLimits() + data);\nelse if (content == 9)\nreturn skeleton->setAccelerationLowerLimits(skeleton->getAccelerationLowerLimits() + data);\nelse if (content == 10)\nreturn skeleton->setAccelerationUpperLimits(skeleton->getAccelerationUpperLimits() + data);\nelse if (content == 11)\nreturn skeleton->setForceLowerLimits(skeleton->getForceLowerLimits() + data);\nelse if (content == 12)\nreturn skeleton->setForceUpperLimits(skeleton->getForceUpperLimits() + data);\nROBOT_DART_EXCEPTION_ASSERT(false, \"Unknown type of data!\");\n}\nROBOT_DART_ASSERT(static_cast<size_t>(data.size()) == dof_names.size(), \"add_dof_data: size of data is not the same as the dof_names size\", );\nfor (size_t i = 0; i < dof_names.size(); i++) {\nauto it = dof_map.find(dof_names[i]);\nROBOT_DART_ASSERT(it != dof_map.end(), \"dof_data: \" + dof_names[i] + \" is not in dof_map\", );\nauto dof = skeleton->getDof(it->second);\nif (content == 0)\ndof->setPosition(dof->getPosition() + data(i));\nelse if (content == 1)\ndof->setVelocity(dof->getVelocity() + data(i));\nelse if (content == 2)\ndof->setAcceleration(dof->getAcceleration() + data(i));\nelse if (content == 3)\ndof->setForce(dof->getForce() + data(i));\nelse if (content == 4)\ndof->setCommand(dof->getCommand() + data(i));\nelse if (content == 5)\ndof->setPositionLowerLimit(dof->getPositionLowerLimit() + data(i));\nelse if (content == 6)\ndof->setPositionUpperLimit(dof->getPositionUpperLimit() + data(i));\nelse if (content == 7)\ndof->setVelocityLowerLimit(dof->getVelocityLowerLimit() + data(i));\nelse if (content == 8)\ndof->setVelocityUpperLimit(dof->getVelocityUpperLimit() + data(i));\nelse if (content == 9)\ndof->setAccelerationLowerLimit(dof->getAccelerationLowerLimit() + data(i));\nelse if (content == 10)\ndof->setAccelerationUpperLimit(dof->getAccelerationUpperLimit() + data(i));\nelse if (content == 11)\ndof->setForceLowerLimit(dof->getForceLowerLimit() + data(i));\nelse if (content == 12)\ndof->setForceUpperLimit(dof->getForceUpperLimit() + data(i));\nelse\nROBOT_DART_EXCEPTION_ASSERT(false, \"Unknown type of data!\");\n}\n}\n} // namespace detail\nRobot::Robot(const std::string& model_file, const std::vector<std::pair<std::string, std::string>>& packages, const std::string& robot_name, bool is_urdf_string, bool cast_shadows)\n: _robot_name(robot_name), _skeleton(_load_model(model_file, packages, is_urdf_string)), _cast_shadows(cast_shadows), _is_ghost(false)\n{\nROBOT_DART_EXCEPTION_INTERNAL_ASSERT(_skeleton != nullptr);\nupdate_joint_dof_maps();\n}\nRobot::Robot(const std::string& model_file, const std::string& robot_name, bool is_urdf_string, bool cast_shadows)\n: Robot(model_file, std::vector<std::pair<std::string, std::string>>(), robot_name, is_urdf_string, cast_shadows)\n{\n}\nRobot::Robot(dart::dynamics::SkeletonPtr skeleton, const std::string& robot_name, bool cast_shadows)\n: _robot_name(robot_name), _skeleton(skeleton), _cast_shadows(cast_shadows), _is_ghost(false)\n{\nROBOT_DART_EXCEPTION_INTERNAL_ASSERT(_skeleton != nullptr);\n_skeleton->setName(robot_name);\nupdate_joint_dof_maps();\nreset();\n}\nstd::shared_ptr<Robot> Robot::clone() const\n{\n// safely clone the skeleton\n_skeleton->getMutex().lock();\n#if DART_VERSION_AT_LEAST(6, 7, 2)\nauto tmp_skel = _skeleton->cloneSkeleton();\n#else\nauto tmp_skel = _skeleton->clone();\n#endif\n_skeleton->getMutex().unlock();\nauto robot = std::make_shared<Robot>(tmp_skel, _robot_name);\n#if DART_VERSION_AT_LEAST(6, 13, 0)\n// Deep copy everything\nfor (auto& bd : robot->skeleton()->getBodyNodes()) {\nauto& visual_shapes = bd->getShapeNodesWith<dart::dynamics::VisualAspect>();\nfor (auto& shape : visual_shapes) {\nif (shape->getShape()->getType() != dart::dynamics::SoftMeshShape::getStaticType())\nshape->setShape(shape->getShape()->clone());\n}\n}\n#endif\nrobot->set_positions(this->positions());\nrobot->_model_filename = _model_filename;\nrobot->_controllers.clear();\nfor (auto& ctrl : _controllers) {\nrobot->add_controller(ctrl->clone(), ctrl->weight());\n}\nreturn robot;\n}\nstd::shared_ptr<Robot> Robot::clone_ghost(const std::string& ghost_name, const Eigen::Vector4d& ghost_color) const\n{\n// safely clone the skeleton\n_skeleton->getMutex().lock();\n#if DART_VERSION_AT_LEAST(6, 7, 2)\nauto tmp_skel = _skeleton->cloneSkeleton();\n#else\nauto tmp_skel = _skeleton->clone();\n#endif\n_skeleton->getMutex().unlock();\nauto robot = std::make_shared<Robot>(tmp_skel, ghost_name + \"_\" + _robot_name);\nrobot->_model_filename = _model_filename;\n// ghost robots have no controllers\nrobot->_controllers.clear();\n// ghost robots do not do physics updates\nrobot->skeleton()->setMobile(false);\nfor (auto& bd : robot->skeleton()->getBodyNodes()) {\n// ghost robots do not have collisions\nauto& collision_shapes = bd->getShapeNodesWith<dart::dynamics::CollisionAspect>();\nfor (auto& shape : collision_shapes) {\nshape->removeAspect<dart::dynamics::CollisionAspect>();\n}\n// ghost robots do not have dynamics\nauto& dyn_shapes = bd->getShapeNodesWith<dart::dynamics::DynamicsAspect>();\nfor (auto& shape : dyn_shapes) {\nshape->removeAspect<dart::dynamics::DynamicsAspect>();\n}\n// ghost robots have a different color (same for all bodies)\nauto& visual_shapes = bd->getShapeNodesWith<dart::dynamics::VisualAspect>();\nfor (auto& shape : visual_shapes) {\n#if DART_VERSION_AT_LEAST(6, 13, 0)\nif (shape->getShape()->getType() != dart::dynamics::SoftMeshShape::getStaticType())\nshape->setShape(shape->getShape()->clone());\n#endif\nshape->getVisualAspect()->setRGBA(ghost_color);\n}\n}\n// set positions\nrobot->set_positions(this->positions());\n// ghost robots, by default, use the color from the VisualAspect\nrobot->set_color_mode(\"aspect\");\n// ghost robots do not cast shadows\nrobot->set_cast_shadows(false);\n// set the ghost flag\nrobot->set_ghost(true);\nreturn robot;\n}\ndart::dynamics::SkeletonPtr Robot::skeleton() { return _skeleton; }\ndart::dynamics::BodyNode* Robot::body_node(const std::string& body_name) { return _skeleton->getBodyNode(body_name); }\ndart::dynamics::BodyNode* Robot::body_node(size_t body_index)\n{\nROBOT_DART_ASSERT(body_index < _skeleton->getNumBodyNodes(), \"BodyNode index out of bounds\", nullptr);\nreturn _skeleton->getBodyNode(body_index);\n}\ndart::dynamics::Joint* Robot::joint(const std::string& joint_name) { return _skeleton->getJoint(joint_name); }\ndart::dynamics::Joint* Robot::joint(size_t joint_index)\n{\nROBOT_DART_ASSERT(joint_index < _skeleton->getNumJoints(), \"Joint index out of bounds\", nullptr);\nreturn _skeleton->getJoint(joint_index);\n}\ndart::dynamics::DegreeOfFreedom* Robot::dof(const std::string& dof_name) { return _skeleton->getDof(dof_name); }\ndart::dynamics::DegreeOfFreedom* Robot::dof(size_t dof_index)\n{\nROBOT_DART_ASSERT(dof_index < _skeleton->getNumDofs(), \"Dof index out of bounds\", nullptr);\nreturn _skeleton->getDof(dof_index);\n}\nconst std::string& Robot::name() const { return _robot_name; }\nvoid Robot::update(double t)\n{\n_skeleton->setCommands(Eigen::VectorXd::Zero(_skeleton->getNumDofs()));\nfor (auto& ctrl : _controllers) {\nif (ctrl->active())\ndetail::add_dof_data<4>(ctrl->weight() * ctrl->calculate(t), _skeleton,\nctrl->controllable_dofs(), _dof_map);\n}\n}\nvoid Robot::reinit_controllers()\n{\nfor (auto& ctrl : _controllers)\nctrl->init();\n}\nsize_t Robot::num_controllers() const { return _controllers.size(); }\nstd::vector<std::shared_ptr<control::RobotControl>> Robot::controllers() const\n{\nreturn _controllers;\n}\nstd::vector<std::shared_ptr<control::RobotControl>> Robot::active_controllers() const\n{\nstd::vector<std::shared_ptr<control::RobotControl>> ctrls;\nfor (auto& ctrl : _controllers) {\nif (ctrl->active())\nctrls.push_back(ctrl);\n}\nreturn ctrls;\n}\nstd::shared_ptr<control::RobotControl> Robot::controller(size_t index) const\n{\nROBOT_DART_ASSERT(index < _controllers.size(), \"Controller index out of bounds\", nullptr);\nreturn _controllers[index];\n}\nvoid Robot::add_controller(\nconst std::shared_ptr<control::RobotControl>& controller, double weight)\n{\n_controllers.push_back(controller);\ncontroller->set_robot(this->shared_from_this());\ncontroller->set_weight(weight);\ncontroller->init();\n}\nvoid Robot::remove_controller(const std::shared_ptr<control::RobotControl>& controller)\n{\nauto it = std::find(_controllers.begin(), _controllers.end(), controller);\nif (it != _controllers.end())\n_controllers.erase(it);\n}\nvoid Robot::remove_controller(size_t index)\n{\nROBOT_DART_ASSERT(index < _controllers.size(), \"Controller index out of bounds\", );\n_controllers.erase(_controllers.begin() + index);\n}\nvoid Robot::clear_controllers() { _controllers.clear(); }\nvoid Robot::fix_to_world()\n{\nauto parent_jt = _skeleton->getRootBodyNode()->getParentJoint();\nROBOT_DART_ASSERT(parent_jt != nullptr, \"RootBodyNode does not have a parent joint!\", );\nif (fixed())\nreturn;\nEigen::Isometry3d tf(dart::math::expAngular(_skeleton->getPositions().head(3)));\ntf.translation() = _skeleton->getPositions().segment(3, 3);\ndart::dynamics::WeldJoint::Properties properties;\nproperties.mName = parent_jt->getName();\n_skeleton->getRootBodyNode()->changeParentJointType<dart::dynamics::WeldJoint>(properties);\n_skeleton->getRootBodyNode()->getParentJoint()->setTransformFromParentBodyNode(tf);\nreinit_controllers();\nupdate_joint_dof_maps();\n}\n// pose: Orientation-Position\nvoid Robot::free_from_world(const Eigen::Vector6d& pose)\n{\nauto parent_jt = _skeleton->getRootBodyNode()->getParentJoint();\nROBOT_DART_ASSERT(parent_jt != nullptr, \"RootBodyNode does not have a parent joint!\", );\nEigen::Isometry3d tf(dart::math::expAngular(pose.head(3)));\ntf.translation() = pose.segment(3, 3);\n// if already free, we only change the transformation\nif (free()) {\nparent_jt->setTransformFromParentBodyNode(tf);\nreturn;\n}\ndart::dynamics::FreeJoint::Properties properties;\nproperties.mName = parent_jt->getName();\n_skeleton->getRootBodyNode()->changeParentJointType<dart::dynamics::FreeJoint>(properties);\n_skeleton->getRootBodyNode()->getParentJoint()->setTransformFromParentBodyNode(tf);\nreinit_controllers();\nupdate_joint_dof_maps();\n}\nbool Robot::fixed() const\n{\nauto parent_jt = _skeleton->getRootBodyNode()->getParentJoint();\nROBOT_DART_ASSERT(parent_jt != nullptr, \"RootBodyNode does not have a parent joint!\", false);\nreturn parent_jt->getType() == dart::dynamics::WeldJoint::getStaticType();\n}\nbool Robot::free() const\n{\nauto parent_jt = _skeleton->getRootBodyNode()->getParentJoint();\nROBOT_DART_ASSERT(parent_jt != nullptr, \"RootBodyNode does not have a parent joint!\", false);\nreturn parent_jt->getType() == dart::dynamics::FreeJoint::getStaticType();\n}\nvoid Robot::reset()\n{\n_skeleton->resetPositions();\n_skeleton->resetVelocities();\n_skeleton->resetAccelerations();\nclear_internal_forces();\nreset_commands();\nclear_external_forces();\n}\nvoid Robot::clear_external_forces() { _skeleton->clearExternalForces(); }\nvoid Robot::clear_internal_forces()\n{\n_skeleton->clearInternalForces();\n_skeleton->clearConstraintImpulses();\n}\nvoid Robot::reset_commands() { _skeleton->resetCommands(); }\nvoid Robot::set_actuator_types(const std::string& type, const std::vector<std::string>& joint_names, bool override_mimic, bool override_base)\n{\n// Set all dofs to same actuator type\nif (joint_names.empty()) {\nif (type == \"torque\") {\nreturn _set_actuator_types(dart::dynamics::Joint::FORCE, override_mimic, override_base);\n}\nelse if (type == \"servo\") {\nreturn _set_actuator_types(dart::dynamics::Joint::SERVO, override_mimic, override_base);\n}\nelse if (type == \"velocity\") {\nreturn _set_actuator_types(dart::dynamics::Joint::VELOCITY, override_mimic, override_base);\n}\nelse if (type == \"passive\") {\nreturn _set_actuator_types(dart::dynamics::Joint::PASSIVE, override_mimic, override_base);\n}\nelse if (type == \"locked\") {\nreturn _set_actuator_types(dart::dynamics::Joint::LOCKED, override_mimic, override_base);\n}\nelse if (type == \"mimic\") {\nROBOT_DART_WARNING(true, \"Use this only if you know what you are doing. Use set_mimic otherwise.\");\nreturn _set_actuator_types(dart::dynamics::Joint::MIMIC, override_mimic, override_base);\n}\nROBOT_DART_EXCEPTION_ASSERT(false, \"Unknown type of actuator type. Valid values: torque, servo, velocity, passive, locked, mimic\");\n}\nfor (size_t i = 0; i < joint_names.size(); i++) {\nauto it = _joint_map.find(joint_names[i]);\nROBOT_DART_ASSERT(it != _joint_map.end(), \"set_actuator_type: \" + joint_names[i] + \" is not in joint_map\", );\nif (type == \"torque\") {\n_set_actuator_type(it->second, dart::dynamics::Joint::FORCE, override_mimic, override_base);\n}\nelse if (type == \"servo\") {\n_set_actuator_type(it->second, dart::dynamics::Joint::SERVO, override_mimic, override_base);\n}\nelse if (type == \"velocity\") {\n_set_actuator_type(it->second, dart::dynamics::Joint::VELOCITY, override_mimic, override_base);\n}\nelse if (type == \"passive\") {\n_set_actuator_type(it->second, dart::dynamics::Joint::PASSIVE, override_mimic, override_base);\n}\nelse if (type == \"locked\") {\n_set_actuator_type(it->second, dart::dynamics::Joint::LOCKED, override_mimic, override_base);\n}\nelse if (type == \"mimic\") {\nROBOT_DART_WARNING(true, \"Use this only if you know what you are doing. Use set_mimic otherwise.\");\n_set_actuator_type(it->second, dart::dynamics::Joint::MIMIC, override_mimic, override_base);\n}\nelse\nROBOT_DART_EXCEPTION_ASSERT(false, \"Unknown type of actuator type. Valid values: torque, servo, velocity, passive, locked, mimic\");\n}\n}\nvoid Robot::set_actuator_type(const std::string& type, const std::string& joint_name, bool override_mimic, bool override_base)\n{\nset_actuator_types(type, {joint_name}, override_mimic, override_base);\n}\nvoid Robot::set_mimic(const std::string& joint_name, const std::string& mimic_joint_name, double multiplier, double offset)\n{\ndart::dynamics::Joint* jnt = _skeleton->getJoint(joint_name);\nconst dart::dynamics::Joint* mimic_jnt = _skeleton->getJoint(mimic_joint_name);\nROBOT_DART_ASSERT((jnt && mimic_jnt), \"set_mimic: joint names do not exist\", );\njnt->setActuatorType(dart::dynamics::Joint::MIMIC);\njnt->setMimicJoint(mimic_jnt, multiplier, offset);\n}\nstd::string Robot::actuator_type(const std::string& joint_name) const\n{\nauto it = _joint_map.find(joint_name);\nROBOT_DART_ASSERT(it != _joint_map.end(), \"actuator_type: \" + joint_name + \" is not in joint_map\", \"invalid\");\nauto type = _actuator_type(it->second);\nif (type == dart::dynamics::Joint::FORCE)\nreturn \"torque\";\nelse if (type == dart::dynamics::Joint::SERVO)\nreturn \"servo\";\nelse if (type == dart::dynamics::Joint::VELOCITY)\nreturn \"velocity\";\nelse if (type == dart::dynamics::Joint::PASSIVE)\nreturn \"passive\";\nelse if (type == dart::dynamics::Joint::LOCKED)\nreturn \"locked\";\nelse if (type == dart::dynamics::Joint::MIMIC)\nreturn \"mimic\";\nROBOT_DART_ASSERT(false, \"actuator_type: we should not reach here\", \"invalid\");\n}\nstd::vector<std::string> Robot::actuator_types(const std::vector<std::string>& joint_names) const\n{\nstd::vector<std::string> str_types;\n// Get all dofs\nif (joint_names.empty()) {\nauto types = _actuator_types();\nfor (size_t i = 0; i < types.size(); i++) {\nauto type = types[i];\nif (type == dart::dynamics::Joint::FORCE)\nstr_types.push_back(\"torque\");\nelse if (type == dart::dynamics::Joint::SERVO)\nstr_types.push_back(\"servo\");\nelse if (type == dart::dynamics::Joint::VELOCITY)\nstr_types.push_back(\"velocity\");\nelse if (type == dart::dynamics::Joint::PASSIVE)\nstr_types.push_back(\"passive\");\nelse if (type == dart::dynamics::Joint::LOCKED)\nstr_types.push_back(\"locked\");\nelse if (type == dart::dynamics::Joint::MIMIC)\nstr_types.push_back(\"mimic\");\n}\nROBOT_DART_ASSERT(str_types.size() == types.size(), \"actuator_types: sizes of retrieved modes do not match\", {});\nreturn str_types;\n}\nfor (size_t i = 0; i < joint_names.size(); i++) {\nstr_types.push_back(actuator_type(joint_names[i]));\n}\nROBOT_DART_ASSERT(str_types.size() == joint_names.size(), \"actuator_types: sizes of retrieved modes do not match\", {});\nreturn str_types;\n}\nvoid Robot::set_position_enforced(const std::vector<bool>& enforced, const std::vector<std::string>& dof_names)\n{\nsize_t n_dofs = dof_names.size();\nif (n_dofs == 0) {\nROBOT_DART_ASSERT(enforced.size() == _skeleton->getNumDofs(),\n\"Position enforced vector size is not the same as the DOFs of the robot\", );\nfor (size_t i = 0; i < _skeleton->getNumDofs(); ++i) {\n#if DART_VERSION_AT_LEAST(6, 10, 0)\n_skeleton->getDof(i)->getJoint()->setLimitEnforcement(enforced[i]);\n#else\n_skeleton->getDof(i)->getJoint()->setPositionLimitEnforced(enforced[i]);\n#endif\n}\n}\nelse {\nROBOT_DART_ASSERT(enforced.size() == dof_names.size(),\n\"Position enforced vector size is not the same as the dof_names size\", );\nfor (size_t i = 0; i < dof_names.size(); i++) {\nauto it = _dof_map.find(dof_names[i]);\nROBOT_DART_ASSERT(it != _dof_map.end(), \"set_position_enforced: \" + dof_names[i] + \" is not in dof_map\", );\n#if DART_VERSION_AT_LEAST(6, 10, 0)\n_skeleton->getDof(it->second)->getJoint()->setLimitEnforcement(enforced[i]);\n#else\n_skeleton->getDof(it->second)->getJoint()->setPositionLimitEnforced(enforced[i]);\n#endif\n}\n}\n}\nvoid Robot::set_position_enforced(bool enforced, const std::vector<std::string>& dof_names)\n{\nsize_t n_dofs = dof_names.size();\nif (n_dofs == 0)\nn_dofs = _skeleton->getNumDofs();\nstd::vector<bool> enforced_all(n_dofs, enforced);\nset_position_enforced(enforced_all, dof_names);\n}\nstd::vector<bool> Robot::position_enforced(const std::vector<std::string>& dof_names) const\n{\nstd::vector<bool> pos;\nif (dof_names.size() == 0) {\nfor (size_t i = 0; i < _skeleton->getNumDofs(); ++i) {\n#if DART_VERSION_AT_LEAST(6, 10, 0)\npos.push_back(_skeleton->getDof(i)->getJoint()->areLimitsEnforced());\n#else\npos.push_back(_skeleton->getDof(i)->getJoint()->isPositionLimitEnforced());\n#endif\n}\n}\nelse {\nfor (size_t i = 0; i < dof_names.size(); i++) {\nauto it = _dof_map.find(dof_names[i]);\nROBOT_DART_ASSERT(it != _dof_map.end(), \"position_enforced: \" + dof_names[i] + \" is not in dof_map\", std::vector<bool>());\n#if DART_VERSION_AT_LEAST(6, 10, 0)\npos.push_back(_skeleton->getDof(it->second)->getJoint()->areLimitsEnforced());\n#else\npos.push_back(_skeleton->getDof(it->second)->getJoint()->isPositionLimitEnforced());\n#endif\n}\n}\nreturn pos;\n}\nvoid Robot::force_position_bounds()\n{\nfor (size_t i = 0; i < _skeleton->getNumDofs(); ++i) {\nauto dof = _skeleton->getDof(i);\nauto jt = dof->getJoint();\n#if DART_VERSION_AT_LEAST(6, 10, 0)\nbool force = jt->areLimitsEnforced();\n#else\nbool force = jt->isPositionLimitEnforced();\n#endif\nauto type = jt->getActuatorType();\nforce = force || type == dart::dynamics::Joint::SERVO || type == dart::dynamics::Joint::MIMIC;\nif (force) {\ndouble epsilon = 1e-5;\nif (dof->getPosition() > dof->getPositionUpperLimit()) {\ndof->setPosition(dof->getPositionUpperLimit() - epsilon);\n}\nelse if (dof->getPosition() < dof->getPositionLowerLimit()) {\ndof->setPosition(dof->getPositionLowerLimit() + epsilon);\n}\n}\n}\n}\nvoid Robot::set_damping_coeffs(const std::vector<double>& damps, const std::vector<std::string>& dof_names)\n{\nsize_t n_dofs = dof_names.size();\nif (n_dofs == 0) {\nROBOT_DART_ASSERT(damps.size() == _skeleton->getNumDofs(),\n\"Damping coefficient vector size is not the same as the DOFs of the robot\", );\nfor (size_t i = 0; i < _skeleton->getNumDofs(); ++i) {\n_skeleton->getDof(i)->setDampingCoefficient(damps[i]);\n}\n}\nelse {\nROBOT_DART_ASSERT(damps.size() == dof_names.size(),\n\"Damping coefficient vector size is not the same as the dof_names size\", );\nfor (size_t i = 0; i < dof_names.size(); i++) {\nauto it = _dof_map.find(dof_names[i]);\nROBOT_DART_ASSERT(it != _dof_map.end(), \"set_damping_coeffs: \" + dof_names[i] + \" is not in dof_map\", );\n_skeleton->getDof(it->second)->setDampingCoefficient(damps[i]);\n}\n}\n}\nvoid Robot::set_damping_coeffs(double damp, const std::vector<std::string>& dof_names)\n{\nsize_t n_dofs = dof_names.size();\nif (n_dofs == 0)\nn_dofs = _skeleton->getNumDofs();\nstd::vector<double> damps_all(n_dofs, damp);\nset_damping_coeffs(damps_all, dof_names);\n}\nstd::vector<double> Robot::damping_coeffs(const std::vector<std::string>& dof_names) const\n{\nstd::vector<double> dampings;\nif (dof_names.size() == 0) {\nfor (size_t i = 0; i < _skeleton->getNumDofs(); ++i) {\ndampings.push_back(_skeleton->getDof(i)->getDampingCoefficient());\n}\n}\nelse {\nfor (size_t i = 0; i < dof_names.size(); i++) {\nauto it = _dof_map.find(dof_names[i]);\nROBOT_DART_ASSERT(it != _dof_map.end(), \"damping_coeffs: \" + dof_names[i] + \" is not in dof_map\", std::vector<double>());\ndampings.push_back(_skeleton->getDof(it->second)->getDampingCoefficient());\n}\n}\nreturn dampings;\n}\nvoid Robot::set_coulomb_coeffs(const std::vector<double>& cfrictions, const std::vector<std::string>& dof_names)\n{\nsize_t n_dofs = dof_names.size();\nif (n_dofs == 0) {\nROBOT_DART_ASSERT(cfrictions.size() == _skeleton->getNumDofs(),\n\"Coulomb friction coefficient vector size is not the same as the DOFs of the robot\", );\nfor (size_t i = 0; i < _skeleton->getNumDofs(); ++i) {\n_skeleton->getDof(i)->setCoulombFriction(cfrictions[i]);\n}\n}\nelse {\nROBOT_DART_ASSERT(cfrictions.size() == dof_names.size(),\n\"Coulomb friction coefficient vector size is not the same as the dof_names size\", );\nfor (size_t i = 0; i < dof_names.size(); i++) {\nauto it = _dof_map.find(dof_names[i]);\nROBOT_DART_ASSERT(it != _dof_map.end(), \"set_coulomb_coeffs: \" + dof_names[i] + \" is not in dof_map\", );\n_skeleton->getDof(it->second)->setCoulombFriction(cfrictions[i]);\n}\n}\n}\nvoid Robot::set_coulomb_coeffs(double cfriction, const std::vector<std::string>& dof_names)\n{\nsize_t n_dofs = dof_names.size();\nif (n_dofs == 0)\nn_dofs = _skeleton->getNumDofs();\nstd::vector<double> cfrictions(n_dofs, cfriction);\nset_coulomb_coeffs(cfrictions, dof_names);\n}\nstd::vector<double> Robot::coulomb_coeffs(const std::vector<std::string>& dof_names) const\n{\nstd::vector<double> cfrictions;\nif (dof_names.size() == 0) {\nfor (size_t i = 0; i < _skeleton->getNumDofs(); ++i) {\ncfrictions.push_back(_skeleton->getDof(i)->getCoulombFriction());\n}\n}\nelse {\nfor (size_t i = 0; i < dof_names.size(); i++) {\nauto it = _dof_map.find(dof_names[i]);\nROBOT_DART_ASSERT(it != _dof_map.end(), \"coulomb_coeffs: \" + dof_names[i] + \" is not in dof_map\", std::vector<double>());\ncfrictions.push_back(_skeleton->getDof(it->second)->getCoulombFriction());\n}\n}\nreturn cfrictions;\n}\nvoid Robot::set_spring_stiffnesses(const std::vector<double>& stiffnesses, const std::vector<std::string>& dof_names)\n{\nsize_t n_dofs = dof_names.size();\nif (n_dofs == 0) {\nROBOT_DART_ASSERT(stiffnesses.size() == _skeleton->getNumDofs(),\n\"Spring stiffnesses vector size is not the same as the DOFs of the robot\", );\nfor (size_t i = 0; i < _skeleton->getNumDofs(); ++i) {\n_skeleton->getDof(i)->setSpringStiffness(stiffnesses[i]);\n}\n}\nelse {\nROBOT_DART_ASSERT(stiffnesses.size() == dof_names.size(),\n\"Spring stiffnesses vector size is not the same as the dof_names size\", );\nfor (size_t i = 0; i < dof_names.size(); i++) {\nauto it = _dof_map.find(dof_names[i]);\nROBOT_DART_ASSERT(it != _dof_map.end(), \"set_spring_stiffnesses: \" + dof_names[i] + \" is not in dof_map\", );\n_skeleton->getDof(it->second)->setSpringStiffness(stiffnesses[i]);\n}\n}\n}\nvoid Robot::set_spring_stiffnesses(double stiffness, const std::vector<std::string>& dof_names)\n{\nsize_t n_dofs = dof_names.size();\nif (n_dofs == 0)\nn_dofs = _skeleton->getNumDofs();\nstd::vector<double> stiffnesses(n_dofs, stiffness);\nset_spring_stiffnesses(stiffnesses, dof_names);\n}\nstd::vector<double> Robot::spring_stiffnesses(const std::vector<std::string>& dof_names) const\n{\nstd::vector<double> stiffnesses;\nif (dof_names.size() == 0) {\nfor (size_t i = 0; i < _skeleton->getNumDofs(); ++i) {\nstiffnesses.push_back(_skeleton->getDof(i)->getSpringStiffness());\n}\n}\nelse {\nfor (size_t i = 0; i < dof_names.size(); i++) {\nauto it = _dof_map.find(dof_names[i]);\nROBOT_DART_ASSERT(it != _dof_map.end(), \"spring_stiffnesses: \" + dof_names[i] + \" is not in dof_map\", std::vector<double>());\nstiffnesses.push_back(_skeleton->getDof(it->second)->getSpringStiffness());\n}\n}\nreturn stiffnesses;\n}\n#if DART_VERSION_AT_LEAST(6, 10, 0)\nauto body_node_set_friction_dir = [](dart::dynamics::BodyNode* body, const Eigen::Vector3d& direction) {\nauto& dyn_shapes = body->getShapeNodesWith<dart::dynamics::DynamicsAspect>();\nfor (auto& shape : dyn_shapes) {\nconst auto& dyn = shape->getDynamicsAspect();\ndyn->setFirstFrictionDirection(direction);\ndyn->setFirstFrictionDirectionFrame(body);\n}\n};\n#endif\nvoid Robot::set_friction_dir(const std::string& body_name, const Eigen::Vector3d& direction)\n{\n#if DART_VERSION_AT_LEAST(6, 10, 0)\nauto bd = _skeleton->getBodyNode(body_name);\nROBOT_DART_ASSERT(bd != nullptr, \"BodyNode does not exist in skeleton!\", );\nbody_node_set_friction_dir(bd, direction);\n#else\nROBOT_DART_WARNING(true, \"DART supports the frictional direction from v.6.10 onwards!\");\n#endif\n}\nvoid Robot::set_friction_dir(size_t body_index, const Eigen::Vector3d& direction)\n{\n#if DART_VERSION_AT_LEAST(6, 10, 0)\nROBOT_DART_ASSERT(body_index < _skeleton->getNumBodyNodes(), \"BodyNode index out of bounds\", );\nbody_node_set_friction_dir(_skeleton->getBodyNode(body_index), direction);\n#else\nROBOT_DART_WARNING(true, \"DART supports the frictional direction from v.6.10 onwards!\");\n#endif\n}\n#if DART_VERSION_AT_LEAST(6, 10, 0)\nauto body_node_get_friction_dir = [](dart::dynamics::BodyNode* body) {\nauto& dyn_shapes = body->getShapeNodesWith<dart::dynamics::DynamicsAspect>();\nfor (auto& shape : dyn_shapes) {\nconst auto& dyn = shape->getDynamicsAspect();\nreturn dyn->getFirstFrictionDirection(); // assume all shape nodes have the same friction direction\n}\nreturn Eigen::Vector3d(Eigen::Vector3d::Zero());\n};\n#endif\nEigen::Vector3d Robot::friction_dir(const std::string& body_name)\n{\n#if DART_VERSION_AT_LEAST(6, 10, 0)\nauto bd = _skeleton->getBodyNode(body_name);\nROBOT_DART_ASSERT(bd != nullptr, \"BodyNode does not exist in skeleton!\", Eigen::Vector3d::Zero());\nreturn body_node_get_friction_dir(bd);\n#else\nROBOT_DART_WARNING(true, \"DART supports the frictional direction from v.6.10 onwards!\");\nreturn Eigen::Vector3d::Zero();\n#endif\n}\nEigen::Vector3d Robot::friction_dir(size_t body_index)\n{\n#if DART_VERSION_AT_LEAST(6, 10, 0)\nROBOT_DART_ASSERT(body_index < _skeleton->getNumBodyNodes(), \"BodyNode index out of bounds\", Eigen::Vector3d::Zero());\nreturn body_node_get_friction_dir(_skeleton->getBodyNode(body_index));\n#else\nROBOT_DART_WARNING(true, \"DART supports the frictional direction from v.6.10 onwards!\");\nreturn Eigen::Vector3d::Zero();\n#endif\n}\nauto body_node_set_friction_coeff = [](dart::dynamics::BodyNode* body, double value) {\n#if DART_VERSION_AT_LEAST(6, 10, 0)\nauto& dyn_shapes = body->getShapeNodesWith<dart::dynamics::DynamicsAspect>();\nfor (auto& shape : dyn_shapes) {\nshape->getDynamicsAspect()->setFrictionCoeff(value);\n}\n#else\nbody->setFrictionCoeff(value);\n#endif\n};\nvoid Robot::set_friction_coeff(const std::string& body_name, double value)\n{\nauto bd = _skeleton->getBodyNode(body_name);\nROBOT_DART_ASSERT(bd != nullptr, \"BodyNode does not exist in skeleton!\", );\nbody_node_set_friction_coeff(bd, value);\n}\nvoid Robot::set_friction_coeff(size_t body_index, double value)\n{\nROBOT_DART_ASSERT(body_index < _skeleton->getNumBodyNodes(), \"BodyNode index out of bounds\", );\nbody_node_set_friction_coeff(_skeleton->getBodyNode(body_index), value);\n}\nvoid Robot::set_friction_coeffs(double value)\n{\nfor (auto bd : _skeleton->getBodyNodes())\nbody_node_set_friction_coeff(bd, value);\n}\nauto body_node_get_friction_coeff = [](dart::dynamics::BodyNode* body) {\n#if DART_VERSION_AT_LEAST(6, 10, 0)\nauto& dyn_shapes = body->getShapeNodesWith<dart::dynamics::DynamicsAspect>();\nfor (auto& shape : dyn_shapes) {\nreturn shape->getDynamicsAspect()->getFrictionCoeff(); // assume all shape nodes have the same friction\n}\nreturn 0.;\n#else\nreturn body->getFrictionCoeff();\n#endif\n};\ndouble Robot::friction_coeff(const std::string& body_name)\n{\nauto bd = _skeleton->getBodyNode(body_name);\nROBOT_DART_ASSERT(bd != nullptr, \"BodyNode does not exist in skeleton!\", 0.);\nreturn body_node_get_friction_coeff(bd);\n}\ndouble Robot::friction_coeff(size_t body_index)\n{\nROBOT_DART_ASSERT(body_index < _skeleton->getNumBodyNodes(), \"BodyNode index out of bounds\", 0.);\nreturn body_node_get_friction_coeff(_skeleton->getBodyNode(body_index));\n}\n#if DART_VERSION_AT_LEAST(6, 10, 0)\nauto body_node_set_secondary_friction_coeff = [](dart::dynamics::BodyNode* body, double value) {\nauto& dyn_shapes = body->getShapeNodesWith<dart::dynamics::DynamicsAspect>();\nfor (auto& shape : dyn_shapes) {\nshape->getDynamicsAspect()->setSecondaryFrictionCoeff(value);\n}\n};\n#endif\nvoid Robot::set_secondary_friction_coeff(const std::string& body_name, double value)\n{\n#if DART_VERSION_AT_LEAST(6, 10, 0)\nauto bd = _skeleton->getBodyNode(body_name);\nROBOT_DART_ASSERT(bd != nullptr, \"BodyNode does not exist in skeleton!\", );\nbody_node_set_secondary_friction_coeff(bd, value);\n#else\nROBOT_DART_WARNING(true, \"DART supports the secondary friction coefficient from v.6.10 onwards!\");\n#endif\n}\nvoid Robot::set_secondary_friction_coeff(size_t body_index, double value)\n{\n#if DART_VERSION_AT_LEAST(6, 10, 0)\nROBOT_DART_ASSERT(body_index < _skeleton->getNumBodyNodes(), \"BodyNode index out of bounds\", );\nbody_node_set_secondary_friction_coeff(_skeleton->getBodyNode(body_index), value);\n#else\nROBOT_DART_WARNING(true, \"DART supports the secondary friction coefficient from v.6.10 onwards!\");\n#endif\n}\nvoid Robot::set_secondary_friction_coeffs(double value)\n{\n#if DART_VERSION_AT_LEAST(6, 10, 0)\nfor (auto bd : _skeleton->getBodyNodes())\nbody_node_set_secondary_friction_coeff(bd, value);\n#else\nROBOT_DART_WARNING(true, \"DART supports the secondary friction coefficient from v.6.10 onwards!\");\n#endif\n}\n#if DART_VERSION_AT_LEAST(6, 10, 0)\nauto body_node_get_secondary_friction_coeff = [](dart::dynamics::BodyNode* body) {\nauto& dyn_shapes = body->getShapeNodesWith<dart::dynamics::DynamicsAspect>();\nfor (auto& shape : dyn_shapes) {\nreturn shape->getDynamicsAspect()->getSecondaryFrictionCoeff(); // assume all shape nodes have the same friction\n}\nreturn 0.;\n};\n#endif\ndouble Robot::secondary_friction_coeff(const std::string& body_name)\n{\n#if DART_VERSION_AT_LEAST(6, 10, 0)\nauto bd = _skeleton->getBodyNode(body_name);\nROBOT_DART_ASSERT(bd != nullptr, \"BodyNode does not exist in skeleton!\", 0.);\nreturn body_node_get_secondary_friction_coeff(bd);\n#else\nROBOT_DART_WARNING(true, \"DART supports the secondary friction coefficient from v.6.10 onwards!\");\nreturn 0.;\n#endif\n}\ndouble Robot::secondary_friction_coeff(size_t body_index)\n{\n#if DART_VERSION_AT_LEAST(6, 10, 0)\nROBOT_DART_ASSERT(body_index < _skeleton->getNumBodyNodes(), \"BodyNode index out of bounds\", 0.);\nreturn body_node_get_secondary_friction_coeff(_skeleton->getBodyNode(body_index));\n#else\nROBOT_DART_WARNING(true, \"DART supports the secondary friction coefficient from v.6.10 onwards!\");\nreturn 0.;\n#endif\n}\nauto body_node_set_restitution_coeff = [](dart::dynamics::BodyNode* body, double value) {\n#if DART_VERSION_AT_LEAST(6, 10, 0)\nauto& dyn_shapes = body->getShapeNodesWith<dart::dynamics::DynamicsAspect>();\nfor (auto& shape : dyn_shapes) {\nshape->getDynamicsAspect()->setRestitutionCoeff(value);\n}\n#else\nbody->setRestitutionCoeff(value);\n#endif\n};\nvoid Robot::set_restitution_coeff(const std::string& body_name, double value)\n{\nauto bd = _skeleton->getBodyNode(body_name);\nROBOT_DART_ASSERT(bd != nullptr, \"BodyNode does not exist in skeleton!\", );\nbody_node_set_restitution_coeff(bd, value);\n}\nvoid Robot::set_restitution_coeff(size_t body_index, double value)\n{\nROBOT_DART_ASSERT(body_index < _skeleton->getNumBodyNodes(), \"BodyNode index out of bounds\", );\nbody_node_set_restitution_coeff(_skeleton->getBodyNode(body_index), value);\n}\nvoid Robot::set_restitution_coeffs(double value)\n{\nfor (auto bd : _skeleton->getBodyNodes())\nbody_node_set_restitution_coeff(bd, value);\n}\nauto body_node_get_restitution_coeff = [](dart::dynamics::BodyNode* body) {\n#if DART_VERSION_AT_LEAST(6, 10, 0)\nauto& dyn_shapes = body->getShapeNodesWith<dart::dynamics::DynamicsAspect>();\nfor (auto& shape : dyn_shapes) {\nreturn shape->getDynamicsAspect()->getRestitutionCoeff(); // assume all shape nodes have the same restitution\n}\nreturn 0.;\n#else\nreturn body->getRestitutionCoeff();\n#endif\n};\ndouble Robot::restitution_coeff(const std::string& body_name)\n{\nauto bd = _skeleton->getBodyNode(body_name);\nROBOT_DART_ASSERT(bd != nullptr, \"BodyNode does not exist in skeleton!\", 0.);\nreturn body_node_get_restitution_coeff(bd);\n}\ndouble Robot::restitution_coeff(size_t body_index)\n{\nROBOT_DART_ASSERT(body_index < _skeleton->getNumBodyNodes(), \"BodyNode index out of bounds\", 0.);\nreturn body_node_get_restitution_coeff(_skeleton->getBodyNode(body_index));\n}\nEigen::Isometry3d Robot::base_pose() const\n{\nif (free()) {\nEigen::Isometry3d tf(Eigen::Isometry3d::Identity());\ntf.linear() = dart::math::expMapRot(_skeleton->getPositions().head<6>().head<3>());\ntf.translation() = _skeleton->getPositions().head<6>().tail<3>();\nreturn tf;\n}\nauto jt = _skeleton->getRootBodyNode()->getParentJoint();\nROBOT_DART_ASSERT(jt != nullptr, \"Skeleton does not have a proper root BodyNode!\",\nEigen::Isometry3d::Identity());\nreturn jt->getTransformFromParentBodyNode();\n}\nEigen::Vector6d Robot::base_pose_vec() const\n{\nif (free())\nreturn _skeleton->getPositions().head(6);\nauto jt = _skeleton->getRootBodyNode()->getParentJoint();\nROBOT_DART_ASSERT(jt != nullptr, \"Skeleton does not have a proper root BodyNode!\",\nEigen::Vector6d::Zero());\nEigen::Isometry3d tf = jt->getTransformFromParentBodyNode();\nEigen::Vector6d x;\nx.head<3>() = dart::math::logMap(tf.linear());\nx.tail<3>() = tf.translation();\nreturn x;\n}\nvoid Robot::set_base_pose(const Eigen::Isometry3d& tf)\n{\nauto jt = _skeleton->getRootBodyNode()->getParentJoint();\nif (jt) {\nif (free()) {\nEigen::Vector6d x;\nx.head<3>() = dart::math::logMap(tf.linear());\nx.tail<3>() = tf.translation();\njt->setPositions(x);\n}\nelse\njt->setTransformFromParentBodyNode(tf);\n}\n}\nvoid Robot::set_base_pose(const Eigen::Vector6d& pose)\n{\nauto jt = _skeleton->getRootBodyNode()->getParentJoint();\nif (jt) {\nif (free())\njt->setPositions(pose);\nelse {\nEigen::Isometry3d tf(Eigen::Isometry3d::Identity());\ntf.linear() = dart::math::expMapRot(pose.head<3>());\ntf.translation() = pose.tail<3>();\njt->setTransformFromParentBodyNode(tf);\n}\n}\n}\nsize_t Robot::num_dofs() const { return _skeleton->getNumDofs(); }\nsize_t Robot::num_joints() const { return _skeleton->getNumJoints(); }\nsize_t Robot::num_bodies() const { return _skeleton->getNumBodyNodes(); }\nEigen::Vector3d Robot::com() const { return _skeleton->getCOM(); }\nEigen::Vector6d Robot::com_velocity() const { return _skeleton->getCOMSpatialVelocity(); }\nEigen::Vector6d Robot::com_acceleration() const { return _skeleton->getCOMSpatialAcceleration(); }\nEigen::VectorXd Robot::positions(const std::vector<std::string>& dof_names) const\n{\nreturn detail::dof_data<0>(_skeleton, dof_names, _dof_map);\n}\nvoid Robot::set_positions(const Eigen::VectorXd& positions, const std::vector<std::string>& dof_names)\n{\ndetail::set_dof_data<0>(positions, _skeleton, dof_names, _dof_map);\n}\nEigen::VectorXd Robot::position_lower_limits(const std::vector<std::string>& dof_names) const\n{\nreturn detail::dof_data<5>(_skeleton, dof_names, _dof_map);\n}\nvoid Robot::set_position_lower_limits(const Eigen::VectorXd& positions, const std::vector<std::string>& dof_names)\n{\ndetail::set_dof_data<5>(positions, _skeleton, dof_names, _dof_map);\n}\nEigen::VectorXd Robot::position_upper_limits(const std::vector<std::string>& dof_names) const\n{\nreturn detail::dof_data<6>(_skeleton, dof_names, _dof_map);\n}\nvoid Robot::set_position_upper_limits(const Eigen::VectorXd& positions, const std::vector<std::string>& dof_names)\n{\ndetail::set_dof_data<6>(positions, _skeleton, dof_names, _dof_map);\n}\nEigen::VectorXd Robot::velocities(const std::vector<std::string>& dof_names) const\n{\nreturn detail::dof_data<1>(_skeleton, dof_names, _dof_map);\n}\nvoid Robot::set_velocities(const Eigen::VectorXd& velocities, const std::vector<std::string>& dof_names)\n{\ndetail::set_dof_data<1>(velocities, _skeleton, dof_names, _dof_map);\n}\nEigen::VectorXd Robot::velocity_lower_limits(const std::vector<std::string>& dof_names) const\n{\nreturn detail::dof_data<7>(_skeleton, dof_names, _dof_map);\n}\nvoid Robot::set_velocity_lower_limits(const Eigen::VectorXd& velocities, const std::vector<std::string>& dof_names)\n{\ndetail::set_dof_data<7>(velocities, _skeleton, dof_names, _dof_map);\n}\nEigen::VectorXd Robot::velocity_upper_limits(const std::vector<std::string>& dof_names) const\n{\nreturn detail::dof_data<8>(_skeleton, dof_names, _dof_map);\n}\nvoid Robot::set_velocity_upper_limits(const Eigen::VectorXd& velocities, const std::vector<std::string>& dof_names)\n{\ndetail::set_dof_data<8>(velocities, _skeleton, dof_names, _dof_map);\n}\nEigen::VectorXd Robot::accelerations(const std::vector<std::string>& dof_names) const\n{\nreturn detail::dof_data<2>(_skeleton, dof_names, _dof_map);\n}\nvoid Robot::set_accelerations(const Eigen::VectorXd& accelerations, const std::vector<std::string>& dof_names)\n{\ndetail::set_dof_data<2>(accelerations, _skeleton, dof_names, _dof_map);\n}\nEigen::VectorXd Robot::acceleration_lower_limits(const std::vector<std::string>& dof_names) const\n{\nreturn detail::dof_data<9>(_skeleton, dof_names, _dof_map);\n}\nvoid Robot::set_acceleration_lower_limits(const Eigen::VectorXd& accelerations, const std::vector<std::string>& dof_names)\n{\ndetail::set_dof_data<9>(accelerations, _skeleton, dof_names, _dof_map);\n}\nEigen::VectorXd Robot::acceleration_upper_limits(const std::vector<std::string>& dof_names) const\n{\nreturn detail::dof_data<10>(_skeleton, dof_names, _dof_map);\n}\nvoid Robot::set_acceleration_upper_limits(const Eigen::VectorXd& accelerations, const std::vector<std::string>& dof_names)\n{\ndetail::set_dof_data<10>(accelerations, _skeleton, dof_names, _dof_map);\n}\nEigen::VectorXd Robot::forces(const std::vector<std::string>& dof_names) const\n{\nreturn detail::dof_data<3>(_skeleton, dof_names, _dof_map);\n}\nvoid Robot::set_forces(const Eigen::VectorXd& forces, const std::vector<std::string>& dof_names)\n{\ndetail::set_dof_data<3>(forces, _skeleton, dof_names, _dof_map);\n}\nEigen::VectorXd Robot::force_lower_limits(const std::vector<std::string>& dof_names) const\n{\nreturn detail::dof_data<11>(_skeleton, dof_names, _dof_map);\n}\nvoid Robot::set_force_lower_limits(const Eigen::VectorXd& forces, const std::vector<std::string>& dof_names)\n{\ndetail::set_dof_data<11>(forces, _skeleton, dof_names, _dof_map);\n}\nEigen::VectorXd Robot::force_upper_limits(const std::vector<std::string>& dof_names) const\n{\nreturn detail::dof_data<12>(_skeleton, dof_names, _dof_map);\n}\nvoid Robot::set_force_upper_limits(const Eigen::VectorXd& forces, const std::vector<std::string>& dof_names)\n{\ndetail::set_dof_data<12>(forces, _skeleton, dof_names, _dof_map);\n}\nEigen::VectorXd Robot::commands(const std::vector<std::string>& dof_names) const\n{\nreturn detail::dof_data<4>(_skeleton, dof_names, _dof_map);\n}\nvoid Robot::set_commands(const Eigen::VectorXd& commands, const std::vector<std::string>& dof_names)\n{\ndetail::set_dof_data<4>(commands, _skeleton, dof_names, _dof_map);\n}\nstd::pair<Eigen::Vector6d, Eigen::Vector6d> Robot::force_torque(size_t joint_index) const\n{\nROBOT_DART_ASSERT(joint_index < _skeleton->getNumJoints(), \"Joint index out of bounds\", {});\nauto jt = _skeleton->getJoint(joint_index);\nEigen::Vector6d F1 = Eigen::Vector6d::Zero();\nEigen::Vector6d F2 = Eigen::Vector6d::Zero();\nEigen::Isometry3d T12 = jt->getRelativeTransform();\nauto child_body = jt->getChildBodyNode();\n// ROBOT_DART_ASSERT(child_body != nullptr, \"Child BodyNode is nullptr\", {});\nif (child_body)\nF2 = -dart::math::dAdT(jt->getTransformFromChildBodyNode(), child_body->getBodyForce());\nF1 = -dart::math::dAdInvR(T12, F2);\n// F1 contains the force applied by the parent Link on the Joint specified in the parent\n// Link frame, F2 contains the force applied by the child Link on the Joint specified in\n// the child Link frame\nreturn {F1, F2};\n}\nvoid Robot::set_external_force(const std::string& body_name, const Eigen::Vector3d& force, const Eigen::Vector3d& offset, bool force_local, bool offset_local)\n{\nauto bd = _skeleton->getBodyNode(body_name);\nROBOT_DART_ASSERT(bd != nullptr, \"BodyNode does not exist in skeleton!\", );\nbd->setExtForce(force, offset, force_local, offset_local);\n}\nvoid Robot::set_external_force(size_t body_index, const Eigen::Vector3d& force, const Eigen::Vector3d& offset, bool force_local, bool offset_local)\n{\nROBOT_DART_ASSERT(body_index < _skeleton->getNumBodyNodes(), \"BodyNode index out of bounds\", );\nauto bd = _skeleton->getBodyNode(body_index);\nbd->setExtForce(force, offset, force_local, offset_local);\n}\nvoid Robot::add_external_force(const std::string& body_name, const Eigen::Vector3d& force, const Eigen::Vector3d& offset, bool force_local, bool offset_local)\n{\nauto bd = _skeleton->getBodyNode(body_name);\nROBOT_DART_ASSERT(bd != nullptr, \"BodyNode does not exist in skeleton!\", );\nbd->addExtForce(force, offset, force_local, offset_local);\n}\nvoid Robot::add_external_force(size_t body_index, const Eigen::Vector3d& force, const Eigen::Vector3d& offset, bool force_local, bool offset_local)\n{\nROBOT_DART_ASSERT(body_index < _skeleton->getNumBodyNodes(), \"BodyNode index out of bounds\", );\nauto bd = _skeleton->getBodyNode(body_index);\nbd->addExtForce(force, offset, force_local, offset_local);\n}\nvoid Robot::set_external_torque(const std::string& body_name, const Eigen::Vector3d& torque, bool local)\n{\nauto bd = _skeleton->getBodyNode(body_name);\nROBOT_DART_ASSERT(bd != nullptr, \"BodyNode does not exist in skeleton!\", );\nbd->setExtTorque(torque, local);\n}\nvoid Robot::set_external_torque(size_t body_index, const Eigen::Vector3d& torque, bool local)\n{\nROBOT_DART_ASSERT(body_index < _skeleton->getNumBodyNodes(), \"BodyNode index out of bounds\", );\nauto bd = _skeleton->getBodyNode(body_index);\nbd->setExtTorque(torque, local);\n}\nvoid Robot::add_external_torque(const std::string& body_name, const Eigen::Vector3d& torque, bool local)\n{\nauto bd = _skeleton->getBodyNode(body_name);\nROBOT_DART_ASSERT(bd != nullptr, \"BodyNode does not exist in skeleton!\", );\nbd->addExtTorque(torque, local);\n}\nvoid Robot::add_external_torque(size_t body_index, const Eigen::Vector3d& torque, bool local)\n{\nROBOT_DART_ASSERT(body_index < _skeleton->getNumBodyNodes(), \"BodyNode index out of bounds\", );\nauto bd = _skeleton->getBodyNode(body_index);\nbd->addExtTorque(torque, local);\n}\nEigen::Vector6d Robot::external_forces(const std::string& body_name) const\n{\nauto bd = _skeleton->getBodyNode(body_name);\nROBOT_DART_ASSERT(bd != nullptr, \"BodyNode does not exist in skeleton!\", Eigen::Vector6d::Zero());\nreturn bd->getExternalForceGlobal();\n}\nEigen::Vector6d Robot::external_forces(size_t body_index) const\n{\nROBOT_DART_ASSERT(body_index < _skeleton->getNumBodyNodes(), \"BodyNode index out of bounds\",\nEigen::Vector6d::Zero());\nauto bd = _skeleton->getBodyNode(body_index);\nreturn bd->getExternalForceGlobal();\n}\nEigen::Isometry3d Robot::body_pose(const std::string& body_name) const\n{\nauto bd = _skeleton->getBodyNode(body_name);\nROBOT_DART_ASSERT(bd != nullptr, \"BodyNode does not exist in skeleton!\", Eigen::Isometry3d::Identity());\nreturn bd->getWorldTransform();\n}\nEigen::Isometry3d Robot::body_pose(size_t body_index) const\n{\nROBOT_DART_ASSERT(body_index < _skeleton->getNumBodyNodes(), \"BodyNode index out of bounds\", Eigen::Isometry3d::Identity());\nreturn _skeleton->getBodyNode(body_index)->getWorldTransform();\n}\nEigen::Vector6d Robot::body_pose_vec(const std::string& body_name) const\n{\nauto bd = _skeleton->getBodyNode(body_name);\nROBOT_DART_ASSERT(bd != nullptr, \"BodyNode does not exist in skeleton!\", Eigen::Vector6d::Zero());\nEigen::Isometry3d tf = bd->getWorldTransform();\nEigen::Vector6d x;\nx.head<3>() = dart::math::logMap(tf.linear());\nx.tail<3>() = tf.translation();\nreturn x;\n}\nEigen::Vector6d Robot::body_pose_vec(size_t body_index) const\n{\nROBOT_DART_ASSERT(body_index < _skeleton->getNumBodyNodes(), \"BodyNode index out of bounds\", Eigen::Vector6d::Zero());\nEigen::Isometry3d tf = _skeleton->getBodyNode(body_index)->getWorldTransform();\nEigen::Vector6d x;\nx.head<3>() = dart::math::logMap(tf.linear());\nx.tail<3>() = tf.translation();\nreturn x;\n}\nEigen::Vector6d Robot::body_velocity(const std::string& body_name) const\n{\nauto bd = _skeleton->getBodyNode(body_name);\nROBOT_DART_ASSERT(bd != nullptr, \"BodyNode does not exist in skeleton!\", Eigen::Vector6d::Zero());\nreturn bd->getSpatialVelocity(dart::dynamics::Frame::World(), dart::dynamics::Frame::World());\n}\nEigen::Vector6d Robot::body_velocity(size_t body_index) const\n{\nROBOT_DART_ASSERT(body_index < _skeleton->getNumBodyNodes(), \"BodyNode index out of bounds\", Eigen::Vector6d::Zero());\nreturn _skeleton->getBodyNode(body_index)->getSpatialVelocity(dart::dynamics::Frame::World(), dart::dynamics::Frame::World());\n}\nEigen::Vector6d Robot::body_acceleration(const std::string& body_name) const\n{\nauto bd = _skeleton->getBodyNode(body_name);\nROBOT_DART_ASSERT(bd != nullptr, \"BodyNode does not exist in skeleton!\", Eigen::Vector6d::Zero());\nreturn bd->getSpatialAcceleration(dart::dynamics::Frame::World(), dart::dynamics::Frame::World());\n}\nEigen::Vector6d Robot::body_acceleration(size_t body_index) const\n{\nROBOT_DART_ASSERT(body_index < _skeleton->getNumBodyNodes(), \"BodyNode index out of bounds\", Eigen::Vector6d::Zero());\nreturn _skeleton->getBodyNode(body_index)->getSpatialAcceleration(dart::dynamics::Frame::World(), dart::dynamics::Frame::World());\n}\nstd::vector<std::string> Robot::body_names() const\n{\nstd::vector<std::string> names;\nfor (auto& bd : _skeleton->getBodyNodes())\nnames.push_back(bd->getName());\nreturn names;\n}\nstd::string Robot::body_name(size_t body_index) const\n{\nROBOT_DART_ASSERT(body_index < _skeleton->getNumBodyNodes(), \"BodyNode index out of bounds\", \"\");\nreturn _skeleton->getBodyNode(body_index)->getName();\n}\nvoid Robot::set_body_name(size_t body_index, const std::string& body_name)\n{\nROBOT_DART_ASSERT(body_index < _skeleton->getNumBodyNodes(), \"BodyNode index out of bounds\", );\n_skeleton->getBodyNode(body_index)->setName(body_name);\n}\nsize_t Robot::body_index(const std::string& body_name) const\n{\nauto bd = _skeleton->getBodyNode(body_name);\nROBOT_DART_ASSERT(bd, \"body_index : \" + body_name + \" is not in the skeleton\", 0);\nreturn bd->getIndexInSkeleton();\n}\ndouble Robot::body_mass(const std::string& body_name) const\n{\nauto bd = _skeleton->getBodyNode(body_name);\nROBOT_DART_ASSERT(bd != nullptr, \"BodyNode does not exist in skeleton!\", 0.);\nreturn bd->getMass();\n}\ndouble Robot::body_mass(size_t body_index) const\n{\nROBOT_DART_ASSERT(body_index < _skeleton->getNumBodyNodes(), \"BodyNode index out of bounds\", 0.);\nreturn _skeleton->getBodyNode(body_index)->getMass();\n}\nvoid Robot::set_body_mass(const std::string& body_name, double mass)\n{\nauto bd = _skeleton->getBodyNode(body_name);\nROBOT_DART_ASSERT(bd != nullptr, \"BodyNode does not exist in skeleton!\", );\nbd->setMass(mass); // TO-DO: Recompute inertia?\n}\nvoid Robot::set_body_mass(size_t body_index, double mass)\n{\nROBOT_DART_ASSERT(body_index < _skeleton->getNumBodyNodes(), \"BodyNode index out of bounds\", );\n_skeleton->getBodyNode(body_index)->setMass(mass); // TO-DO: Recompute inertia?\n}\nvoid Robot::add_body_mass(const std::string& body_name, double mass)\n{\nauto bd = _skeleton->getBodyNode(body_name);\nROBOT_DART_ASSERT(bd != nullptr, \"BodyNode does not exist in skeleton!\", );\nbd->setMass(mass + bd->getMass()); // TO-DO: Recompute inertia?\n}\nvoid Robot::add_body_mass(size_t body_index, double mass)\n{\nROBOT_DART_ASSERT(body_index < _skeleton->getNumBodyNodes(), \"BodyNode index out of bounds\", );\nauto bd = _skeleton->getBodyNode(body_index);\nbd->setMass(mass + bd->getMass()); // TO-DO: Recompute inertia?\n}\nEigen::MatrixXd Robot::jacobian(const std::string& body_name, const std::vector<std::string>& dof_names) const\n{\nauto bd = _skeleton->getBodyNode(body_name);\nROBOT_DART_ASSERT(bd != nullptr, \"BodyNode does not exist in skeleton!\", Eigen::MatrixXd());\nEigen::MatrixXd jac = _skeleton->getWorldJacobian(bd);\nreturn _jacobian(jac, dof_names);\n}\nEigen::MatrixXd Robot::jacobian_deriv(const std::string& body_name, const std::vector<std::string>& dof_names) const\n{\nauto bd = _skeleton->getBodyNode(body_name);\nROBOT_DART_ASSERT(bd != nullptr, \"BodyNode does not exist in skeleton!\", Eigen::MatrixXd());\nEigen::MatrixXd jac = _skeleton->getJacobianSpatialDeriv(bd, dart::dynamics::Frame::World());\nreturn _jacobian(jac, dof_names);\n}\nEigen::MatrixXd Robot::com_jacobian(const std::vector<std::string>& dof_names) const\n{\nEigen::MatrixXd jac = _skeleton->getCOMJacobian();\nreturn _jacobian(jac, dof_names);\n}\nEigen::MatrixXd Robot::com_jacobian_deriv(const std::vector<std::string>& dof_names) const\n{\nEigen::MatrixXd jac = _skeleton->getCOMJacobianSpatialDeriv();\nreturn _jacobian(jac, dof_names);\n}\nEigen::MatrixXd Robot::mass_matrix(const std::vector<std::string>& dof_names) const\n{\nEigen::MatrixXd M = _skeleton->getMassMatrix();\nreturn _mass_matrix(M, dof_names);\n}\nEigen::MatrixXd Robot::aug_mass_matrix(const std::vector<std::string>& dof_names) const\n{\nEigen::MatrixXd M = _skeleton->getAugMassMatrix();\nreturn _mass_matrix(M, dof_names);\n}\nEigen::MatrixXd Robot::inv_mass_matrix(const std::vector<std::string>& dof_names) const\n{\nEigen::MatrixXd M = _skeleton->getInvMassMatrix();\nreturn _mass_matrix(M, dof_names);\n}\nEigen::MatrixXd Robot::inv_aug_mass_matrix(const std::vector<std::string>& dof_names) const\n{\nEigen::MatrixXd M = _skeleton->getInvAugMassMatrix();\nreturn _mass_matrix(M, dof_names);\n}\nEigen::VectorXd Robot::coriolis_forces(const std::vector<std::string>& dof_names) const\n{\nreturn detail::dof_data<13>(_skeleton, dof_names, _dof_map);\n}\nEigen::VectorXd Robot::gravity_forces(const std::vector<std::string>& dof_names) const\n{\nreturn detail::dof_data<14>(_skeleton, dof_names, _dof_map);\n}\nEigen::VectorXd Robot::coriolis_gravity_forces(const std::vector<std::string>& dof_names) const\n{\nreturn detail::dof_data<15>(_skeleton, dof_names, _dof_map);\n}\nEigen::VectorXd Robot::constraint_forces(const std::vector<std::string>& dof_names) const\n{\nreturn detail::dof_data<16>(_skeleton, dof_names, _dof_map);\n}\nEigen::VectorXd Robot::vec_dof(const Eigen::VectorXd& vec, const std::vector<std::string>& dof_names) const\n{\nassert(vec.size() == static_cast<int>(_skeleton->getNumDofs()));\nEigen::VectorXd ret(dof_names.size());\nfor (size_t i = 0; i < dof_names.size(); i++) {\nauto it = _dof_map.find(dof_names[i]);\nROBOT_DART_ASSERT(it != _dof_map.end(), \"vec_dof: \" + dof_names[i] + \" is not in dof_map\", Eigen::VectorXd());\nret(i) = vec[it->second];\n}\nreturn ret;\n}\nvoid Robot::update_joint_dof_maps()\n{\n// DoFs\n_dof_map.clear();\nfor (size_t i = 0; i < _skeleton->getNumDofs(); ++i)\n_dof_map[_skeleton->getDof(i)->getName()] = i;\n// Joints\n_joint_map.clear();\nfor (size_t i = 0; i < _skeleton->getNumJoints(); ++i)\n_joint_map[_skeleton->getJoint(i)->getName()] = i;\n}\nconst std::unordered_map<std::string, size_t>& Robot::dof_map() const { return _dof_map; }\nconst std::unordered_map<std::string, size_t>& Robot::joint_map() const { return _joint_map; }\nstd::vector<std::string> Robot::dof_names(bool filter_mimics, bool filter_locked, bool filter_passive) const\n{\nstd::vector<std::string> names;\nfor (auto& dof : _skeleton->getDofs()) {\nauto jt = dof->getJoint();\nif ((!filter_mimics\n#if DART_VERSION_AT_LEAST(6, 7, 0)\n|| jt->getActuatorType() != dart::dynamics::Joint::MIMIC\n#else\n|| true\n#endif\n)\n&& (!filter_locked || jt->getActuatorType() != dart::dynamics::Joint::LOCKED)\n&& (!filter_passive || jt->getActuatorType() != dart::dynamics::Joint::PASSIVE))\nnames.push_back(dof->getName());\n}\nreturn names;\n}\nstd::vector<std::string> Robot::mimic_dof_names() const\n{\nstd::vector<std::string> names;\n#if DART_VERSION_AT_LEAST(6, 7, 0)\nfor (auto& dof : _skeleton->getDofs()) {\nauto jt = dof->getJoint();\nif (jt->getActuatorType() == dart::dynamics::Joint::MIMIC)\nnames.push_back(dof->getName());\n}\n#endif\nreturn names;\n}\nstd::vector<std::string> Robot::locked_dof_names() const\n{\nstd::vector<std::string> names;\nfor (auto& dof : _skeleton->getDofs()) {\nauto jt = dof->getJoint();\nif (jt->getActuatorType() == dart::dynamics::Joint::LOCKED)\nnames.push_back(dof->getName());\n}\nreturn names;\n}\nstd::vector<std::string> Robot::passive_dof_names() const\n{\nstd::vector<std::string> names;\nfor (auto& dof : _skeleton->getDofs()) {\nauto jt = dof->getJoint();\nif (jt->getActuatorType() == dart::dynamics::Joint::PASSIVE)\nnames.push_back(dof->getName());\n}\nreturn names;\n}\nstd::string Robot::dof_name(size_t dof_index) const\n{\nROBOT_DART_ASSERT(dof_index < _skeleton->getNumDofs(), \"Dof index out of bounds\", \"\");\nreturn _skeleton->getDof(dof_index)->getName();\n}\nsize_t Robot::dof_index(const std::string& dof_name) const\n{\nif (_dof_map.empty()) {\nROBOT_DART_WARNING(true,\n\"DoF map is empty. Iterating over all skeleton DoFs to get the index. Consider \"\n\"calling update_joint_dof_maps() before using dof_index()\");\nfor (size_t i = 0; i < _skeleton->getNumDofs(); i++)\nif (_skeleton->getDof(i)->getName() == dof_name)\nreturn i;\nROBOT_DART_ASSERT(false, \"dof_index : \" + dof_name + \" is not in the skeleton\", 0);\n}\nauto it = _dof_map.find(dof_name);\nROBOT_DART_ASSERT(it != _dof_map.end(), \"dof_index : \" + dof_name + \" is not in DoF map\", 0);\nreturn it->second;\n}\nstd::vector<std::string> Robot::joint_names() const\n{\nstd::vector<std::string> names;\nfor (auto& jt : _skeleton->getJoints())\nnames.push_back(jt->getName());\nreturn names;\n}\nstd::string Robot::joint_name(size_t joint_index) const\n{\nROBOT_DART_ASSERT(joint_index < _skeleton->getNumJoints(), \"Joint index out of bounds\", \"\");\nreturn _skeleton->getJoint(joint_index)->getName();\n}\nvoid Robot::set_joint_name(size_t joint_index, const std::string& joint_name)\n{\nROBOT_DART_ASSERT(joint_index < _skeleton->getNumJoints(), \"Joint index out of bounds\", );\n_skeleton->getJoint(joint_index)->setName(joint_name);\nupdate_joint_dof_maps();\n}\nsize_t Robot::joint_index(const std::string& joint_name) const\n{\nif (_joint_map.empty()) {\nROBOT_DART_WARNING(true,\n\"Joint map is empty. Iterating over all skeleton joints to get the index. \"\n\"Consider calling update_joint_dof_maps() before using joint_index()\");\nfor (size_t i = 0; i < _skeleton->getNumJoints(); i++)\nif (_skeleton->getJoint(i)->getName() == joint_name)\nreturn i;\nROBOT_DART_ASSERT(false, \"joint_index : \" + joint_name + \" is not in the skeleton\", 0);\n}\nauto it = _joint_map.find(joint_name);\nROBOT_DART_ASSERT(it != _joint_map.end(), \"joint_index : \" + joint_name + \" is not in Joint map\", 0);\nreturn it->second;\n}\nvoid Robot::set_color_mode(const std::string& color_mode)\n{\nif (color_mode == \"material\")\n_set_color_mode(dart::dynamics::MeshShape::ColorMode::MATERIAL_COLOR, _skeleton);\nelse if (color_mode == \"assimp\")\n_set_color_mode(dart::dynamics::MeshShape::ColorMode::COLOR_INDEX, _skeleton);\nelse if (color_mode == \"aspect\")\n_set_color_mode(dart::dynamics::MeshShape::ColorMode::SHAPE_COLOR, _skeleton);\nelse\nROBOT_DART_EXCEPTION_ASSERT(false, \"Unknown color mode. Valid values: material, assimp and aspect.\");\n}\nvoid Robot::set_color_mode(const std::string& color_mode, const std::string& body_name)\n{\ndart::dynamics::MeshShape::ColorMode cmode;\nif (color_mode == \"material\")\ncmode = dart::dynamics::MeshShape::ColorMode::MATERIAL_COLOR;\nelse if (color_mode == \"assimp\")\ncmode = dart::dynamics::MeshShape::ColorMode::COLOR_INDEX;\nelse if (color_mode == \"aspect\")\ncmode = dart::dynamics::MeshShape::ColorMode::SHAPE_COLOR;\nelse\nROBOT_DART_EXCEPTION_ASSERT(false, \"Unknown color mode. Valid values: material, assimp and aspect.\");\nauto bn = _skeleton->getBodyNode(body_name);\nif (bn) {\nfor (size_t j = 0; j < bn->getNumShapeNodes(); ++j) {\ndart::dynamics::ShapeNode* sn = bn->getShapeNode(j);\n_set_color_mode(cmode, sn);\n}\n}\n}\nvoid Robot::set_self_collision(bool enable_self_collisions, bool enable_adjacent_collisions)\n{\n_skeleton->setSelfCollisionCheck(enable_self_collisions);\n_skeleton->setAdjacentBodyCheck(enable_adjacent_collisions);\n}\nbool Robot::self_colliding() const\n{\nreturn _skeleton->getSelfCollisionCheck();\n}\nbool Robot::adjacent_colliding() const\n{\nreturn _skeleton->getAdjacentBodyCheck() && self_colliding();\n}\nvoid Robot::set_cast_shadows(bool cast_shadows) { _cast_shadows = cast_shadows; }\nbool Robot::cast_shadows() const { return _cast_shadows; }\nvoid Robot::set_ghost(bool ghost) { _is_ghost = ghost; }\nbool Robot::ghost() const { return _is_ghost; }\nvoid Robot::set_draw_axis(const std::string& body_name, double size)\n{\nauto bd = _skeleton->getBodyNode(body_name);\nROBOT_DART_ASSERT(bd, \"Body name does not exist in skeleton\", );\nstd::pair<dart::dynamics::BodyNode*, double> p = {bd, size};\nauto iter = std::find(_axis_shapes.begin(), _axis_shapes.end(), p);\nif (iter == _axis_shapes.end())\n_axis_shapes.push_back(p);\n}\nvoid Robot::remove_all_drawing_axis()\n{\n_axis_shapes.clear();\n}\nconst std::vector<std::pair<dart::dynamics::BodyNode*, double>>& Robot::drawing_axes() const { return _axis_shapes; }\ndart::dynamics::SkeletonPtr Robot::_load_model(const std::string& filename, const std::vector<std::pair<std::string, std::string>>& packages, bool is_urdf_string)\n{\nROBOT_DART_EXCEPTION_ASSERT(!filename.empty(), \"Empty URDF filename\");\ndart::dynamics::SkeletonPtr tmp_skel;\nif (!is_urdf_string) {\n// search for the right directory for our files\nstd::string model_file = utheque::path(filename, false, std::string(ROBOT_DART_PREFIX));\n// store the name for future use\n_model_filename = model_file;\n_packages = packages;\n// std::cout << \"RobotDART:: using: \" << model_file << std::endl;\nfs::path path(model_file);\nstd::string extension = path.extension().string();\nif (extension == \".urdf\") {\n#if DART_VERSION_AT_LEAST(6, 12, 0)\ndart::io::DartLoader::Options options;\n// if links have no inertia, we put ~zero mass and very very small inertia\noptions.mDefaultInertia = dart::dynamics::Inertia(1e-10, Eigen::Vector3d::Zero(), Eigen::Matrix3d::Identity() * 1e-6);\ndart::io::DartLoader loader(options);\n#else\ndart::io::DartLoader loader;\n#endif\nfor (size_t i = 0; i < packages.size(); i++) {\nstd::string package = std::get<1>(packages[i]);\nstd::string package_path = utheque::directory(package, false, std::string(ROBOT_DART_PREFIX));\nloader.addPackageDirectory(\nstd::get<0>(packages[i]), package_path + \"/\" + package);\n}\ntmp_skel = loader.parseSkeleton(model_file);\n}\nelse if (extension == \".sdf\")\ntmp_skel = dart::io::SdfParser::readSkeleton(model_file);\nelse if (extension == \".skel\") {\ntmp_skel = dart::io::SkelParser::readSkeleton(model_file);\n// if the skel file contains a world\n// try to read the skeleton with name 'robot_name'\nif (!tmp_skel) {\ndart::simulation::WorldPtr world = dart::io::SkelParser::readWorld(model_file);\ntmp_skel = world->getSkeleton(_robot_name);\n}\n}\nelse\nreturn nullptr;\n}\nelse {\n// Load from URDF string\ndart::io::DartLoader loader;\nfor (size_t i = 0; i < packages.size(); i++) {\nstd::string package = std::get<1>(packages[i]);\nstd::string package_path = utheque::directory(package, false, std::string(ROBOT_DART_PREFIX));\nloader.addPackageDirectory(std::get<0>(packages[i]), package_path + \"/\" + package);\n}\ntmp_skel = loader.parseSkeletonString(filename, \"\");\n}\nif (tmp_skel == nullptr)\nreturn nullptr;\ntmp_skel->setName(_robot_name);\n// Set joint limits\nfor (size_t i = 0; i < tmp_skel->getNumJoints(); ++i) {\n#if DART_VERSION_AT_LEAST(6, 10, 0)\ntmp_skel->getJoint(i)->setLimitEnforcement(true);\n#else\ntmp_skel->getJoint(i)->setPositionLimitEnforced(true);\n#endif\n}\n_set_color_mode(dart::dynamics::MeshShape::ColorMode::SHAPE_COLOR, tmp_skel);\nreturn tmp_skel;\n}\nvoid Robot::_set_color_mode(dart::dynamics::MeshShape::ColorMode color_mode, dart::dynamics::SkeletonPtr skel)\n{\nfor (size_t i = 0; i < skel->getNumBodyNodes(); ++i) {\ndart::dynamics::BodyNode* bn = skel->getBodyNode(i);\nfor (size_t j = 0; j < bn->getNumShapeNodes(); ++j) {\ndart::dynamics::ShapeNode* sn = bn->getShapeNode(j);\n_set_color_mode(color_mode, sn);\n}\n}\n}\nvoid Robot::_set_color_mode(dart::dynamics::MeshShape::ColorMode color_mode, dart::dynamics::ShapeNode* sn)\n{\nif (sn->getVisualAspect()) {\ndart::dynamics::MeshShape* ms\n= dynamic_cast<dart::dynamics::MeshShape*>(sn->getShape().get());\nif (ms)\nms->setColorMode(color_mode);\n}\n}\nvoid Robot::_set_actuator_type(size_t joint_index, dart::dynamics::Joint::ActuatorType type, bool override_mimic, bool override_base)\n{\nROBOT_DART_ASSERT(joint_index < _skeleton->getNumJoints(), \"joint_index index out of bounds\", );\nauto jt = _skeleton->getJoint(joint_index);\n// Do not override 6D base if robot is free and override_base is false\nif (free() && (!override_base && _skeleton->getRootJoint() == jt))\nreturn;\n#if DART_VERSION_AT_LEAST(6, 7, 0)\nif (override_mimic || jt->getActuatorType() != dart::dynamics::Joint::MIMIC)\n#endif\njt->setActuatorType(type);\n}\nvoid Robot::_set_actuator_types(const std::vector<dart::dynamics::Joint::ActuatorType>& types, bool override_mimic, bool override_base)\n{\nROBOT_DART_ASSERT(types.size() == _skeleton->getNumJoints(), \"Actuator types vector size is not the same as the joints of the robot\", );\n// Ignore first root joint if robot is free, and override_base is false\nbool ignore_base = free() && !override_base;\nauto root_jt = _skeleton->getRootJoint();\nfor (size_t i = 0; i < _skeleton->getNumJoints(); ++i) {\nauto jt = _skeleton->getJoint(i);\nif (jt->getNumDofs() == 0 || (ignore_base && jt == root_jt))\ncontinue;\n#if DART_VERSION_AT_LEAST(6, 7, 0)\nif (override_mimic || jt->getActuatorType() != dart::dynamics::Joint::MIMIC)\n#endif\njt->setActuatorType(types[i]);\n}\n}\nvoid Robot::_set_actuator_types(dart::dynamics::Joint::ActuatorType type, bool override_mimic, bool override_base)\n{\n// Ignore first root joint if robot is free, and override_base is false\nbool ignore_base = free() && !override_base;\nauto root_jt = _skeleton->getRootJoint();\nfor (size_t i = 0; i < _skeleton->getNumJoints(); ++i) {\nauto jt = _skeleton->getJoint(i);\nif (jt->getNumDofs() == 0 || (ignore_base && jt == root_jt))\ncontinue;\n#if DART_VERSION_AT_LEAST(6, 7, 0)\nif (override_mimic || jt->getActuatorType() != dart::dynamics::Joint::MIMIC)\n#endif\njt->setActuatorType(type);\n}\n}\ndart::dynamics::Joint::ActuatorType Robot::_actuator_type(size_t joint_index) const\n{\nROBOT_DART_ASSERT(joint_index < _skeleton->getNumJoints(), \"joint_index out of bounds\", dart::dynamics::Joint::ActuatorType::FORCE);\nreturn _skeleton->getJoint(joint_index)->getActuatorType();\n}\nstd::vector<dart::dynamics::Joint::ActuatorType> Robot::_actuator_types() const\n{\nstd::vector<dart::dynamics::Joint::ActuatorType> types;\nfor (size_t i = 0; i < _skeleton->getNumJoints(); ++i) {\ntypes.push_back(_skeleton->getJoint(i)->getActuatorType());\n}\nreturn types;\n}\nEigen::MatrixXd Robot::_jacobian(const Eigen::MatrixXd& full_jacobian, const std::vector<std::string>& dof_names) const\n{\nif (dof_names.empty())\nreturn full_jacobian;\nEigen::MatrixXd jac_ret(6, dof_names.size());\nfor (size_t i = 0; i < dof_names.size(); i++) {\nauto it = _dof_map.find(dof_names[i]);\nROBOT_DART_ASSERT(it != _dof_map.end(), \"_jacobian: \" + dof_names[i] + \" is not in dof_map\", Eigen::MatrixXd());\njac_ret.col(i) = full_jacobian.col(it->second);\n}\nreturn jac_ret;\n}\nEigen::MatrixXd Robot::_mass_matrix(const Eigen::MatrixXd& full_mass_matrix, const std::vector<std::string>& dof_names) const\n{\nif (dof_names.empty())\nreturn full_mass_matrix;\nEigen::MatrixXd M_ret(dof_names.size(), dof_names.size());\nfor (size_t i = 0; i < dof_names.size(); i++) {\nauto it = _dof_map.find(dof_names[i]);\nROBOT_DART_ASSERT(it != _dof_map.end(), \"mass_matrix: \" + dof_names[i] + \" is not in dof_map\", Eigen::MatrixXd());\nM_ret(i, i) = full_mass_matrix(it->second, it->second);\nfor (size_t j = i + 1; j < dof_names.size(); j++) {\nauto it2 = _dof_map.find(dof_names[j]);\nROBOT_DART_ASSERT(it2 != _dof_map.end(), \"mass_matrix: \" + dof_names[j] + \" is not in dof_map\", Eigen::MatrixXd());\nM_ret(i, j) = full_mass_matrix(it->second, it2->second);\nM_ret(j, i) = full_mass_matrix(it2->second, it->second);\n}\n}\nreturn M_ret;\n}\nstd::shared_ptr<Robot> Robot::create_box(const Eigen::Vector3d& dims, const Eigen::Isometry3d& tf, const std::string& type, double mass, const Eigen::Vector4d& color, const std::string& box_name)\n{\nEigen::Vector6d x;\nx.head<3>() = dart::math::logMap(tf.linear());\nx.tail<3>() = tf.translation();\nreturn create_box(dims, x, type, mass, color, box_name);\n}\nstd::shared_ptr<Robot> Robot::create_box(const Eigen::Vector3d& dims, const Eigen::Vector6d& pose, const std::string& type, double mass, const Eigen::Vector4d& color, const std::string& box_name)\n{\nROBOT_DART_ASSERT((dims.array() > 0.).all(), \"Dimensions should be bigger than zero!\", nullptr);\nROBOT_DART_ASSERT(mass > 0., \"Box mass should be bigger than zero!\", nullptr);\ndart::dynamics::SkeletonPtr box_skel = dart::dynamics::Skeleton::create(box_name);\n// Give the box a body\ndart::dynamics::BodyNodePtr body;\nif (type == \"free\")\nbody = box_skel->createJointAndBodyNodePair<dart::dynamics::FreeJoint>(nullptr).second;\nelse\nbody = box_skel->createJointAndBodyNodePair<dart::dynamics::WeldJoint>(nullptr).second;\nbody->setName(box_name);\n// Give the body a shape\nauto box = std::make_shared<dart::dynamics::BoxShape>(dims);\nauto box_node = body->createShapeNodeWith<dart::dynamics::VisualAspect,\ndart::dynamics::CollisionAspect, dart::dynamics::DynamicsAspect>(box);\nbox_node->getVisualAspect()->setColor(color);\n// Set up inertia\ndart::dynamics::Inertia inertia;\ninertia.setMass(mass);\ninertia.setMoment(box->computeInertia(mass));\nbody->setInertia(inertia);\n// Put the body into position\nauto robot = std::make_shared<Robot>(box_skel, box_name);\nif (type == \"free\") // free floating\nrobot->set_positions(pose);\nelse // fixed\n{\nEigen::Isometry3d T;\nT.linear() = dart::math::expMapRot(pose.head<3>());\nT.translation() = pose.tail<3>();\nbody->getParentJoint()->setTransformFromParentBodyNode(T);\n}\nreturn robot;\n}\nstd::shared_ptr<Robot> Robot::create_ellipsoid(const Eigen::Vector3d& dims, const Eigen::Isometry3d& tf, const std::string& type, double mass, const Eigen::Vector4d& color, const std::string& ellipsoid_name)\n{\nEigen::Vector6d x;\nx.head<3>() = dart::math::logMap(tf.linear());\nx.tail<3>() = tf.translation();\nreturn create_ellipsoid(dims, x, type, mass, color, ellipsoid_name);\n}\nstd::shared_ptr<Robot> Robot::create_ellipsoid(const Eigen::Vector3d& dims, const Eigen::Vector6d& pose, const std::string& type, double mass, const Eigen::Vector4d& color, const std::string& ellipsoid_name)\n{\nROBOT_DART_ASSERT((dims.array() > 0.).all(), \"Dimensions should be bigger than zero!\", nullptr);\nROBOT_DART_ASSERT(mass > 0., \"Box mass should be bigger than zero!\", nullptr);\ndart::dynamics::SkeletonPtr ellipsoid_skel = dart::dynamics::Skeleton::create(ellipsoid_name);\n// Give the ellipsoid a body\ndart::dynamics::BodyNodePtr body;\nif (type == \"free\")\nbody = ellipsoid_skel->createJointAndBodyNodePair<dart::dynamics::FreeJoint>(nullptr).second;\nelse\nbody = ellipsoid_skel->createJointAndBodyNodePair<dart::dynamics::WeldJoint>(nullptr).second;\nbody->setName(ellipsoid_name);\n// Give the body a shape\nauto ellipsoid = std::make_shared<dart::dynamics::EllipsoidShape>(dims);\nauto ellipsoid_node = body->createShapeNodeWith<dart::dynamics::VisualAspect,\ndart::dynamics::CollisionAspect, dart::dynamics::DynamicsAspect>(ellipsoid);\nellipsoid_node->getVisualAspect()->setColor(color);\n// Set up inertia\ndart::dynamics::Inertia inertia;\ninertia.setMass(mass);\ninertia.setMoment(ellipsoid->computeInertia(mass));\nbody->setInertia(inertia);\nauto robot = std::make_shared<Robot>(ellipsoid_skel, ellipsoid_name);\n// Put the body into position\nif (type == \"free\") // free floating\nrobot->set_positions(pose);\nelse // fixed\n{\nEigen::Isometry3d T;\nT.linear() = dart::math::expMapRot(pose.head<3>());\nT.translation() = pose.tail<3>();\nbody->getParentJoint()->setTransformFromParentBodyNode(T);\n}\nreturn robot;\n}\n} // namespace robot_dart\n
"},{"location":"api/robot_8hpp/","title":"File robot.hpp","text":"

FileList > robot_dart > robot.hpp

Go to the source code of this file

"},{"location":"api/robot_8hpp/#namespaces","title":"Namespaces","text":"Type Name namespace robot_dart namespace control"},{"location":"api/robot_8hpp/#classes","title":"Classes","text":"Type Name class Robot

The documentation for this class was generated from the following file robot_dart/robot.hpp

"},{"location":"api/robot_8hpp_source/","title":"File robot.hpp","text":"

File List > robot_dart > robot.hpp

Go to the documentation of this file

#ifndef ROBOT_DART_ROBOT_HPP\n#define ROBOT_DART_ROBOT_HPP\n#include <unordered_map>\n#include <robot_dart/utils.hpp>\nnamespace robot_dart {\nclass RobotDARTSimu;\nnamespace control {\nclass RobotControl;\n}\nclass Robot : public std::enable_shared_from_this<Robot> {\npublic:\nRobot(const std::string& model_file, const std::vector<std::pair<std::string, std::string>>& packages, const std::string& robot_name = \"robot\", bool is_urdf_string = false, bool cast_shadows = true);\nRobot(const std::string& model_file, const std::string& robot_name = \"robot\", bool is_urdf_string = false, bool cast_shadows = true);\nRobot(dart::dynamics::SkeletonPtr skeleton, const std::string& robot_name = \"robot\", bool cast_shadows = true);\nvirtual ~Robot() {}\nstd::shared_ptr<Robot> clone() const;\nstd::shared_ptr<Robot> clone_ghost(const std::string& ghost_name = \"ghost\", const Eigen::Vector4d& ghost_color = {0.3, 0.3, 0.3, 0.7}) const;\ndart::dynamics::SkeletonPtr skeleton();\ndart::dynamics::BodyNode* body_node(const std::string& body_name);\ndart::dynamics::BodyNode* body_node(size_t body_index);\ndart::dynamics::Joint* joint(const std::string& joint_name);\ndart::dynamics::Joint* joint(size_t joint_index);\ndart::dynamics::DegreeOfFreedom* dof(const std::string& dof_name);\ndart::dynamics::DegreeOfFreedom* dof(size_t dof_index);\nconst std::string& name() const;\n// to use the same urdf somewhere else\nconst std::string& model_filename() const { return _model_filename; }\nconst std::vector<std::pair<std::string, std::string>>& model_packages() const { return _packages; }\nvoid update(double t);\nvoid reinit_controllers();\nsize_t num_controllers() const;\nstd::vector<std::shared_ptr<control::RobotControl>> controllers() const;\nstd::vector<std::shared_ptr<control::RobotControl>> active_controllers() const;\nstd::shared_ptr<control::RobotControl> controller(size_t index) const;\nvoid add_controller(\nconst std::shared_ptr<control::RobotControl>& controller, double weight = 1.0);\nvoid remove_controller(const std::shared_ptr<control::RobotControl>& controller);\nvoid remove_controller(size_t index);\nvoid clear_controllers();\nvoid fix_to_world();\n// pose: Orientation-Position\nvoid free_from_world(const Eigen::Vector6d& pose = Eigen::Vector6d::Zero());\nbool fixed() const;\nbool free() const;\nvirtual void reset();\nvoid clear_external_forces();\nvoid clear_internal_forces();\nvoid reset_commands();\n// actuator type can be: torque, servo, velocity, passive, locked, mimic (only for completeness, use set_mimic to use this)\n// Be careful that actuator types are per joint and not per DoF\nvoid set_actuator_types(const std::string& type, const std::vector<std::string>& joint_names = {}, bool override_mimic = false, bool override_base = false);\nvoid set_actuator_type(const std::string& type, const std::string& joint_name, bool override_mimic = false, bool override_base = false);\nvoid set_mimic(const std::string& joint_name, const std::string& mimic_joint_name, double multiplier = 1., double offset = 0.);\nstd::string actuator_type(const std::string& joint_name) const;\nstd::vector<std::string> actuator_types(const std::vector<std::string>& joint_names = {}) const;\nvoid set_position_enforced(const std::vector<bool>& enforced, const std::vector<std::string>& dof_names = {});\nvoid set_position_enforced(bool enforced, const std::vector<std::string>& dof_names = {});\nstd::vector<bool> position_enforced(const std::vector<std::string>& dof_names = {}) const;\nvoid force_position_bounds();\nvoid set_damping_coeffs(const std::vector<double>& damps, const std::vector<std::string>& dof_names = {});\nvoid set_damping_coeffs(double damp, const std::vector<std::string>& dof_names = {});\nstd::vector<double> damping_coeffs(const std::vector<std::string>& dof_names = {}) const;\nvoid set_coulomb_coeffs(const std::vector<double>& cfrictions, const std::vector<std::string>& dof_names = {});\nvoid set_coulomb_coeffs(double cfriction, const std::vector<std::string>& dof_names = {});\nstd::vector<double> coulomb_coeffs(const std::vector<std::string>& dof_names = {}) const;\nvoid set_spring_stiffnesses(const std::vector<double>& stiffnesses, const std::vector<std::string>& dof_names = {});\nvoid set_spring_stiffnesses(double stiffness, const std::vector<std::string>& dof_names = {});\nstd::vector<double> spring_stiffnesses(const std::vector<std::string>& dof_names = {}) const;\n// the friction direction is in local frame\nvoid set_friction_dir(const std::string& body_name, const Eigen::Vector3d& direction);\nvoid set_friction_dir(size_t body_index, const Eigen::Vector3d& direction);\nEigen::Vector3d friction_dir(const std::string& body_name);\nEigen::Vector3d friction_dir(size_t body_index);\nvoid set_friction_coeff(const std::string& body_name, double value);\nvoid set_friction_coeff(size_t body_index, double value);\nvoid set_friction_coeffs(double value);\ndouble friction_coeff(const std::string& body_name);\ndouble friction_coeff(size_t body_index);\nvoid set_secondary_friction_coeff(const std::string& body_name, double value);\nvoid set_secondary_friction_coeff(size_t body_index, double value);\nvoid set_secondary_friction_coeffs(double value);\ndouble secondary_friction_coeff(const std::string& body_name);\ndouble secondary_friction_coeff(size_t body_index);\nvoid set_restitution_coeff(const std::string& body_name, double value);\nvoid set_restitution_coeff(size_t body_index, double value);\nvoid set_restitution_coeffs(double value);\ndouble restitution_coeff(const std::string& body_name);\ndouble restitution_coeff(size_t body_index);\nEigen::Isometry3d base_pose() const;\nEigen::Vector6d base_pose_vec() const;\nvoid set_base_pose(const Eigen::Isometry3d& tf);\nvoid set_base_pose(const Eigen::Vector6d& pose);\nsize_t num_dofs() const;\nsize_t num_joints() const;\nsize_t num_bodies() const;\nEigen::Vector3d com() const;\nEigen::Vector6d com_velocity() const;\nEigen::Vector6d com_acceleration() const;\nEigen::VectorXd positions(const std::vector<std::string>& dof_names = {}) const;\nvoid set_positions(const Eigen::VectorXd& positions, const std::vector<std::string>& dof_names = {});\nEigen::VectorXd position_lower_limits(const std::vector<std::string>& dof_names = {}) const;\nvoid set_position_lower_limits(const Eigen::VectorXd& positions, const std::vector<std::string>& dof_names = {});\nEigen::VectorXd position_upper_limits(const std::vector<std::string>& dof_names = {}) const;\nvoid set_position_upper_limits(const Eigen::VectorXd& positions, const std::vector<std::string>& dof_names = {});\nEigen::VectorXd velocities(const std::vector<std::string>& dof_names = {}) const;\nvoid set_velocities(const Eigen::VectorXd& velocities, const std::vector<std::string>& dof_names = {});\nEigen::VectorXd velocity_lower_limits(const std::vector<std::string>& dof_names = {}) const;\nvoid set_velocity_lower_limits(const Eigen::VectorXd& velocities, const std::vector<std::string>& dof_names = {});\nEigen::VectorXd velocity_upper_limits(const std::vector<std::string>& dof_names = {}) const;\nvoid set_velocity_upper_limits(const Eigen::VectorXd& velocities, const std::vector<std::string>& dof_names = {});\nEigen::VectorXd accelerations(const std::vector<std::string>& dof_names = {}) const;\nvoid set_accelerations(const Eigen::VectorXd& accelerations, const std::vector<std::string>& dof_names = {});\nEigen::VectorXd acceleration_lower_limits(const std::vector<std::string>& dof_names = {}) const;\nvoid set_acceleration_lower_limits(const Eigen::VectorXd& accelerations, const std::vector<std::string>& dof_names = {});\nEigen::VectorXd acceleration_upper_limits(const std::vector<std::string>& dof_names = {}) const;\nvoid set_acceleration_upper_limits(const Eigen::VectorXd& accelerations, const std::vector<std::string>& dof_names = {});\nEigen::VectorXd forces(const std::vector<std::string>& dof_names = {}) const;\nvoid set_forces(const Eigen::VectorXd& forces, const std::vector<std::string>& dof_names = {});\nEigen::VectorXd force_lower_limits(const std::vector<std::string>& dof_names = {}) const;\nvoid set_force_lower_limits(const Eigen::VectorXd& forces, const std::vector<std::string>& dof_names = {});\nEigen::VectorXd force_upper_limits(const std::vector<std::string>& dof_names = {}) const;\nvoid set_force_upper_limits(const Eigen::VectorXd& forces, const std::vector<std::string>& dof_names = {});\nEigen::VectorXd commands(const std::vector<std::string>& dof_names = {}) const;\nvoid set_commands(const Eigen::VectorXd& commands, const std::vector<std::string>& dof_names = {});\nstd::pair<Eigen::Vector6d, Eigen::Vector6d> force_torque(size_t joint_index) const;\nvoid set_external_force(const std::string& body_name, const Eigen::Vector3d& force, const Eigen::Vector3d& offset = Eigen::Vector3d::Zero(), bool force_local = false, bool offset_local = true);\nvoid set_external_force(size_t body_index, const Eigen::Vector3d& force, const Eigen::Vector3d& offset = Eigen::Vector3d::Zero(), bool force_local = false, bool offset_local = true);\nvoid add_external_force(const std::string& body_name, const Eigen::Vector3d& force, const Eigen::Vector3d& offset = Eigen::Vector3d::Zero(), bool force_local = false, bool offset_local = true);\nvoid add_external_force(size_t body_index, const Eigen::Vector3d& force, const Eigen::Vector3d& offset = Eigen::Vector3d::Zero(), bool force_local = false, bool offset_local = true);\nvoid set_external_torque(const std::string& body_name, const Eigen::Vector3d& torque, bool local = false);\nvoid set_external_torque(size_t body_index, const Eigen::Vector3d& torque, bool local = false);\nvoid add_external_torque(const std::string& body_name, const Eigen::Vector3d& torque, bool local = false);\nvoid add_external_torque(size_t body_index, const Eigen::Vector3d& torque, bool local = false);\nEigen::Vector6d external_forces(const std::string& body_name) const;\nEigen::Vector6d external_forces(size_t body_index) const;\nEigen::Isometry3d body_pose(const std::string& body_name) const;\nEigen::Isometry3d body_pose(size_t body_index) const;\nEigen::Vector6d body_pose_vec(const std::string& body_name) const;\nEigen::Vector6d body_pose_vec(size_t body_index) const;\nEigen::Vector6d body_velocity(const std::string& body_name) const;\nEigen::Vector6d body_velocity(size_t body_index) const;\nEigen::Vector6d body_acceleration(const std::string& body_name) const;\nEigen::Vector6d body_acceleration(size_t body_index) const;\nstd::vector<std::string> body_names() const;\nstd::string body_name(size_t body_index) const;\nvoid set_body_name(size_t body_index, const std::string& body_name);\nsize_t body_index(const std::string& body_name) const;\ndouble body_mass(const std::string& body_name) const;\ndouble body_mass(size_t body_index) const;\nvoid set_body_mass(const std::string& body_name, double mass);\nvoid set_body_mass(size_t body_index, double mass);\nvoid add_body_mass(const std::string& body_name, double mass);\nvoid add_body_mass(size_t body_index, double mass);\nEigen::MatrixXd jacobian(const std::string& body_name, const std::vector<std::string>& dof_names = {}) const;\nEigen::MatrixXd jacobian_deriv(const std::string& body_name, const std::vector<std::string>& dof_names = {}) const;\nEigen::MatrixXd com_jacobian(const std::vector<std::string>& dof_names = {}) const;\nEigen::MatrixXd com_jacobian_deriv(const std::vector<std::string>& dof_names = {}) const;\nEigen::MatrixXd mass_matrix(const std::vector<std::string>& dof_names = {}) const;\nEigen::MatrixXd aug_mass_matrix(const std::vector<std::string>& dof_names = {}) const;\nEigen::MatrixXd inv_mass_matrix(const std::vector<std::string>& dof_names = {}) const;\nEigen::MatrixXd inv_aug_mass_matrix(const std::vector<std::string>& dof_names = {}) const;\nEigen::VectorXd coriolis_forces(const std::vector<std::string>& dof_names = {}) const;\nEigen::VectorXd gravity_forces(const std::vector<std::string>& dof_names = {}) const;\nEigen::VectorXd coriolis_gravity_forces(const std::vector<std::string>& dof_names = {}) const;\nEigen::VectorXd constraint_forces(const std::vector<std::string>& dof_names = {}) const;\n// Get only the part of vector for DOFs in dof_names\nEigen::VectorXd vec_dof(const Eigen::VectorXd& vec, const std::vector<std::string>& dof_names) const;\nvoid update_joint_dof_maps();\nconst std::unordered_map<std::string, size_t>& dof_map() const;\nconst std::unordered_map<std::string, size_t>& joint_map() const;\nstd::vector<std::string> dof_names(bool filter_mimics = false, bool filter_locked = false, bool filter_passive = false) const;\nstd::vector<std::string> mimic_dof_names() const;\nstd::vector<std::string> locked_dof_names() const;\nstd::vector<std::string> passive_dof_names() const;\nstd::string dof_name(size_t dof_index) const;\nsize_t dof_index(const std::string& dof_name) const;\nstd::vector<std::string> joint_names() const;\nstd::string joint_name(size_t joint_index) const;\nvoid set_joint_name(size_t joint_index, const std::string& joint_name);\nsize_t joint_index(const std::string& joint_name) const;\n// MATERIAL_COLOR, COLOR_INDEX, SHAPE_COLOR\n// This applies only to MeshShapes. Color mode can be: \"material\", \"assimp\", or \"aspect\"\n// \"material\" -> uses the color of the material in the mesh file\n// \"assimp\" -> uses the color specified by aiMesh::mColor\n// \"aspect\" -> uses the color defined in the VisualAspect (if not changed, this is what read from the URDF)\nvoid set_color_mode(const std::string& color_mode);\nvoid set_color_mode(const std::string& color_mode, const std::string& body_name);\nvoid set_self_collision(bool enable_self_collisions = true, bool enable_adjacent_collisions = false);\nbool self_colliding() const;\n// This returns true if self colliding AND adjacent checks are on\nbool adjacent_colliding() const;\n// GUI options\nvoid set_cast_shadows(bool cast_shadows = true);\nbool cast_shadows() const;\nvoid set_ghost(bool ghost = true);\nbool ghost() const;\nvoid set_draw_axis(const std::string& body_name, double size = 0.25);\nvoid remove_all_drawing_axis();\nconst std::vector<std::pair<dart::dynamics::BodyNode*, double>>& drawing_axes() const;\n// helper functions\nstatic std::shared_ptr<Robot> create_box(const Eigen::Vector3d& dims,\nconst Eigen::Isometry3d& tf, const std::string& type = \"free\",\ndouble mass = 1.0, const Eigen::Vector4d& color = dart::Color::Red(1.0),\nconst std::string& box_name = \"box\");\n// pose: 6D log_map\nstatic std::shared_ptr<Robot> create_box(const Eigen::Vector3d& dims,\nconst Eigen::Vector6d& pose = Eigen::Vector6d::Zero(), const std::string& type = \"free\",\ndouble mass = 1.0, const Eigen::Vector4d& color = dart::Color::Red(1.0),\nconst std::string& box_name = \"box\");\nstatic std::shared_ptr<Robot> create_ellipsoid(const Eigen::Vector3d& dims,\nconst Eigen::Isometry3d& tf, const std::string& type = \"free\",\ndouble mass = 1.0, const Eigen::Vector4d& color = dart::Color::Red(1.0),\nconst std::string& ellipsoid_name = \"ellipsoid\");\n// pose: 6D log_map\nstatic std::shared_ptr<Robot> create_ellipsoid(const Eigen::Vector3d& dims,\nconst Eigen::Vector6d& pose = Eigen::Vector6d::Zero(), const std::string& type = \"free\",\ndouble mass = 1.0, const Eigen::Vector4d& color = dart::Color::Red(1.0),\nconst std::string& ellipsoid_name = \"ellipsoid\");\nprotected:\nstd::string _get_path(const std::string& filename) const;\ndart::dynamics::SkeletonPtr _load_model(const std::string& filename, const std::vector<std::pair<std::string, std::string>>& packages = std::vector<std::pair<std::string, std::string>>(), bool is_urdf_string = false);\nvoid _set_color_mode(dart::dynamics::MeshShape::ColorMode color_mode, dart::dynamics::SkeletonPtr skel);\nvoid _set_color_mode(dart::dynamics::MeshShape::ColorMode color_mode, dart::dynamics::ShapeNode* sn);\nvoid _set_actuator_type(size_t joint_index, dart::dynamics::Joint::ActuatorType type, bool override_mimic = false, bool override_base = false);\nvoid _set_actuator_types(const std::vector<dart::dynamics::Joint::ActuatorType>& types, bool override_mimic = false, bool override_base = false);\nvoid _set_actuator_types(dart::dynamics::Joint::ActuatorType type, bool override_mimic = false, bool override_base = false);\ndart::dynamics::Joint::ActuatorType _actuator_type(size_t joint_index) const;\nstd::vector<dart::dynamics::Joint::ActuatorType> _actuator_types() const;\nEigen::MatrixXd _jacobian(const Eigen::MatrixXd& full_jacobian, const std::vector<std::string>& dof_names) const;\nEigen::MatrixXd _mass_matrix(const Eigen::MatrixXd& full_mass_matrix, const std::vector<std::string>& dof_names) const;\nvirtual void _post_addition(RobotDARTSimu*) {}\nvirtual void _post_removal(RobotDARTSimu*) {}\nfriend class RobotDARTSimu;\nstd::string _robot_name;\nstd::string _model_filename;\nstd::vector<std::pair<std::string, std::string>> _packages;\ndart::dynamics::SkeletonPtr _skeleton;\nstd::vector<std::shared_ptr<control::RobotControl>> _controllers;\nstd::unordered_map<std::string, size_t> _dof_map, _joint_map;\nbool _cast_shadows;\nbool _is_ghost;\nstd::vector<std::pair<dart::dynamics::BodyNode*, double>> _axis_shapes;\n};\n} // namespace robot_dart\n#endif\n
"},{"location":"api/dir_1a1ccbdd0954eb7721b1a771872472c9/","title":"Dir robot_dart/control","text":"

FileList > control

"},{"location":"api/dir_1a1ccbdd0954eb7721b1a771872472c9/#files","title":"Files","text":"Type Name file pd_control.cpp file pd_control.hpp file policy_control.hpp file robot_control.cpp file robot_control.hpp file simple_control.cpp file simple_control.hpp

The documentation for this class was generated from the following file robot_dart/control/

"},{"location":"api/pd__control_8cpp/","title":"File pd_control.cpp","text":"

FileList > control > pd_control.cpp

Go to the source code of this file

"},{"location":"api/pd__control_8cpp/#namespaces","title":"Namespaces","text":"Type Name namespace robot_dart namespace control

The documentation for this class was generated from the following file robot_dart/control/pd_control.cpp

"},{"location":"api/pd__control_8cpp_source/","title":"File pd_control.cpp","text":"

File List > control > pd_control.cpp

Go to the documentation of this file

#include \"pd_control.hpp\"\n#include \"robot_dart/robot.hpp\"\n#include \"robot_dart/utils.hpp\"\n#include \"robot_dart/utils_headers_dart_dynamics.hpp\"\nnamespace robot_dart {\nnamespace control {\nPDControl::PDControl() : RobotControl() {}\nPDControl::PDControl(const Eigen::VectorXd& ctrl, bool full_control, bool use_angular_errors) : RobotControl(ctrl, full_control), _use_angular_errors(use_angular_errors) {}\nPDControl::PDControl(const Eigen::VectorXd& ctrl, const std::vector<std::string>& controllable_dofs, bool use_angular_errors) : RobotControl(ctrl, controllable_dofs), _use_angular_errors(use_angular_errors) {}\nvoid PDControl::configure()\n{\nif (_ctrl.size() == _control_dof)\n_active = true;\nif (_Kp.size() == 0)\nset_pd(10., 0.1);\n}\nEigen::VectorXd PDControl::calculate(double)\n{\nROBOT_DART_ASSERT(_control_dof == _ctrl.size(), \"PDControl: Controller parameters size is not the same as DOFs of the robot\", Eigen::VectorXd::Zero(_control_dof));\nauto robot = _robot.lock();\nEigen::VectorXd dq = robot->velocities(_controllable_dofs);\nEigen::VectorXd error;\nif (!_use_angular_errors) {\nEigen::VectorXd q = robot->positions(_controllable_dofs);\nerror = _ctrl - q;\n}\nelse {\nerror = Eigen::VectorXd::Zero(_control_dof);\nstd::unordered_map<size_t, Eigen::VectorXd> joint_vals, joint_desired, errors;\nfor (int i = 0; i < _control_dof; ++i) {\nauto dof = robot->dof(_controllable_dofs[i]);\nsize_t joint_index = dof->getJoint()->getJointIndexInSkeleton();\nif (joint_vals.find(joint_index) == joint_vals.end()) {\njoint_vals[joint_index] = dof->getJoint()->getPositions();\njoint_desired[joint_index] = dof->getJoint()->getPositions();\n}\njoint_desired[joint_index][dof->getIndexInJoint()] = _ctrl[i];\n}\nfor (int i = 0; i < _control_dof; ++i) {\nauto dof = robot->dof(_controllable_dofs[i]);\nsize_t joint_index = dof->getJoint()->getJointIndexInSkeleton();\nsize_t dof_index_in_joint = dof->getIndexInJoint();\nEigen::VectorXd val;\nif (errors.find(joint_index) == errors.end()) {\nval = Eigen::VectorXd(dof->getJoint()->getNumDofs());\nstd::string joint_type = robot->dof(_controllable_dofs[i])->getJoint()->getType();\nif (joint_type == dart::dynamics::RevoluteJoint::getStaticType()) {\nval[dof_index_in_joint] = _angle_dist(_ctrl[i], joint_vals[joint_index][dof_index_in_joint]);\n}\nelse if (joint_type == dart::dynamics::BallJoint::getStaticType()) {\nEigen::Matrix3d R_desired = dart::math::expMapRot(joint_desired[joint_index]);\nEigen::Matrix3d R_current = dart::math::expMapRot(joint_vals[joint_index]);\nval = dart::math::logMap(R_desired * R_current.transpose());\n}\nelse if (joint_type == dart::dynamics::EulerJoint::getStaticType()) {\n// TO-DO: Check if this is 100% correct\nfor (size_t d = 0; d < dof->getJoint()->getNumDofs(); d++)\nval[d] = _angle_dist(joint_desired[joint_index][d], joint_vals[joint_index][d]);\n}\nelse if (joint_type == dart::dynamics::FreeJoint::getStaticType()) {\nauto free_joint = static_cast<dart::dynamics::FreeJoint*>(dof->getJoint());\nEigen::Isometry3d tf_desired = free_joint->convertToTransform(joint_desired[joint_index]);\nEigen::Isometry3d tf_current = free_joint->convertToTransform(joint_vals[joint_index]);\nval.tail(3) = tf_desired.translation() - tf_current.translation();\nval.head(3) = dart::math::logMap(tf_desired.linear().matrix() * tf_current.linear().matrix().transpose());\n}\nelse {\nval[dof_index_in_joint] = _ctrl[i] - joint_vals[joint_index][dof_index_in_joint];\n}\nerrors[joint_index] = val;\n}\nelse\nval = errors[joint_index];\nerror(i) = val[dof_index_in_joint];\n}\n}\nEigen::VectorXd commands = _Kp.array() * error.array() - _Kd.array() * dq.array();\nreturn commands;\n}\nvoid PDControl::set_pd(double Kp, double Kd)\n{\n_Kp = Eigen::VectorXd::Constant(_control_dof, Kp);\n_Kd = Eigen::VectorXd::Constant(_control_dof, Kd);\n}\nvoid PDControl::set_pd(const Eigen::VectorXd& Kp, const Eigen::VectorXd& Kd)\n{\nROBOT_DART_ASSERT(Kp.size() == _control_dof, \"PDControl: The Kp size is not the same as the DOFs!\", );\nROBOT_DART_ASSERT(Kd.size() == _control_dof, \"PDControl: The Kd size is not the same as the DOFs!\", );\n_Kp = Kp;\n_Kd = Kd;\n}\nstd::pair<Eigen::VectorXd, Eigen::VectorXd> PDControl::pd() const\n{\nreturn std::make_pair(_Kp, _Kd);\n}\nbool PDControl::using_angular_errors() const { return _use_angular_errors; }\nvoid PDControl::set_use_angular_errors(bool enable) { _use_angular_errors = enable; }\nstd::shared_ptr<RobotControl> PDControl::clone() const\n{\nreturn std::make_shared<PDControl>(*this);\n}\ndouble PDControl::_angle_dist(double target, double current)\n{\ndouble theta = target - current;\nwhile (theta < -M_PI)\ntheta += 2 * M_PI;\nwhile (theta > M_PI)\ntheta -= 2 * M_PI;\nreturn theta;\n}\n} // namespace control\n} // namespace robot_dart\n
"},{"location":"api/pd__control_8hpp/","title":"File pd_control.hpp","text":"

FileList > control > pd_control.hpp

Go to the source code of this file

"},{"location":"api/pd__control_8hpp/#namespaces","title":"Namespaces","text":"Type Name namespace robot_dart namespace control"},{"location":"api/pd__control_8hpp/#classes","title":"Classes","text":"Type Name class PDControl

The documentation for this class was generated from the following file robot_dart/control/pd_control.hpp

"},{"location":"api/pd__control_8hpp_source/","title":"File pd_control.hpp","text":"

File List > control > pd_control.hpp

Go to the documentation of this file

#ifndef ROBOT_DART_CONTROL_PD_CONTROL\n#define ROBOT_DART_CONTROL_PD_CONTROL\n#include <utility>\n#include <robot_dart/control/robot_control.hpp>\n#include <robot_dart/robot.hpp>\nnamespace robot_dart {\nnamespace control {\nclass PDControl : public RobotControl {\npublic:\nPDControl();\nPDControl(const Eigen::VectorXd& ctrl, bool full_control = false, bool use_angular_errors = true);\nPDControl(const Eigen::VectorXd& ctrl, const std::vector<std::string>& controllable_dofs, bool use_angular_errors = true);\nvoid configure() override;\nEigen::VectorXd calculate(double) override;\nvoid set_pd(double p, double d);\nvoid set_pd(const Eigen::VectorXd& p, const Eigen::VectorXd& d);\nstd::pair<Eigen::VectorXd, Eigen::VectorXd> pd() const;\nbool using_angular_errors() const;\nvoid set_use_angular_errors(bool enable = true);\nstd::shared_ptr<RobotControl> clone() const override;\nprotected:\nEigen::VectorXd _Kp;\nEigen::VectorXd _Kd;\nbool _use_angular_errors;\nstatic double _angle_dist(double target, double current);\n};\n} // namespace control\n} // namespace robot_dart\n#endif\n
"},{"location":"api/policy__control_8hpp/","title":"File policy_control.hpp","text":"

FileList > control > policy_control.hpp

Go to the source code of this file

"},{"location":"api/policy__control_8hpp/#namespaces","title":"Namespaces","text":"Type Name namespace robot_dart namespace control"},{"location":"api/policy__control_8hpp/#classes","title":"Classes","text":"Type Name class PolicyControl <typename Policy>

The documentation for this class was generated from the following file robot_dart/control/policy_control.hpp

"},{"location":"api/policy__control_8hpp_source/","title":"File policy_control.hpp","text":"

File List > control > policy_control.hpp

Go to the documentation of this file

#ifndef ROBOT_DART_CONTROL_POLICY_CONTROL\n#define ROBOT_DART_CONTROL_POLICY_CONTROL\n#include <robot_dart/control/robot_control.hpp>\n#include <robot_dart/robot.hpp>\nnamespace robot_dart {\nnamespace control {\ntemplate <typename Policy>\nclass PolicyControl : public RobotControl {\npublic:\nPolicyControl() : RobotControl() {}\nPolicyControl(double dt, const Eigen::VectorXd& ctrl, bool full_control = false) : RobotControl(ctrl, full_control), _dt(dt), _first(true), _full_dt(false) {}\nPolicyControl(const Eigen::VectorXd& ctrl, bool full_control = false) : RobotControl(ctrl, full_control), _dt(0.), _first(true), _full_dt(true) {}\nPolicyControl(double dt, const Eigen::VectorXd& ctrl, const std::vector<std::string>& controllable_dofs) : RobotControl(ctrl, controllable_dofs), _dt(dt), _first(true), _full_dt(false) {}\nPolicyControl(const Eigen::VectorXd& ctrl, const std::vector<std::string>& controllable_dofs) : RobotControl(ctrl, controllable_dofs), _dt(0.), _first(true), _full_dt(true) {}\nvoid configure() override\n{\n_policy.set_params(_ctrl);\nif (_policy.output_size() == _control_dof)\n_active = true;\nelse\nROBOT_DART_WARNING(_policy.output_size() != _control_dof, \"Control DoF != Policy output size. Policy is not active.\");\nauto robot = _robot.lock();\nif (_full_dt)\n_dt = robot->skeleton()->getTimeStep();\n_first = true;\n_i = 0;\n_threshold = -robot->skeleton()->getTimeStep() * 0.5;\n}\nvoid set_h_params(const Eigen::VectorXd& h_params)\n{\n_policy.set_h_params(h_params);\n}\nEigen::VectorXd h_params() const\n{\nreturn _policy.h_params();\n}\nEigen::VectorXd calculate(double t) override\n{\nROBOT_DART_ASSERT(_control_dof == _policy.output_size(), \"PolicyControl: Policy output size is not the same as DOFs of the robot\", Eigen::VectorXd::Zero(_control_dof));\nif (_first || _full_dt || (t - _prev_time - _dt) >= _threshold) {\n_prev_commands = _policy.query(_robot.lock(), t);\n_first = false;\n_prev_time = t;\n_i++;\n}\nreturn _prev_commands;\n}\nstd::shared_ptr<RobotControl> clone() const override\n{\nreturn std::make_shared<PolicyControl>(*this);\n}\nprotected:\nint _i;\nPolicy _policy;\ndouble _dt, _prev_time, _threshold;\nEigen::VectorXd _prev_commands;\nbool _first, _full_dt;\n};\n} // namespace control\n} // namespace robot_dart\n#endif\n
"},{"location":"api/robot__control_8cpp/","title":"File robot_control.cpp","text":"

FileList > control > robot_control.cpp

Go to the source code of this file

"},{"location":"api/robot__control_8cpp/#namespaces","title":"Namespaces","text":"Type Name namespace robot_dart namespace control

The documentation for this class was generated from the following file robot_dart/control/robot_control.cpp

"},{"location":"api/robot__control_8cpp_source/","title":"File robot_control.cpp","text":"

File List > control > robot_control.cpp

Go to the documentation of this file

#include \"robot_control.hpp\"\n#include \"robot_dart/robot.hpp\"\n#include \"robot_dart/utils.hpp\"\n#include \"robot_dart/utils_headers_dart_dynamics.hpp\"\nnamespace robot_dart {\nnamespace control {\nRobotControl::RobotControl() : _weight(1.), _active(false), _check_free(true) {}\nRobotControl::RobotControl(const Eigen::VectorXd& ctrl, const std::vector<std::string>& controllable_dofs) : _ctrl(ctrl), _weight(1.), _active(false), _check_free(false), _controllable_dofs(controllable_dofs) {}\nRobotControl::RobotControl(const Eigen::VectorXd& ctrl, bool full_control) : _ctrl(ctrl), _weight(1.), _active(false), _check_free(!full_control) {}\nvoid RobotControl::set_parameters(const Eigen::VectorXd& ctrl)\n{\n_ctrl = ctrl;\n_active = false;\ninit();\n}\nconst Eigen::VectorXd& RobotControl::parameters() const\n{\nreturn _ctrl;\n}\nvoid RobotControl::init()\n{\nROBOT_DART_ASSERT(_robot.use_count() > 0, \"RobotControl: parent robot should be initialized; use set_robot()\", );\nauto robot = _robot.lock();\n_dof = robot->skeleton()->getNumDofs();\nif (_check_free && robot->free()) {\nauto names = robot->dof_names(true, true, true);\n_controllable_dofs = std::vector<std::string>(names.begin() + 6, names.end());\n}\nelse if (_controllable_dofs.empty()) {\n// we cannot control mimic, locked and passive joints\n_controllable_dofs = robot->dof_names(true, true, true);\n}\n_control_dof = _controllable_dofs.size();\nconfigure();\n}\nvoid RobotControl::set_robot(const std::shared_ptr<Robot>& robot)\n{\n_robot = robot;\n}\nstd::shared_ptr<Robot> RobotControl::robot() const\n{\nreturn _robot.lock();\n}\nvoid RobotControl::activate(bool enable)\n{\n_active = false;\nif (enable) {\ninit();\n}\n}\nbool RobotControl::active() const\n{\nreturn _active;\n}\nconst std::vector<std::string>& RobotControl::controllable_dofs() const { return _controllable_dofs; }\ndouble RobotControl::weight() const\n{\nreturn _weight;\n}\nvoid RobotControl::set_weight(double weight)\n{\n_weight = weight;\n}\n} // namespace control\n} // namespace robot_dart\n
"},{"location":"api/robot__control_8hpp/","title":"File robot_control.hpp","text":"

FileList > control > robot_control.hpp

Go to the source code of this file

"},{"location":"api/robot__control_8hpp/#namespaces","title":"Namespaces","text":"Type Name namespace robot_dart namespace control"},{"location":"api/robot__control_8hpp/#classes","title":"Classes","text":"Type Name class RobotControl

The documentation for this class was generated from the following file robot_dart/control/robot_control.hpp

"},{"location":"api/robot__control_8hpp_source/","title":"File robot_control.hpp","text":"

File List > control > robot_control.hpp

Go to the documentation of this file

#ifndef ROBOT_DART_CONTROL_ROBOT_CONTROL\n#define ROBOT_DART_CONTROL_ROBOT_CONTROL\n#include <robot_dart/utils.hpp>\n#include <memory>\n#include <vector>\nnamespace robot_dart {\nclass Robot;\nnamespace control {\nclass RobotControl {\npublic:\nRobotControl();\nRobotControl(const Eigen::VectorXd& ctrl, bool full_control = false);\nRobotControl(const Eigen::VectorXd& ctrl, const std::vector<std::string>& controllable_dofs);\nvirtual ~RobotControl() {}\nvoid set_parameters(const Eigen::VectorXd& ctrl);\nconst Eigen::VectorXd& parameters() const;\nvoid init();\nvoid set_robot(const std::shared_ptr<Robot>& robot);\nstd::shared_ptr<Robot> robot() const;\nvoid activate(bool enable = true);\nbool active() const;\nconst std::vector<std::string>& controllable_dofs() const;\ndouble weight() const;\nvoid set_weight(double weight);\nvirtual void configure() = 0;\n// TO-DO: Maybe make this const?\nvirtual Eigen::VectorXd calculate(double t) = 0;\nvirtual std::shared_ptr<RobotControl> clone() const = 0;\nprotected:\nstd::weak_ptr<Robot> _robot;\nEigen::VectorXd _ctrl;\ndouble _weight;\nbool _active, _check_free = false;\nint _dof, _control_dof;\nstd::vector<std::string> _controllable_dofs;\n};\n} // namespace control\n} // namespace robot_dart\n#endif\n
"},{"location":"api/simple__control_8cpp/","title":"File simple_control.cpp","text":"

FileList > control > simple_control.cpp

Go to the source code of this file

"},{"location":"api/simple__control_8cpp/#namespaces","title":"Namespaces","text":"Type Name namespace robot_dart namespace control

The documentation for this class was generated from the following file robot_dart/control/simple_control.cpp

"},{"location":"api/simple__control_8cpp_source/","title":"File simple_control.cpp","text":"

File List > control > simple_control.cpp

Go to the documentation of this file

#include \"simple_control.hpp\"\n#include \"robot_dart/robot.hpp\"\n#include \"robot_dart/utils.hpp\"\nnamespace robot_dart {\nnamespace control {\nSimpleControl::SimpleControl() : RobotControl() {}\nSimpleControl::SimpleControl(const Eigen::VectorXd& ctrl, bool full_control) : RobotControl(ctrl, full_control) {}\nSimpleControl::SimpleControl(const Eigen::VectorXd& ctrl, const std::vector<std::string>& controllable_dofs) : RobotControl(ctrl, controllable_dofs) {}\nvoid SimpleControl::configure()\n{\nif (_ctrl.size() == _control_dof)\n_active = true;\n}\nEigen::VectorXd SimpleControl::calculate(double)\n{\nROBOT_DART_ASSERT(_control_dof == _ctrl.size(), \"SimpleControl: Controller parameters size is not the same as DOFs of the robot\", Eigen::VectorXd::Zero(_control_dof));\nreturn _ctrl;\n}\nstd::shared_ptr<RobotControl> SimpleControl::clone() const\n{\nreturn std::make_shared<SimpleControl>(*this);\n}\n} // namespace control\n} // namespace robot_dart\n
"},{"location":"api/simple__control_8hpp/","title":"File simple_control.hpp","text":"

FileList > control > simple_control.hpp

Go to the source code of this file

"},{"location":"api/simple__control_8hpp/#namespaces","title":"Namespaces","text":"Type Name namespace robot_dart namespace control"},{"location":"api/simple__control_8hpp/#classes","title":"Classes","text":"Type Name class SimpleControl

The documentation for this class was generated from the following file robot_dart/control/simple_control.hpp

"},{"location":"api/simple__control_8hpp_source/","title":"File simple_control.hpp","text":"

File List > control > simple_control.hpp

Go to the documentation of this file

#ifndef ROBOT_DART_CONTROL_SIMPLE_CONTROL\n#define ROBOT_DART_CONTROL_SIMPLE_CONTROL\n#include <robot_dart/control/robot_control.hpp>\nnamespace robot_dart {\nnamespace control {\nclass SimpleControl : public RobotControl {\npublic:\nSimpleControl();\nSimpleControl(const Eigen::VectorXd& ctrl, bool full_control = false);\nSimpleControl(const Eigen::VectorXd& ctrl, const std::vector<std::string>& controllable_dofs);\nvoid configure() override;\nEigen::VectorXd calculate(double) override;\nstd::shared_ptr<RobotControl> clone() const override;\n};\n} // namespace control\n} // namespace robot_dart\n#endif\n
"},{"location":"api/dir_6a9d4b7ec29c938d1d9a486c655cfc8a/","title":"Dir robot_dart/gui","text":"

FileList > gui

"},{"location":"api/dir_6a9d4b7ec29c938d1d9a486c655cfc8a/#files","title":"Files","text":"Type Name file base.hpp file helper.cpp file helper.hpp file stb_image_write.h"},{"location":"api/dir_6a9d4b7ec29c938d1d9a486c655cfc8a/#directories","title":"Directories","text":"Type Name dir magnum

The documentation for this class was generated from the following file robot_dart/gui/

"},{"location":"api/base_8hpp/","title":"File base.hpp","text":"

FileList > gui > base.hpp

Go to the source code of this file

"},{"location":"api/base_8hpp/#namespaces","title":"Namespaces","text":"Type Name namespace robot_dart namespace gui"},{"location":"api/base_8hpp/#classes","title":"Classes","text":"Type Name class Base

The documentation for this class was generated from the following file robot_dart/gui/base.hpp

"},{"location":"api/base_8hpp_source/","title":"File base.hpp","text":"

File List > gui > base.hpp

Go to the documentation of this file

#ifndef ROBOT_DART_GUI_BASE_HPP\n#define ROBOT_DART_GUI_BASE_HPP\n#include <robot_dart/gui/helper.hpp>\nnamespace robot_dart {\nclass RobotDARTSimu;\nnamespace gui {\nclass Base {\npublic:\nBase() {}\nvirtual ~Base() {}\nvirtual void set_simu(RobotDARTSimu* simu) { _simu = simu; }\nconst RobotDARTSimu* simu() const { return _simu; }\nvirtual bool done() const { return false; }\nvirtual void refresh() {}\nvirtual void set_render_period(double) {}\nvirtual void set_enable(bool) {}\nvirtual void set_fps(int) {}\nvirtual Image image() { return Image(); }\nvirtual GrayscaleImage depth_image() { return GrayscaleImage(); }\nvirtual GrayscaleImage raw_depth_image() { return GrayscaleImage(); }\nvirtual DepthImage depth_array() { return DepthImage(); }\nvirtual size_t width() const { return 0; }\nvirtual size_t height() const { return 0; }\nprotected:\nRobotDARTSimu* _simu = nullptr;\n};\n} // namespace gui\n} // namespace robot_dart\n#endif\n
"},{"location":"api/helper_8cpp/","title":"File helper.cpp","text":"

FileList > gui > helper.cpp

Go to the source code of this file

"},{"location":"api/helper_8cpp/#namespaces","title":"Namespaces","text":"Type Name namespace robot_dart namespace gui"},{"location":"api/helper_8cpp/#macros","title":"Macros","text":"Type Name define STB_IMAGE_WRITE_IMPLEMENTATION"},{"location":"api/helper_8cpp/#macro-definition-documentation","title":"Macro Definition Documentation","text":""},{"location":"api/helper_8cpp/#define-stb_image_write_implementation","title":"define STB_IMAGE_WRITE_IMPLEMENTATION","text":"
#define STB_IMAGE_WRITE_IMPLEMENTATION \n

The documentation for this class was generated from the following file robot_dart/gui/helper.cpp

"},{"location":"api/helper_8cpp_source/","title":"File helper.cpp","text":"

File List > gui > helper.cpp

Go to the documentation of this file

#include \"helper.hpp\"\n#define STB_IMAGE_WRITE_IMPLEMENTATION\n#include \"stb_image_write.h\"\nnamespace robot_dart {\nnamespace gui {\nvoid save_png_image(const std::string& filename, const Image& rgb)\n{\nauto ends_with = [](const std::string& value, const std::string& ending) {\nif (ending.size() > value.size())\nreturn false;\nreturn std::equal(ending.rbegin(), ending.rend(), value.rbegin());\n};\nstd::string png = \".png\";\nif (ends_with(filename, png))\npng = \"\";\nstbi_write_png((filename + png).c_str(), rgb.width, rgb.height, rgb.channels, rgb.data.data(), rgb.width * rgb.channels);\n}\nvoid save_png_image(const std::string& filename, const GrayscaleImage& gray)\n{\nauto ends_with = [](const std::string& value, const std::string& ending) {\nif (ending.size() > value.size())\nreturn false;\nreturn std::equal(ending.rbegin(), ending.rend(), value.rbegin());\n};\nstd::string png = \".png\";\nif (ends_with(filename, png))\npng = \"\";\nstbi_write_png((filename + png).c_str(), gray.width, gray.height, 1, gray.data.data(), gray.width);\n}\nGrayscaleImage convert_rgb_to_grayscale(const Image& rgb)\n{\nassert(rgb.channels == 3);\nsize_t width = rgb.width;\nsize_t height = rgb.height;\nGrayscaleImage gray;\ngray.width = width;\ngray.height = height;\ngray.data.resize(width * height);\nfor (size_t h = 0; h < height; h++) {\nfor (size_t w = 0; w < width; w++) {\nint id = w + h * width;\nint id_rgb = w * rgb.channels + h * (width * rgb.channels);\nuint8_t color = 0.3 * rgb.data[id_rgb + 0] + 0.59 * rgb.data[id_rgb + 1] + 0.11 * rgb.data[id_rgb + 2];\ngray.data[id] = color;\n}\n}\nreturn gray;\n}\nstd::vector<Eigen::Vector3d> point_cloud_from_depth_array(const DepthImage& depth_image, const Eigen::Matrix3d& intrinsic_matrix, const Eigen::Matrix4d& tf, double far_plane)\n{\n// This is assuming that K is normal intrisinc matrix (i.e., camera pointing to +Z),\n// but an OpenGL camera (i.e., pointing to -Z). Thus it transforms the points accordingly\n// TO-DO: Format the intrinsic matrix correctly, and take as an argument the camera orientation\n// with respect to the normal cameras. See http://ksimek.github.io/2013/06/03/calibrated_cameras_in_opengl/.\nauto point_3d = [](const Eigen::Matrix3d& K, size_t u, size_t v, double depth) {\ndouble fx = K(0, 0);\ndouble fy = K(1, 1);\ndouble cx = K(0, 2);\ndouble cy = K(1, 2);\ndouble gamma = K(0, 1);\nEigen::Vector3d p;\np << 0., 0., -depth;\np(1) = (cy - v) * depth / fy;\np(0) = -((cx - u) * depth - gamma * p(1)) / fx;\nreturn p;\n};\nstd::vector<Eigen::Vector3d> point_cloud;\nsize_t height = depth_image.height;\nsize_t width = depth_image.width;\nfor (size_t h = 0; h < height; h++) {\nfor (size_t w = 0; w < width; w++) {\nint id = w + h * width;\nif (depth_image.data[id] >= 0.99 * far_plane) // close to far plane\ncontinue;\nEigen::Vector4d pp;\npp.head(3) = point_3d(intrinsic_matrix, w, h, depth_image.data[id]);\npp.tail(1) << 1.;\npp = tf.inverse() * pp;\npoint_cloud.push_back(pp.head(3));\n}\n}\nreturn point_cloud;\n}\n} // namespace gui\n} // namespace robot_dart\n
"},{"location":"api/helper_8hpp/","title":"File helper.hpp","text":"

FileList > gui > helper.hpp

Go to the source code of this file

"},{"location":"api/helper_8hpp/#namespaces","title":"Namespaces","text":"Type Name namespace robot_dart namespace gui"},{"location":"api/helper_8hpp/#classes","title":"Classes","text":"Type Name struct DepthImage struct GrayscaleImage struct Image

The documentation for this class was generated from the following file robot_dart/gui/helper.hpp

"},{"location":"api/helper_8hpp_source/","title":"File helper.hpp","text":"

File List > gui > helper.hpp

Go to the documentation of this file

#ifndef ROBOT_DART_GUI_HELPER_HPP\n#define ROBOT_DART_GUI_HELPER_HPP\n#include <string>\n#include <vector>\n#include <robot_dart/utils.hpp>\nnamespace robot_dart {\nnamespace gui {\nstruct Image {\nsize_t width = 0, height = 0;\nsize_t channels = 3;\nstd::vector<uint8_t> data;\n};\nstruct GrayscaleImage {\nsize_t width = 0, height = 0;\nstd::vector<uint8_t> data;\n};\nstruct DepthImage {\nsize_t width = 0, height = 0;\nstd::vector<double> data;\n};\nvoid save_png_image(const std::string& filename, const Image& rgb);\nvoid save_png_image(const std::string& filename, const GrayscaleImage& gray);\nGrayscaleImage convert_rgb_to_grayscale(const Image& rgb);\nstd::vector<Eigen::Vector3d> point_cloud_from_depth_array(const DepthImage& depth_image, const Eigen::Matrix3d& intrinsic_matrix, const Eigen::Matrix4d& tf, double far_plane = 1000.);\n} // namespace gui\n} // namespace robot_dart\n#endif\n
"},{"location":"api/dir_5d18adecbc10cabf3ca51da31f2acdd1/","title":"Dir robot_dart/gui/magnum","text":"

FileList > gui > magnum

"},{"location":"api/dir_5d18adecbc10cabf3ca51da31f2acdd1/#files","title":"Files","text":"Type Name file base_application.cpp file base_application.hpp file base_graphics.hpp file drawables.cpp file drawables.hpp file glfw_application.cpp file glfw_application.hpp file graphics.cpp file graphics.hpp file types.hpp file utils_headers_eigen.hpp file windowless_gl_application.cpp file windowless_gl_application.hpp file windowless_graphics.cpp file windowless_graphics.hpp"},{"location":"api/dir_5d18adecbc10cabf3ca51da31f2acdd1/#directories","title":"Directories","text":"Type Name dir gs dir sensor

The documentation for this class was generated from the following file robot_dart/gui/magnum/

"},{"location":"api/base__application_8cpp/","title":"File base_application.cpp","text":"

FileList > gui > magnum > base_application.cpp

Go to the source code of this file

"},{"location":"api/base__application_8cpp/#namespaces","title":"Namespaces","text":"Type Name namespace robot_dart namespace gui namespace magnum

The documentation for this class was generated from the following file robot_dart/gui/magnum/base_application.cpp

"},{"location":"api/base__application_8cpp_source/","title":"Macro Syntax Error","text":"

Line 88 in Markdown file: Expected an expression, got 'end of print statement'

                    _gl_contexts.emplace_back(Magnum::Platform::WindowlessGLContext{{}});\n

"},{"location":"api/base__application_8hpp/","title":"File base_application.hpp","text":"

FileList > gui > magnum > base_application.hpp

Go to the source code of this file

"},{"location":"api/base__application_8hpp/#namespaces","title":"Namespaces","text":"Type Name namespace robot_dart namespace gui namespace magnum"},{"location":"api/base__application_8hpp/#classes","title":"Classes","text":"Type Name class BaseApplication struct DebugDrawData struct GlobalData struct GraphicsConfiguration"},{"location":"api/base__application_8hpp/#macros","title":"Macros","text":"Type Name define get_gl_context (name) get_gl_context_with_sleep(name, 0) define get_gl_context_with_sleep (name, ms_sleep) define release_gl_context (name) robot_dart::gui::magnum::GlobalData::instance()->free_gl_context(name);"},{"location":"api/base__application_8hpp/#macro-definition-documentation","title":"Macro Definition Documentation","text":""},{"location":"api/base__application_8hpp/#define-get_gl_context","title":"define get_gl_context","text":"
#define get_gl_context (\nname\n) get_gl_context_with_sleep(name, 0)\n
"},{"location":"api/base__application_8hpp/#define-get_gl_context_with_sleep","title":"define get_gl_context_with_sleep","text":"
#define get_gl_context_with_sleep (\nname,\nms_sleep\n) /* Create/Get GLContext */                                                \\\n    Corrade::Utility::Debug name##_magnum_silence_output{nullptr};            \\\n    Magnum::Platform::WindowlessGLContext* name = nullptr;                    \\\n    while (name == nullptr) {                                                 \\\n        name = robot_dart::gui::magnum::GlobalData::instance()->gl_context(); \\\n        /* Sleep for some ms */                                               \\\n        usleep(ms_sleep * 1000);                                              \\\n    }                                                                         \\\n    while (!name->makeCurrent()) {                                            \\\n        /* Sleep for some ms */                                               \\\n        usleep(ms_sleep * 1000);                                              \\\n    }                                                                         \\\n                                                                              \\\n    Magnum::Platform::GLContext name##_magnum_context;\n
"},{"location":"api/base__application_8hpp/#define-release_gl_context","title":"define release_gl_context","text":"
#define release_gl_context (\nname\n) robot_dart::gui::magnum::GlobalData::instance()->free_gl_context(name);\n

The documentation for this class was generated from the following file robot_dart/gui/magnum/base_application.hpp

"},{"location":"api/base__application_8hpp_source/","title":"File base_application.hpp","text":"

File List > gui > magnum > base_application.hpp

Go to the documentation of this file

#ifndef ROBOT_DART_GUI_MAGNUM_BASE_APPLICATION_HPP\n#define ROBOT_DART_GUI_MAGNUM_BASE_APPLICATION_HPP\n#include <mutex>\n#include <unistd.h>\n#include <unordered_map>\n#include <robot_dart/gui/helper.hpp>\n#include <robot_dart/gui/magnum/drawables.hpp>\n#include <robot_dart/gui/magnum/gs/camera.hpp>\n#include <robot_dart/gui/magnum/gs/cube_map.hpp>\n#include <robot_dart/gui/magnum/gs/cube_map_color.hpp>\n#include <robot_dart/gui/magnum/gs/phong_multi_light.hpp>\n#include <robot_dart/gui/magnum/gs/shadow_map.hpp>\n#include <robot_dart/gui/magnum/gs/shadow_map_color.hpp>\n#include <robot_dart/gui/magnum/types.hpp>\n#include <robot_dart/utils_headers_external_gui.hpp>\n#include <Magnum/GL/CubeMapTextureArray.h>\n#include <Magnum/GL/Framebuffer.h>\n#include <Magnum/GL/Mesh.h>\n#include <Magnum/GL/TextureArray.h>\n#include <Magnum/Platform/GLContext.h>\n#ifndef MAGNUM_MAC_OSX\n#include <Magnum/Platform/WindowlessEglApplication.h>\n#else\n#include <Magnum/Platform/WindowlessCglApplication.h>\n#endif\n#include <Magnum/Shaders/DistanceFieldVector.h>\n#include <Magnum/Shaders/Flat.h>\n#include <Magnum/Shaders/VertexColor.h>\n#include <Magnum/Text/AbstractFont.h>\n#include <Magnum/Text/DistanceFieldGlyphCache.h>\n#include <Magnum/Text/Renderer.h>\n#define get_gl_context_with_sleep(name, ms_sleep)                             \\\n/* Create/Get GLContext */                                                \\\n    Corrade::Utility::Debug name##_magnum_silence_output{nullptr};            \\\n    Magnum::Platform::WindowlessGLContext* name = nullptr;                    \\\n    while (name == nullptr) {                                                 \\\n        name = robot_dart::gui::magnum::GlobalData::instance()->gl_context(); \\\n/* Sleep for some ms */                                               \\\n        usleep(ms_sleep * 1000);                                              \\\n    }                                                                         \\\n    while (!name->makeCurrent()) {                                            \\\n/* Sleep for some ms */                                               \\\n        usleep(ms_sleep * 1000);                                              \\\n    }                                                                         \\\n                                                                              \\\n    Magnum::Platform::GLContext name##_magnum_context;\n#define get_gl_context(name) get_gl_context_with_sleep(name, 0)\n#define release_gl_context(name) robot_dart::gui::magnum::GlobalData::instance()->free_gl_context(name);\nnamespace robot_dart {\nnamespace gui {\nnamespace magnum {\nstruct GlobalData {\npublic:\nstatic GlobalData* instance()\n{\nstatic GlobalData gdata;\nreturn &gdata;\n}\nGlobalData(const GlobalData&) = delete;\nvoid operator=(const GlobalData&) = delete;\nMagnum::Platform::WindowlessGLContext* gl_context();\nvoid free_gl_context(Magnum::Platform::WindowlessGLContext* context);\n/* You should call this before starting to draw or after finished */\nvoid set_max_contexts(size_t N);\nprivate:\nGlobalData() = default;\n~GlobalData() = default;\nvoid _create_contexts();\nstd::vector<Magnum::Platform::WindowlessGLContext> _gl_contexts;\nstd::vector<bool> _used;\nstd::mutex _context_mutex;\nsize_t _max_contexts = 4;\n};\nstruct GraphicsConfiguration {\n// General\nsize_t width = 640;\nsize_t height = 480;\nstd::string title = \"DART\";\n// Shadows\nbool shadowed = true;\nbool transparent_shadows = true;\nsize_t shadow_map_size = 1024;\n// Lights\nsize_t max_lights = 3;\ndouble specular_strength = 0.25; // strength of the specular component\n// These options are only for the main camera\nbool draw_main_camera = true;\nbool draw_debug = true;\nbool draw_text = true;\n// Background (default = black)\nEigen::Vector4d bg_color{0.0, 0.0, 0.0, 1.0};\n};\nstruct DebugDrawData {\nMagnum::Shaders::VertexColorGL3D* axes_shader;\nMagnum::GL::Mesh* axes_mesh;\nMagnum::Shaders::FlatGL2D* background_shader;\nMagnum::GL::Mesh* background_mesh;\nMagnum::Shaders::DistanceFieldVectorGL2D* text_shader;\nMagnum::GL::Buffer* text_vertices;\nMagnum::GL::Buffer* text_indices;\nMagnum::Text::AbstractFont* font;\nMagnum::Text::DistanceFieldGlyphCache* cache;\n};\nclass BaseApplication {\npublic:\nBaseApplication(const GraphicsConfiguration& configuration = GraphicsConfiguration());\nvirtual ~BaseApplication() {}\nvoid init(RobotDARTSimu* simu, const GraphicsConfiguration& configuration);\nvoid clear_lights();\nvoid add_light(const gs::Light& light);\ngs::Light& light(size_t i);\nstd::vector<gs::Light>& lights();\nsize_t num_lights() const;\nMagnum::SceneGraph::DrawableGroup3D& drawables() { return _drawables; }\nScene3D& scene() { return _scene; }\ngs::Camera& camera() { return *_camera; }\nconst gs::Camera& camera() const { return *_camera; }\nbool done() const;\nvoid look_at(const Eigen::Vector3d& camera_pos,\nconst Eigen::Vector3d& look_at,\nconst Eigen::Vector3d& up);\nvirtual void render() {}\nvoid update_lights(const gs::Camera& camera);\nvoid update_graphics();\nvoid render_shadows();\nbool attach_camera(gs::Camera& camera, dart::dynamics::BodyNode* body);\n// video (FPS is mandatory here, see the Graphics class for automatic computation)\nvoid record_video(const std::string& video_fname, int fps) { _camera->record_video(video_fname, fps); }\nbool shadowed() const { return _shadowed; }\nbool transparent_shadows() const { return _transparent_shadows; }\nvoid enable_shadows(bool enable = true, bool drawTransparentShadows = false);\nCorrade::Containers::Optional<Magnum::Image2D>& image() { return _camera->image(); }\n// This is for visualization purposes\nGrayscaleImage depth_image();\n// Image filled with depth buffer values\nGrayscaleImage raw_depth_image();\n// \"Image\" filled with depth buffer values (this returns an array of doubles)\nDepthImage depth_array();\n// Access to debug data\nDebugDrawData debug_draw_data()\n{\nDebugDrawData data;\ndata.axes_shader = _3D_axis_shader.get();\ndata.background_shader = _background_shader.get();\ndata.axes_mesh = _3D_axis_mesh.get();\ndata.background_mesh = _background_mesh.get();\ndata.text_shader = _text_shader.get();\ndata.text_vertices = _text_vertices.get();\ndata.text_indices = _text_indices.get();\ndata.font = _font.get();\ndata.cache = _glyph_cache.get();\nreturn data;\n}\nprotected:\n/* Magnum */\nScene3D _scene;\nMagnum::SceneGraph::DrawableGroup3D _drawables, _shadowed_drawables, _shadowed_color_drawables, _cubemap_drawables, _cubemap_color_drawables;\nstd::unique_ptr<gs::PhongMultiLight> _color_shader, _texture_shader;\nstd::unique_ptr<gs::Camera> _camera;\nbool _done = false;\n/* GUI Config */\nGraphicsConfiguration _configuration;\n/* DART */\nRobotDARTSimu* _simu;\nstd::unique_ptr<Magnum::DartIntegration::World> _dart_world;\nstd::unordered_map<Magnum::DartIntegration::Object*, ObjectStruct*> _drawable_objects;\nstd::vector<gs::Light> _lights;\n/* Shadows */\nbool _shadowed = true, _transparent_shadows = false;\nint _transparentSize = 0;\nstd::unique_ptr<gs::ShadowMap> _shadow_shader, _shadow_texture_shader;\nstd::unique_ptr<gs::ShadowMapColor> _shadow_color_shader, _shadow_texture_color_shader;\nstd::unique_ptr<gs::CubeMap> _cubemap_shader, _cubemap_texture_shader;\nstd::unique_ptr<gs::CubeMapColor> _cubemap_color_shader, _cubemap_texture_color_shader;\nstd::vector<ShadowData> _shadow_data;\nstd::unique_ptr<Magnum::GL::Texture2DArray> _shadow_texture, _shadow_color_texture;\nstd::unique_ptr<Magnum::GL::CubeMapTextureArray> _shadow_cube_map, _shadow_color_cube_map;\nint _max_lights = 5;\nint _shadow_map_size = 512;\nstd::unique_ptr<Camera3D> _shadow_camera;\nObject3D* _shadow_camera_object;\n/* Debug visualization */\nstd::unique_ptr<Magnum::GL::Mesh> _3D_axis_mesh;\nstd::unique_ptr<Magnum::Shaders::VertexColorGL3D> _3D_axis_shader;\nstd::unique_ptr<Magnum::GL::Mesh> _background_mesh;\nstd::unique_ptr<Magnum::Shaders::FlatGL2D> _background_shader;\n/* Text visualization */\nstd::unique_ptr<Magnum::Shaders::DistanceFieldVectorGL2D> _text_shader;\nCorrade::PluginManager::Manager<Magnum::Text::AbstractFont> _font_manager;\nCorrade::Containers::Pointer<Magnum::Text::DistanceFieldGlyphCache> _glyph_cache;\nCorrade::Containers::Pointer<Magnum::Text::AbstractFont> _font;\nCorrade::Containers::Pointer<Magnum::GL::Buffer> _text_vertices;\nCorrade::Containers::Pointer<Magnum::GL::Buffer> _text_indices;\n/* Importer */\nCorrade::PluginManager::Manager<Magnum::Trade::AbstractImporter> _importer_manager;\nvoid _gl_clean_up();\nvoid _prepare_shadows();\n};\ntemplate <typename T>\ninline BaseApplication* make_application(RobotDARTSimu* simu, const GraphicsConfiguration& configuration = GraphicsConfiguration())\n{\nint argc = 0;\nchar** argv = NULL;\nreturn new T(argc, argv, simu, configuration);\n// configuration.width, configuration.height, configuration.shadowed, configuration.transparent_shadows, configuration.max_lights, configuration.shadow_map_size);\n}\n} // namespace magnum\n} // namespace gui\n} // namespace robot_dart\n#endif\n
"},{"location":"api/base__graphics_8hpp/","title":"File base_graphics.hpp","text":"

FileList > gui > magnum > base_graphics.hpp

Go to the source code of this file

"},{"location":"api/base__graphics_8hpp/#namespaces","title":"Namespaces","text":"Type Name namespace robot_dart namespace gui namespace magnum"},{"location":"api/base__graphics_8hpp/#classes","title":"Classes","text":"Type Name class BaseGraphics <typename T>"},{"location":"api/base__graphics_8hpp/#public-static-functions","title":"Public Static Functions","text":"Type Name void robot_dart_initialize_magnum_resources ()"},{"location":"api/base__graphics_8hpp/#public-static-functions-documentation","title":"Public Static Functions Documentation","text":""},{"location":"api/base__graphics_8hpp/#function-robot_dart_initialize_magnum_resources","title":"function robot_dart_initialize_magnum_resources","text":"
static inline void robot_dart_initialize_magnum_resources () 

The documentation for this class was generated from the following file robot_dart/gui/magnum/base_graphics.hpp

"},{"location":"api/base__graphics_8hpp_source/","title":"File base_graphics.hpp","text":"

File List > gui > magnum > base_graphics.hpp

Go to the documentation of this file

#ifndef ROBOT_DART_GUI_MAGNUM_BASE_GRAPHICS_HPP\n#define ROBOT_DART_GUI_MAGNUM_BASE_GRAPHICS_HPP\n#include <robot_dart/gui/base.hpp>\n#include <robot_dart/gui/magnum/glfw_application.hpp>\n#include <robot_dart/gui/magnum/gs/helper.hpp>\n#include <robot_dart/gui/magnum/utils_headers_eigen.hpp>\n#include <robot_dart/robot_dart_simu.hpp>\n// We need this for CORRADE_RESOURCE_INITIALIZE\n#include <Corrade/Utility/Resource.h>\ninline static void robot_dart_initialize_magnum_resources()\n{\nCORRADE_RESOURCE_INITIALIZE(RobotDARTShaders);\n}\nnamespace robot_dart {\nnamespace gui {\nnamespace magnum {\ntemplate <typename T = GlfwApplication>\nclass BaseGraphics : public Base {\npublic:\nBaseGraphics(const GraphicsConfiguration& configuration = GraphicsConfiguration())\n: _configuration(configuration), _enabled(true)\n{\nrobot_dart_initialize_magnum_resources();\n}\nvirtual ~BaseGraphics() {}\nvirtual void set_simu(RobotDARTSimu* simu) override\n{\nROBOT_DART_EXCEPTION_ASSERT(simu, \"Simulation pointer is null!\");\n_simu = simu;\n_magnum_app.reset(make_application<T>(simu, _configuration));\n}\nsize_t width() const override\n{\nROBOT_DART_EXCEPTION_ASSERT(_magnum_app, \"MagnumApp pointer is null!\");\nreturn _magnum_app->camera().width();\n}\nsize_t height() const override\n{\nROBOT_DART_EXCEPTION_ASSERT(_magnum_app, \"MagnumApp pointer is null!\");\nreturn _magnum_app->camera().height();\n}\nbool done() const override\n{\nROBOT_DART_EXCEPTION_ASSERT(_magnum_app, \"MagnumApp pointer is null!\");\nreturn _magnum_app->done();\n}\nvoid refresh() override\n{\nif (!_enabled)\nreturn;\nROBOT_DART_EXCEPTION_ASSERT(_magnum_app, \"MagnumApp pointer is null!\");\n_magnum_app->render();\n}\nvoid set_enable(bool enable) override\n{\n_enabled = enable;\n}\nvoid set_fps(int fps) override { _fps = fps; }\nvoid look_at(const Eigen::Vector3d& camera_pos,\nconst Eigen::Vector3d& look_at = Eigen::Vector3d(0, 0, 0),\nconst Eigen::Vector3d& up = Eigen::Vector3d(0, 0, 1))\n{\nROBOT_DART_EXCEPTION_ASSERT(_magnum_app, \"MagnumApp pointer is null!\");\n_magnum_app->look_at(camera_pos, look_at, up);\n}\nvoid clear_lights()\n{\nROBOT_DART_EXCEPTION_ASSERT(_magnum_app, \"MagnumApp pointer is null!\");\n_magnum_app->clear_lights();\n}\nvoid add_light(const magnum::gs::Light& light)\n{\nROBOT_DART_EXCEPTION_ASSERT(_magnum_app, \"MagnumApp pointer is null!\");\n_magnum_app->add_light(light);\n}\nstd::vector<gs::Light>& lights()\n{\nROBOT_DART_EXCEPTION_ASSERT(_magnum_app, \"MagnumApp pointer is null!\");\nreturn _magnum_app->lights();\n}\nsize_t num_lights() const\n{\nROBOT_DART_EXCEPTION_ASSERT(_magnum_app, \"MagnumApp pointer is null!\");\nreturn _magnum_app->num_lights();\n}\nmagnum::gs::Light& light(size_t i)\n{\nROBOT_DART_EXCEPTION_ASSERT(_magnum_app, \"MagnumApp pointer is null!\");\nreturn _magnum_app->light(i);\n}\nvoid record_video(const std::string& video_fname, int fps = -1)\n{\nint fps_computed = (fps == -1) ? _fps : fps;\nROBOT_DART_EXCEPTION_ASSERT(fps_computed != -1, \"Video FPS not set!\");\nROBOT_DART_EXCEPTION_ASSERT(_magnum_app, \"MagnumApp pointer is null!\");\n_magnum_app->record_video(video_fname, fps_computed);\n}\nbool shadowed() const\n{\nROBOT_DART_EXCEPTION_ASSERT(_magnum_app, \"MagnumApp pointer is null!\");\nreturn _magnum_app->shadowed();\n}\nbool transparent_shadows() const\n{\nROBOT_DART_EXCEPTION_ASSERT(_magnum_app, \"MagnumApp pointer is null!\");\nreturn _magnum_app->transparent_shadows();\n}\nvoid enable_shadows(bool enable = true, bool transparent = true)\n{\nROBOT_DART_EXCEPTION_ASSERT(_magnum_app, \"MagnumApp pointer is null!\");\n_magnum_app->enable_shadows(enable, transparent);\n}\nMagnum::Image2D* magnum_image()\n{\nROBOT_DART_EXCEPTION_ASSERT(_magnum_app, \"MagnumApp pointer is null!\");\nif (_magnum_app->image())\nreturn &(*_magnum_app->image());\nreturn nullptr;\n}\nImage image() override\n{\nauto image = magnum_image();\nif (image)\nreturn gs::rgb_from_image(image);\nreturn Image();\n}\nGrayscaleImage depth_image() override\n{\nROBOT_DART_EXCEPTION_ASSERT(_magnum_app, \"MagnumApp pointer is null!\");\nreturn _magnum_app->depth_image();\n}\nGrayscaleImage raw_depth_image() override\n{\nROBOT_DART_EXCEPTION_ASSERT(_magnum_app, \"MagnumApp pointer is null!\");\nreturn _magnum_app->raw_depth_image();\n}\nDepthImage depth_array() override\n{\nROBOT_DART_EXCEPTION_ASSERT(_magnum_app, \"MagnumApp pointer is null!\");\nreturn _magnum_app->depth_array();\n}\ngs::Camera& camera()\n{\nROBOT_DART_EXCEPTION_ASSERT(_magnum_app, \"MagnumApp pointer is null!\");\nreturn _magnum_app->camera();\n}\nconst gs::Camera& camera() const\n{\nROBOT_DART_EXCEPTION_ASSERT(_magnum_app, \"MagnumApp pointer is null!\");\nreturn _magnum_app->camera();\n}\nEigen::Matrix3d camera_intrinsic_matrix() const\n{\nROBOT_DART_EXCEPTION_ASSERT(_magnum_app, \"MagnumApp pointer is null!\");\nreturn Magnum::EigenIntegration::cast<Eigen::Matrix3d>(Magnum::Matrix3d(_magnum_app->camera().intrinsic_matrix()));\n}\nEigen::Matrix4d camera_extrinsic_matrix() const\n{\nROBOT_DART_EXCEPTION_ASSERT(_magnum_app, \"MagnumApp pointer is null!\");\nreturn Magnum::EigenIntegration::cast<Eigen::Matrix4d>(Magnum::Matrix4d(_magnum_app->camera().extrinsic_matrix()));\n}\nBaseApplication* magnum_app()\n{\nROBOT_DART_EXCEPTION_ASSERT(_magnum_app, \"MagnumApp pointer is null!\");\nreturn &*_magnum_app;\n}\nconst BaseApplication* magnum_app() const\n{\nROBOT_DART_EXCEPTION_ASSERT(_magnum_app, \"MagnumApp pointer is null!\");\nreturn &*_magnum_app;\n}\nprotected:\nGraphicsConfiguration _configuration;\nbool _enabled;\nint _fps;\nstd::unique_ptr<BaseApplication> _magnum_app;\nCorrade::Utility::Debug _magnum_silence_output{nullptr};\n};\n} // namespace magnum\n} // namespace gui\n} // namespace robot_dart\n#endif\n
"},{"location":"api/drawables_8cpp/","title":"File drawables.cpp","text":"

FileList > gui > magnum > drawables.cpp

Go to the source code of this file

"},{"location":"api/drawables_8cpp/#namespaces","title":"Namespaces","text":"Type Name namespace robot_dart namespace gui namespace magnum

The documentation for this class was generated from the following file robot_dart/gui/magnum/drawables.cpp

"},{"location":"api/drawables_8cpp_source/","title":"File drawables.cpp","text":"

File List > gui > magnum > drawables.cpp

Go to the documentation of this file

#include <robot_dart/gui/magnum/drawables.hpp>\n#include <robot_dart/gui_data.hpp>\n#include <robot_dart/robot_dart_simu.hpp>\n#include <robot_dart/utils.hpp>\n#include <Magnum/GL/CubeMapTexture.h>\n#include <Magnum/GL/DefaultFramebuffer.h>\n#include <Magnum/GL/Mesh.h>\n#include <Magnum/GL/Renderer.h>\n#include <Magnum/GL/AbstractFramebuffer.h>\n#include <Magnum/GL/GL.h>\nnamespace robot_dart {\nnamespace gui {\nnamespace magnum {\n// DrawableObject\nDrawableObject::DrawableObject(\nRobotDARTSimu* simu,\ndart::dynamics::ShapeNode* shape,\nconst std::vector<std::reference_wrapper<Magnum::GL::Mesh>>& meshes,\nconst std::vector<gs::Material>& materials,\ngs::PhongMultiLight& color,\ngs::PhongMultiLight& texture,\nObject3D* parent,\nMagnum::SceneGraph::DrawableGroup3D* group)\n: Object3D{parent},\nMagnum::SceneGraph::Drawable3D{*this, group},\n_simu(simu),\n_shape(shape),\n_meshes{meshes},\n_color_shader{color},\n_texture_shader{texture},\n_materials(materials)\n{\n_is_soft_body.resize(_meshes.size(), false);\n}\nDrawableObject& DrawableObject::set_meshes(const std::vector<std::reference_wrapper<Magnum::GL::Mesh>>& meshes)\n{\n_meshes = meshes;\nreturn *this;\n}\nDrawableObject& DrawableObject::set_materials(const std::vector<gs::Material>& materials)\n{\n_materials = materials;\nreturn *this;\n}\nDrawableObject& DrawableObject::set_soft_bodies(const std::vector<bool>& softBody)\n{\n_is_soft_body = softBody;\nreturn *this;\n}\nDrawableObject& DrawableObject::set_scalings(const std::vector<Magnum::Vector3>& scalings)\n{\n_scalings = scalings;\n_has_negative_scaling.resize(_scalings.size());\nfor (size_t i = 0; i < scalings.size(); i++) {\n_has_negative_scaling[i] = false;\nfor (size_t j = 0; j < 3; j++)\nif (_scalings[i][j] < 0.f) {\n_has_negative_scaling[i] = true;\nbreak;\n}\n}\nreturn *this;\n}\nDrawableObject& DrawableObject::set_transparent(bool transparent)\n{\n_isTransparent = transparent;\nreturn *this;\n}\nDrawableObject& DrawableObject::set_color_shader(std::reference_wrapper<gs::PhongMultiLight> shader)\n{\n_color_shader = shader;\nreturn *this;\n}\nDrawableObject& DrawableObject::set_texture_shader(std::reference_wrapper<gs::PhongMultiLight> shader)\n{\n_texture_shader = shader;\nreturn *this;\n}\nvoid DrawableObject::draw(const Magnum::Matrix4& transformationMatrix, Magnum::SceneGraph::Camera3D& camera)\n{\nfor (size_t i = 0; i < _meshes.size(); i++) {\nMagnum::GL::Mesh& mesh = _meshes[i];\nMagnum::Matrix4 scalingMatrix = Magnum::Matrix4::scaling(_scalings[i]);\nbool isColor = !_materials[i].has_diffuse_texture();\nif (_is_soft_body[i])\nMagnum::GL::Renderer::disable(Magnum::GL::Renderer::Feature::FaceCulling);\nelse if (_has_negative_scaling[i])\nMagnum::GL::Renderer::setFaceCullingMode(Magnum::GL::Renderer::PolygonFacing::Front);\nif (isColor) {\n_color_shader.get()\n.set_material(_materials[i])\n.set_transformation_matrix(absoluteTransformationMatrix() * scalingMatrix)\n.set_normal_matrix((transformationMatrix * scalingMatrix).rotationScaling())\n.set_camera_matrix(camera.cameraMatrix())\n.set_projection_matrix(camera.projectionMatrix())\n.draw(mesh);\n}\nelse {\n_texture_shader.get()\n.set_material(_materials[i])\n.set_transformation_matrix(absoluteTransformationMatrix() * scalingMatrix)\n.set_normal_matrix((transformationMatrix * scalingMatrix).rotationScaling())\n.set_camera_matrix(camera.cameraMatrix())\n.set_projection_matrix(camera.projectionMatrix())\n.draw(mesh);\n}\nif (_is_soft_body[i])\nMagnum::GL::Renderer::enable(Magnum::GL::Renderer::Feature::FaceCulling);\nelse if (_has_negative_scaling[i])\nMagnum::GL::Renderer::setFaceCullingMode(Magnum::GL::Renderer::PolygonFacing::Back);\n}\n}\n// ShadowedObject\nShadowedObject::ShadowedObject(\nRobotDARTSimu* simu,\ndart::dynamics::ShapeNode* shape,\nconst std::vector<std::reference_wrapper<Magnum::GL::Mesh>>& meshes,\ngs::ShadowMap& shader,\ngs::ShadowMap& texture_shader,\nObject3D* parent,\nMagnum::SceneGraph::DrawableGroup3D* group)\n: Object3D{parent},\nMagnum::SceneGraph::Drawable3D{*this, group},\n_simu(simu),\n_shape(shape),\n_meshes{meshes},\n_shader{shader},\n_texture_shader(texture_shader) {}\nShadowedObject& ShadowedObject::set_meshes(const std::vector<std::reference_wrapper<Magnum::GL::Mesh>>& meshes)\n{\n_meshes = meshes;\nreturn *this;\n}\nShadowedObject& ShadowedObject::set_materials(const std::vector<gs::Material>& materials)\n{\n_materials = materials;\nreturn *this;\n}\nShadowedObject& ShadowedObject::set_scalings(const std::vector<Magnum::Vector3>& scalings)\n{\n_scalings = scalings;\nreturn *this;\n}\nvoid ShadowedObject::draw(const Magnum::Matrix4& transformationMatrix, Magnum::SceneGraph::Camera3D& camera)\n{\nif (!_simu->gui_data()->cast_shadows(_shape))\nreturn;\nfor (size_t i = 0; i < _meshes.size(); i++) {\nMagnum::GL::Mesh& mesh = _meshes[i];\nMagnum::Matrix4 scalingMatrix = Magnum::Matrix4::scaling(_scalings[i]);\nbool isColor = !_materials[i].has_diffuse_texture();\nif (isColor) {\n(_shader.get())\n.set_transformation_matrix(transformationMatrix * scalingMatrix)\n.set_projection_matrix(camera.projectionMatrix())\n.set_material(_materials[i])\n.draw(mesh);\n}\nelse {\n(_texture_shader.get())\n.set_transformation_matrix(transformationMatrix * scalingMatrix)\n.set_projection_matrix(camera.projectionMatrix())\n.set_material(_materials[i])\n.draw(mesh);\n}\n}\n}\n// ShadowedColorObject\nShadowedColorObject::ShadowedColorObject(\nRobotDARTSimu* simu,\ndart::dynamics::ShapeNode* shape,\nconst std::vector<std::reference_wrapper<Magnum::GL::Mesh>>& meshes,\ngs::ShadowMapColor& shader,\ngs::ShadowMapColor& texture_shader,\nObject3D* parent,\nMagnum::SceneGraph::DrawableGroup3D* group)\n: Object3D{parent},\nMagnum::SceneGraph::Drawable3D{*this, group},\n_simu(simu),\n_shape(shape),\n_meshes{meshes},\n_shader{shader},\n_texture_shader(texture_shader) {}\nShadowedColorObject& ShadowedColorObject::set_meshes(const std::vector<std::reference_wrapper<Magnum::GL::Mesh>>& meshes)\n{\n_meshes = meshes;\nreturn *this;\n}\nShadowedColorObject& ShadowedColorObject::set_materials(const std::vector<gs::Material>& materials)\n{\n_materials = materials;\nreturn *this;\n}\nShadowedColorObject& ShadowedColorObject::set_scalings(const std::vector<Magnum::Vector3>& scalings)\n{\n_scalings = scalings;\nreturn *this;\n}\nvoid ShadowedColorObject::draw(const Magnum::Matrix4& transformationMatrix, Magnum::SceneGraph::Camera3D& camera)\n{\nif (!_simu->gui_data()->cast_shadows(_shape))\nreturn;\nfor (size_t i = 0; i < _meshes.size(); i++) {\nMagnum::GL::Mesh& mesh = _meshes[i];\nMagnum::Matrix4 scalingMatrix = Magnum::Matrix4::scaling(_scalings[i]);\nbool isColor = !_materials[i].has_diffuse_texture();\nif (isColor) {\n(_shader.get())\n.set_transformation_matrix(transformationMatrix * scalingMatrix)\n.set_projection_matrix(camera.projectionMatrix())\n.set_material(_materials[i])\n.draw(mesh);\n}\nelse {\n(_texture_shader.get())\n.set_transformation_matrix(transformationMatrix * scalingMatrix)\n.set_projection_matrix(camera.projectionMatrix())\n.set_material(_materials[i])\n.draw(mesh);\n}\n}\n}\n// CubeMapShadowedObject\nCubeMapShadowedObject::CubeMapShadowedObject(\nRobotDARTSimu* simu,\ndart::dynamics::ShapeNode* shape,\nconst std::vector<std::reference_wrapper<Magnum::GL::Mesh>>& meshes,\ngs::CubeMap& shader,\ngs::CubeMap& texture_shader,\nObject3D* parent,\nMagnum::SceneGraph::DrawableGroup3D* group)\n: Object3D{parent},\nMagnum::SceneGraph::Drawable3D{*this, group},\n_simu(simu),\n_shape(shape),\n_meshes{meshes},\n_shader{shader},\n_texture_shader(texture_shader) {}\nCubeMapShadowedObject& CubeMapShadowedObject::set_meshes(const std::vector<std::reference_wrapper<Magnum::GL::Mesh>>& meshes)\n{\n_meshes = meshes;\nreturn *this;\n}\nCubeMapShadowedObject& CubeMapShadowedObject::set_materials(const std::vector<gs::Material>& materials)\n{\n_materials = materials;\nreturn *this;\n}\nCubeMapShadowedObject& CubeMapShadowedObject::set_scalings(const std::vector<Magnum::Vector3>& scalings)\n{\n_scalings = scalings;\nreturn *this;\n}\nvoid CubeMapShadowedObject::draw(const Magnum::Matrix4&, Magnum::SceneGraph::Camera3D&)\n{\nfor (size_t i = 0; i < _meshes.size(); i++) {\nMagnum::GL::Mesh& mesh = _meshes[i];\nMagnum::Matrix4 scalingMatrix = Magnum::Matrix4::scaling(_scalings[i]);\nbool isColor = !_materials[i].has_diffuse_texture();\nif (isColor) {\n(_shader.get())\n.set_transformation_matrix(absoluteTransformation() * scalingMatrix)\n.set_material(_materials[i])\n.draw(mesh);\n}\nelse {\n(_texture_shader.get())\n.set_transformation_matrix(absoluteTransformation() * scalingMatrix)\n.set_material(_materials[i])\n.draw(mesh);\n}\n}\n}\n// CubeMapShadowedColorObject\nCubeMapShadowedColorObject::CubeMapShadowedColorObject(\nRobotDARTSimu* simu,\ndart::dynamics::ShapeNode* shape,\nconst std::vector<std::reference_wrapper<Magnum::GL::Mesh>>& meshes,\ngs::CubeMapColor& shader,\ngs::CubeMapColor& texture_shader,\nObject3D* parent,\nMagnum::SceneGraph::DrawableGroup3D* group)\n: Object3D{parent},\nMagnum::SceneGraph::Drawable3D{*this, group},\n_simu(simu),\n_shape(shape),\n_meshes{meshes},\n_shader{shader},\n_texture_shader(texture_shader) {}\nCubeMapShadowedColorObject& CubeMapShadowedColorObject::set_meshes(const std::vector<std::reference_wrapper<Magnum::GL::Mesh>>& meshes)\n{\n_meshes = meshes;\nreturn *this;\n}\nCubeMapShadowedColorObject& CubeMapShadowedColorObject::set_materials(const std::vector<gs::Material>& materials)\n{\n_materials = materials;\nreturn *this;\n}\nCubeMapShadowedColorObject& CubeMapShadowedColorObject::set_scalings(const std::vector<Magnum::Vector3>& scalings)\n{\n_scalings = scalings;\nreturn *this;\n}\nvoid CubeMapShadowedColorObject::draw(const Magnum::Matrix4&, Magnum::SceneGraph::Camera3D&)\n{\nif (!_simu->gui_data()->cast_shadows(_shape))\nreturn;\nfor (size_t i = 0; i < _meshes.size(); i++) {\nMagnum::GL::Mesh& mesh = _meshes[i];\nMagnum::Matrix4 scalingMatrix = Magnum::Matrix4::scaling(_scalings[i]);\nbool isColor = !_materials[i].has_diffuse_texture();\nif (isColor) {\n(_shader.get())\n.set_transformation_matrix(absoluteTransformation() * scalingMatrix)\n.set_material(_materials[i])\n.draw(mesh);\n}\nelse {\n(_texture_shader.get())\n.set_transformation_matrix(absoluteTransformation() * scalingMatrix)\n.set_material(_materials[i])\n.draw(mesh);\n}\n}\n}\n} // namespace magnum\n} // namespace gui\n} // namespace robot_dart\n
"},{"location":"api/drawables_8hpp/","title":"File drawables.hpp","text":"

FileList > gui > magnum > drawables.hpp

Go to the source code of this file

"},{"location":"api/drawables_8hpp/#namespaces","title":"Namespaces","text":"Type Name namespace dart namespace dynamics namespace robot_dart namespace gui namespace magnum"},{"location":"api/drawables_8hpp/#classes","title":"Classes","text":"Type Name class CubeMapShadowedColorObject class CubeMapShadowedObject class DrawableObject struct ObjectStruct struct ShadowData class ShadowedColorObject class ShadowedObject

The documentation for this class was generated from the following file robot_dart/gui/magnum/drawables.hpp

"},{"location":"api/drawables_8hpp_source/","title":"File drawables.hpp","text":"

File List > gui > magnum > drawables.hpp

Go to the documentation of this file

#ifndef ROBOT_DART_GUI_MAGNUM_DRAWABLES_HPP\n#define ROBOT_DART_GUI_MAGNUM_DRAWABLES_HPP\n#include <robot_dart/gui/helper.hpp>\n#include <robot_dart/gui/magnum/gs/cube_map.hpp>\n#include <robot_dart/gui/magnum/gs/cube_map_color.hpp>\n#include <robot_dart/gui/magnum/gs/phong_multi_light.hpp>\n#include <robot_dart/gui/magnum/gs/shadow_map.hpp>\n#include <robot_dart/gui/magnum/gs/shadow_map_color.hpp>\n#include <robot_dart/gui/magnum/types.hpp>\n#include <Magnum/GL/Framebuffer.h>\n#include <Magnum/SceneGraph/Drawable.h>\nnamespace dart {\nnamespace dynamics {\nclass ShapeNode;\n}\n} // namespace dart\nnamespace robot_dart {\nclass RobotDARTSimu;\nnamespace gui {\nnamespace magnum {\nclass DrawableObject : public Object3D, public Magnum::SceneGraph::Drawable3D {\npublic:\nexplicit DrawableObject(\nRobotDARTSimu* simu,\ndart::dynamics::ShapeNode* shape,\nconst std::vector<std::reference_wrapper<Magnum::GL::Mesh>>& meshes,\nconst std::vector<gs::Material>& materials,\ngs::PhongMultiLight& color,\ngs::PhongMultiLight& texture,\nObject3D* parent,\nMagnum::SceneGraph::DrawableGroup3D* group);\nDrawableObject& set_meshes(const std::vector<std::reference_wrapper<Magnum::GL::Mesh>>& meshes);\nDrawableObject& set_materials(const std::vector<gs::Material>& materials);\nDrawableObject& set_soft_bodies(const std::vector<bool>& softBody);\nDrawableObject& set_scalings(const std::vector<Magnum::Vector3>& scalings);\nDrawableObject& set_transparent(bool transparent = true);\nDrawableObject& set_color_shader(std::reference_wrapper<gs::PhongMultiLight> shader);\nDrawableObject& set_texture_shader(std::reference_wrapper<gs::PhongMultiLight> shader);\nconst std::vector<gs::Material>& materials() const { return _materials; }\nbool transparent() const { return _isTransparent; }\nRobotDARTSimu* simu() const { return _simu; }\ndart::dynamics::ShapeNode* shape() const { return _shape; }\nprivate:\nvoid draw(const Magnum::Matrix4& transformationMatrix, Magnum::SceneGraph::Camera3D& camera) override;\nRobotDARTSimu* _simu;\ndart::dynamics::ShapeNode* _shape;\nstd::vector<std::reference_wrapper<Magnum::GL::Mesh>> _meshes;\nstd::reference_wrapper<gs::PhongMultiLight> _color_shader;\nstd::reference_wrapper<gs::PhongMultiLight> _texture_shader;\nstd::vector<gs::Material> _materials;\nstd::vector<Magnum::Vector3> _scalings;\nstd::vector<bool> _has_negative_scaling;\nstd::vector<bool> _is_soft_body;\nbool _isTransparent;\n};\nclass ShadowedObject : public Object3D, public Magnum::SceneGraph::Drawable3D {\npublic:\nexplicit ShadowedObject(\nRobotDARTSimu* simu,\ndart::dynamics::ShapeNode* shape,\nconst std::vector<std::reference_wrapper<Magnum::GL::Mesh>>& meshes,\ngs::ShadowMap& shader,\ngs::ShadowMap& texture_shader,\nObject3D* parent,\nMagnum::SceneGraph::DrawableGroup3D* group);\nShadowedObject& set_meshes(const std::vector<std::reference_wrapper<Magnum::GL::Mesh>>& meshes);\nShadowedObject& set_materials(const std::vector<gs::Material>& materials);\nShadowedObject& set_scalings(const std::vector<Magnum::Vector3>& scalings);\nRobotDARTSimu* simu() const { return _simu; }\ndart::dynamics::ShapeNode* shape() const { return _shape; }\nprivate:\nvoid draw(const Magnum::Matrix4& transformationMatrix, Magnum::SceneGraph::Camera3D& camera) override;\nRobotDARTSimu* _simu;\ndart::dynamics::ShapeNode* _shape;\nstd::vector<std::reference_wrapper<Magnum::GL::Mesh>> _meshes;\nstd::reference_wrapper<gs::ShadowMap> _shader, _texture_shader;\nstd::vector<gs::Material> _materials;\nstd::vector<Magnum::Vector3> _scalings;\n};\nclass ShadowedColorObject : public Object3D, public Magnum::SceneGraph::Drawable3D {\npublic:\nexplicit ShadowedColorObject(\nRobotDARTSimu* simu,\ndart::dynamics::ShapeNode* shape,\nconst std::vector<std::reference_wrapper<Magnum::GL::Mesh>>& meshes,\ngs::ShadowMapColor& shader,\ngs::ShadowMapColor& texture_shader,\nObject3D* parent,\nMagnum::SceneGraph::DrawableGroup3D* group);\nShadowedColorObject& set_meshes(const std::vector<std::reference_wrapper<Magnum::GL::Mesh>>& meshes);\nShadowedColorObject& set_materials(const std::vector<gs::Material>& materials);\nShadowedColorObject& set_scalings(const std::vector<Magnum::Vector3>& scalings);\nRobotDARTSimu* simu() const { return _simu; }\ndart::dynamics::ShapeNode* shape() const { return _shape; }\nprivate:\nvoid draw(const Magnum::Matrix4& transformationMatrix, Magnum::SceneGraph::Camera3D& camera) override;\nRobotDARTSimu* _simu;\ndart::dynamics::ShapeNode* _shape;\nstd::vector<std::reference_wrapper<Magnum::GL::Mesh>> _meshes;\nstd::reference_wrapper<gs::ShadowMapColor> _shader, _texture_shader;\nstd::vector<gs::Material> _materials;\nstd::vector<Magnum::Vector3> _scalings;\n};\nclass CubeMapShadowedObject : public Object3D, public Magnum::SceneGraph::Drawable3D {\npublic:\nexplicit CubeMapShadowedObject(\nRobotDARTSimu* simu,\ndart::dynamics::ShapeNode* shape,\nconst std::vector<std::reference_wrapper<Magnum::GL::Mesh>>& meshes,\ngs::CubeMap& shader,\ngs::CubeMap& texture_shader,\nObject3D* parent,\nMagnum::SceneGraph::DrawableGroup3D* group);\nCubeMapShadowedObject& set_meshes(const std::vector<std::reference_wrapper<Magnum::GL::Mesh>>& meshes);\nCubeMapShadowedObject& set_materials(const std::vector<gs::Material>& materials);\nCubeMapShadowedObject& set_scalings(const std::vector<Magnum::Vector3>& scalings);\nRobotDARTSimu* simu() const { return _simu; }\ndart::dynamics::ShapeNode* shape() const { return _shape; }\nprivate:\nvoid draw(const Magnum::Matrix4& transformationMatrix, Magnum::SceneGraph::Camera3D& camera) override;\nRobotDARTSimu* _simu;\ndart::dynamics::ShapeNode* _shape;\nstd::vector<std::reference_wrapper<Magnum::GL::Mesh>> _meshes;\nstd::reference_wrapper<gs::CubeMap> _shader, _texture_shader;\nstd::vector<gs::Material> _materials;\nstd::vector<Magnum::Vector3> _scalings;\n};\nclass CubeMapShadowedColorObject : public Object3D, public Magnum::SceneGraph::Drawable3D {\npublic:\nexplicit CubeMapShadowedColorObject(\nRobotDARTSimu* simu,\ndart::dynamics::ShapeNode* shape,\nconst std::vector<std::reference_wrapper<Magnum::GL::Mesh>>& meshes,\ngs::CubeMapColor& shader,\ngs::CubeMapColor& texture_shader,\nObject3D* parent,\nMagnum::SceneGraph::DrawableGroup3D* group);\nCubeMapShadowedColorObject& set_meshes(const std::vector<std::reference_wrapper<Magnum::GL::Mesh>>& meshes);\nCubeMapShadowedColorObject& set_materials(const std::vector<gs::Material>& materials);\nCubeMapShadowedColorObject& set_scalings(const std::vector<Magnum::Vector3>& scalings);\nRobotDARTSimu* simu() const { return _simu; }\ndart::dynamics::ShapeNode* shape() const { return _shape; }\nprivate:\nvoid draw(const Magnum::Matrix4& transformationMatrix, Magnum::SceneGraph::Camera3D& camera) override;\nRobotDARTSimu* _simu;\ndart::dynamics::ShapeNode* _shape;\nstd::vector<std::reference_wrapper<Magnum::GL::Mesh>> _meshes;\nstd::reference_wrapper<gs::CubeMapColor> _shader, _texture_shader;\nstd::vector<gs::Material> _materials;\nstd::vector<Magnum::Vector3> _scalings;\n};\nstruct ShadowData {\nMagnum::GL::Framebuffer shadow_framebuffer{Magnum::NoCreate};\nMagnum::GL::Framebuffer shadow_color_framebuffer{Magnum::NoCreate};\n};\nstruct ObjectStruct {\nDrawableObject* drawable;\nShadowedObject* shadowed;\nShadowedColorObject* shadowed_color;\nCubeMapShadowedObject* cubemapped;\nCubeMapShadowedColorObject* cubemapped_color;\n};\n} // namespace magnum\n} // namespace gui\n} // namespace robot_dart\n#endif\n
"},{"location":"api/glfw__application_8cpp/","title":"File glfw_application.cpp","text":"

FileList > gui > magnum > glfw_application.cpp

Go to the source code of this file

"},{"location":"api/glfw__application_8cpp/#namespaces","title":"Namespaces","text":"Type Name namespace robot_dart namespace gui namespace magnum

The documentation for this class was generated from the following file robot_dart/gui/magnum/glfw_application.cpp

"},{"location":"api/glfw__application_8cpp_source/","title":"Macro Syntax Error","text":"

Line 69 in Markdown file: unexpected '}'

                Magnum::GL::defaultFramebuffer.setViewport({{}, event.framebufferSize()});\n

"},{"location":"api/glfw__application_8hpp/","title":"File glfw_application.hpp","text":"

FileList > gui > magnum > glfw_application.hpp

Go to the source code of this file

"},{"location":"api/glfw__application_8hpp/#namespaces","title":"Namespaces","text":"Type Name namespace robot_dart namespace gui namespace magnum"},{"location":"api/glfw__application_8hpp/#classes","title":"Classes","text":"Type Name class GlfwApplication

The documentation for this class was generated from the following file robot_dart/gui/magnum/glfw_application.hpp

"},{"location":"api/glfw__application_8hpp_source/","title":"File glfw_application.hpp","text":"

File List > gui > magnum > glfw_application.hpp

Go to the documentation of this file

#ifndef ROBOT_DART_GUI_MAGNUM_GLFW_APPLICATION_HPP\n#define ROBOT_DART_GUI_MAGNUM_GLFW_APPLICATION_HPP\n#include <robot_dart/gui/magnum/base_application.hpp>\n// Workaround for X11lib defines\n#undef Button1\n#undef Button2\n#undef Button3\n#undef Button4\n#undef Button5\n#include <Magnum/Platform/GlfwApplication.h>\nnamespace robot_dart {\nnamespace gui {\nnamespace magnum {\nclass GlfwApplication : public BaseApplication, public Magnum::Platform::Application {\npublic:\nexplicit GlfwApplication(int argc, char** argv, RobotDARTSimu* simu, const GraphicsConfiguration& configuration = GraphicsConfiguration());\n~GlfwApplication();\nvoid render() override;\nprotected:\nRobotDARTSimu* _simu;\nMagnum::Float _speed_move, _speed_strafe;\nbool _draw_main_camera, _draw_debug;\nMagnum::Color4 _bg_color;\nstatic constexpr Magnum::Float _speed = 0.05f;\nvoid viewportEvent(ViewportEvent& event) override;\nvoid drawEvent() override;\nvirtual void keyReleaseEvent(KeyEvent& event) override;\nvirtual void keyPressEvent(KeyEvent& event) override;\nvirtual void mouseScrollEvent(MouseScrollEvent& event) override;\nvirtual void mouseMoveEvent(MouseMoveEvent& event) override;\nvoid exitEvent(ExitEvent& event) override;\n};\n} // namespace magnum\n} // namespace gui\n} // namespace robot_dart\n#endif\n
"},{"location":"api/graphics_8cpp/","title":"File graphics.cpp","text":"

FileList > gui > magnum > graphics.cpp

Go to the source code of this file

"},{"location":"api/graphics_8cpp/#namespaces","title":"Namespaces","text":"Type Name namespace robot_dart namespace gui namespace magnum

The documentation for this class was generated from the following file robot_dart/gui/magnum/graphics.cpp

"},{"location":"api/graphics_8cpp_source/","title":"File graphics.cpp","text":"

File List > gui > magnum > graphics.cpp

Go to the documentation of this file

#include <robot_dart/gui/magnum/graphics.hpp>\nnamespace robot_dart {\nnamespace gui {\nnamespace magnum {\nvoid Graphics::set_simu(RobotDARTSimu* simu)\n{\nBaseGraphics<GlfwApplication>::set_simu(simu);\n// we synchronize by default if we have the graphics activated\nsimu->scheduler().set_sync(true);\n// enable summary text when graphics activated\nsimu->enable_text_panel(true);\nsimu->enable_status_bar(true);\n}\nGraphicsConfiguration Graphics::default_configuration()\n{\nreturn GraphicsConfiguration();\n}\n} // namespace magnum\n} // namespace gui\n} // namespace robot_dart\n
"},{"location":"api/graphics_8hpp/","title":"File graphics.hpp","text":"

FileList > gui > magnum > graphics.hpp

Go to the source code of this file

"},{"location":"api/graphics_8hpp/#namespaces","title":"Namespaces","text":"Type Name namespace robot_dart namespace gui namespace magnum"},{"location":"api/graphics_8hpp/#classes","title":"Classes","text":"Type Name class Graphics

The documentation for this class was generated from the following file robot_dart/gui/magnum/graphics.hpp

"},{"location":"api/graphics_8hpp_source/","title":"File graphics.hpp","text":"

File List > gui > magnum > graphics.hpp

Go to the documentation of this file

#ifndef ROBOT_DART_GUI_MAGNUM_GRAPHICS_HPP\n#define ROBOT_DART_GUI_MAGNUM_GRAPHICS_HPP\n#include <robot_dart/gui/magnum/base_graphics.hpp>\nnamespace robot_dart {\nnamespace gui {\nnamespace magnum {\nclass Graphics : public BaseGraphics<GlfwApplication> {\npublic:\nGraphics(const GraphicsConfiguration& configuration = default_configuration()) : BaseGraphics<GlfwApplication>(configuration) {}\n~Graphics() {}\nvoid set_simu(RobotDARTSimu* simu) override;\nstatic GraphicsConfiguration default_configuration();\n};\n} // namespace magnum\n} // namespace gui\n} // namespace robot_dart\n#endif\n
"},{"location":"api/dir_2f8612d80f6bb57c97efd4c82e0df286/","title":"Dir robot_dart/gui/magnum/gs","text":"

FileList > gs

"},{"location":"api/dir_2f8612d80f6bb57c97efd4c82e0df286/#files","title":"Files","text":"Type Name file camera.cpp file camera.hpp file create_compatibility_shader.hpp file cube_map.cpp file cube_map.hpp file cube_map_color.cpp file cube_map_color.hpp file helper.cpp file helper.hpp file light.cpp file light.hpp file material.cpp file material.hpp file phong_multi_light.cpp file phong_multi_light.hpp file shadow_map.cpp file shadow_map.hpp file shadow_map_color.cpp file shadow_map_color.hpp

The documentation for this class was generated from the following file robot_dart/gui/magnum/gs/

"},{"location":"api/gs_2camera_8cpp/","title":"File camera.cpp","text":"

FileList > gs > camera.cpp

Go to the source code of this file

"},{"location":"api/gs_2camera_8cpp/#namespaces","title":"Namespaces","text":"Type Name namespace robot_dart namespace gui namespace magnum namespace gs

The documentation for this class was generated from the following file robot_dart/gui/magnum/gs/camera.cpp

"},{"location":"api/gs_2camera_8cpp_source/","title":"Macro Syntax Error","text":"

Line 204 in Markdown file: expected name or number

                    return {{projection[0][0], 0., 0.},\n

"},{"location":"api/gs_2camera_8hpp/","title":"File camera.hpp","text":"

FileList > gs > camera.hpp

Go to the source code of this file

"},{"location":"api/gs_2camera_8hpp/#namespaces","title":"Namespaces","text":"Type Name namespace robot_dart namespace gui namespace magnum namespace gs namespace subprocess"},{"location":"api/gs_2camera_8hpp/#classes","title":"Classes","text":"Type Name class Camera

The documentation for this class was generated from the following file robot_dart/gui/magnum/gs/camera.hpp

"},{"location":"api/gs_2camera_8hpp_source/","title":"File camera.hpp","text":"

File List > gs > camera.hpp

Go to the documentation of this file

#ifndef ROBOT_DART_GUI_MAGNUM_GS_CAMERA_HPP\n#define ROBOT_DART_GUI_MAGNUM_GS_CAMERA_HPP\n#include <robot_dart/gui/magnum/gs/light.hpp>\n#include <robot_dart/gui/magnum/types.hpp>\n#include <robot_dart/robot_dart_simu.hpp>\n#include <Corrade/Containers/Optional.h>\n#include <Magnum/GL/Mesh.h>\n#include <Magnum/Image.h>\n#include <Magnum/Shaders/DistanceFieldVector.h>\n#include <Magnum/Shaders/VertexColor.h>\n#include <Magnum/Text/Renderer.h>\nnamespace subprocess {\nclass popen;\n}\nnamespace robot_dart {\nnamespace gui {\nnamespace magnum {\nstruct DebugDrawData;\nnamespace gs {\n// This is partly code from the ThirdPersonCameraController of https://github.com/alexesDev/magnum-tips\nclass Camera : public Object3D {\npublic:\nexplicit Camera(Object3D& object, Magnum::Int width, Magnum::Int height);\n~Camera();\nCamera3D& camera() const;\nObject3D& root_object();\nObject3D& camera_object() const;\nCamera& set_viewport(const Magnum::Vector2i& size);\nCamera& move(const Magnum::Vector2i& shift);\nCamera& forward(Magnum::Float speed);\nCamera& strafe(Magnum::Float speed);\nCamera& set_speed(const Magnum::Vector2& speed);\nCamera& set_near_plane(Magnum::Float near_plane);\nCamera& set_far_plane(Magnum::Float far_plane);\nCamera& set_fov(Magnum::Float fov);\nCamera& set_camera_params(Magnum::Float near_plane, Magnum::Float far_plane, Magnum::Float fov, Magnum::Int width, Magnum::Int height);\nMagnum::Vector2 speed() const { return _speed; }\nMagnum::Float near_plane() const { return _near_plane; }\nMagnum::Float far_plane() const { return _far_plane; }\nMagnum::Float fov() const { return static_cast<Magnum::Float>(_fov); }\nMagnum::Int width() const { return _camera->viewport()[0]; }\nMagnum::Int height() const { return _camera->viewport()[1]; }\nMagnum::Matrix3 intrinsic_matrix() const;\nMagnum::Matrix4 extrinsic_matrix() const;\nCamera& look_at(const Magnum::Vector3& camera, const Magnum::Vector3& center, const Magnum::Vector3& up = Magnum::Vector3::zAxis());\nvoid transform_lights(std::vector<gs::Light>& lights) const;\nvoid record(bool recording, bool recording_depth = false)\n{\n_recording = recording;\n_recording_depth = recording_depth;\n}\n// FPS is mandatory here (compared to Graphics and CameraOSR)\nvoid record_video(const std::string& video_fname, int fps);\nbool recording() { return _recording; }\nbool recording_depth() { return _recording_depth; }\nCorrade::Containers::Optional<Magnum::Image2D>& image() { return _image; }\nCorrade::Containers::Optional<Magnum::Image2D>& depth_image() { return _depth_image; }\nvoid draw(Magnum::SceneGraph::DrawableGroup3D& drawables, Magnum::GL::AbstractFramebuffer& framebuffer, Magnum::PixelFormat format, RobotDARTSimu* simu, const DebugDrawData& debug_data, bool draw_debug = true);\nprivate:\nObject3D* _yaw_object;\nObject3D* _pitch_object;\nObject3D* _camera_object;\nCamera3D* _camera;\nMagnum::Vector2 _speed{-0.01f, 0.01f};\nMagnum::Vector3 _up, _front, _right;\nMagnum::Float _aspect_ratio, _near_plane, _far_plane;\nMagnum::Rad _fov;\nMagnum::Int _width, _height;\nbool _recording = false, _recording_depth = false;\nbool _recording_video = false;\nCorrade::Containers::Optional<Magnum::Image2D> _image, _depth_image;\nsubprocess::popen* _ffmpeg_process = nullptr;\nvoid _clean_up_subprocess();\n};\n} // namespace gs\n} // namespace magnum\n} // namespace gui\n} // namespace robot_dart\n#endif\n
"},{"location":"api/create__compatibility__shader_8hpp/","title":"File create_compatibility_shader.hpp","text":"

FileList > gs > create_compatibility_shader.hpp

Go to the source code of this file

"},{"location":"api/create__compatibility__shader_8hpp/#namespaces","title":"Namespaces","text":"Type Name namespace Magnum namespace Shaders namespace Implementation namespace robot_dart namespace gui namespace magnum namespace gs

The documentation for this class was generated from the following file robot_dart/gui/magnum/gs/create_compatibility_shader.hpp

"},{"location":"api/create__compatibility__shader_8hpp_source/","title":"File create_compatibility_shader.hpp","text":"

File List > gs > create_compatibility_shader.hpp

Go to the documentation of this file

#ifndef Magnum_Shaders_Implementation_CreateCompatibilityShader_h\n#define Magnum_Shaders_Implementation_CreateCompatibilityShader_h\n/*\n    This file is part of Magnum.\n    Copyright \u00a9 2010, 2011, 2012, 2013, 2014, 2015, 2016, 2017, 2018\n              Vladim\u00edr Vondru\u0161 <mosra@centrum.cz>\n    Permission is hereby granted, free of charge, to any person obtaining a\n    copy of this software and associated documentation files (the \"Software\"),\n    to deal in the Software without restriction, including without limitation\n    the rights to use, copy, modify, merge, publish, distribute, sublicense,\n    and/or sell copies of the Software, and to permit persons to whom the\n    Software is furnished to do so, subject to the following conditions:\n    The above copyright notice and this permission notice shall be included\n    in all copies or substantial portions of the Software.\n    THE SOFTWARE IS PROVIDED \"AS IS\", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR\n    IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,\n    FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL\n    THE AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER\n    LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING\n    FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER\n    DEALINGS IN THE SOFTWARE.\n*/\n#include <Corrade/Utility/Resource.h>\n#include <Magnum/GL/Context.h>\n#include <Magnum/GL/Extensions.h>\n#include <Magnum/GL/Shader.h>\n#include <string>\nnamespace robot_dart {\nnamespace gui {\nnamespace magnum {\nnamespace gs {\nnamespace {\nenum : Magnum::Int { AmbientTextureLayer = 0,\nDiffuseTextureLayer = 1,\nSpecularTextureLayer = 2 };\n}\n} // namespace gs\n} // namespace magnum\n} // namespace gui\n} // namespace robot_dart\nnamespace Magnum {\nnamespace Shaders {\nnamespace Implementation {\ninline GL::Shader createCompatibilityShader(const Utility::Resource& rs, GL::Version version, GL::Shader::Type type)\n{\nGL::Shader shader(version, type);\n#ifndef MAGNUM_TARGET_GLES\nif (GL::Context::current().isExtensionDisabled<GL::Extensions::ARB::explicit_attrib_location>(version))\nshader.addSource(\"#define DISABLE_GL_ARB_explicit_attrib_location\\n\");\nif (GL::Context::current().isExtensionDisabled<GL::Extensions::ARB::shading_language_420pack>(version))\nshader.addSource(\"#define DISABLE_GL_ARB_shading_language_420pack\\n\");\nif (GL::Context::current().isExtensionDisabled<GL::Extensions::ARB::explicit_uniform_location>(version))\nshader.addSource(\"#define DISABLE_GL_ARB_explicit_uniform_location\\n\");\n#endif\n#ifndef MAGNUM_TARGET_GLES2\nif (type == GL::Shader::Type::Vertex && GL::Context::current().isExtensionDisabled<GL::Extensions::MAGNUM::shader_vertex_id>(version))\nshader.addSource(\"#define DISABLE_GL_MAGNUM_shader_vertex_id\\n\");\n#endif\n/* My Android emulator (running on NVidia) doesn't define GL_ES\n       preprocessor macro, thus *all* the stock shaders fail to compile */\n#ifdef CORRADE_TARGET_ANDROID\nshader.addSource(\"#ifndef GL_ES\\n#define GL_ES 1\\n#endif\\n\");\n#endif\nshader.addSource(rs.get(\"compatibility.glsl\"));\nreturn shader;\n}\n} // namespace Implementation\n} // namespace Shaders\n} // namespace Magnum\n#endif\n
"},{"location":"api/cube__map_8cpp/","title":"File cube_map.cpp","text":"

FileList > gs > cube_map.cpp

Go to the source code of this file

"},{"location":"api/cube__map_8cpp/#namespaces","title":"Namespaces","text":"Type Name namespace robot_dart namespace gui namespace magnum namespace gs

The documentation for this class was generated from the following file robot_dart/gui/magnum/gs/cube_map.cpp

"},{"location":"api/cube__map_8cpp_source/","title":"File cube_map.cpp","text":"

File List > gs > cube_map.cpp

Go to the documentation of this file

#include \"cube_map.hpp\"\n#include \"create_compatibility_shader.hpp\"\n#include <Magnum/GL/Texture.h>\nnamespace robot_dart {\nnamespace gui {\nnamespace magnum {\nnamespace gs {\nCubeMap::CubeMap(CubeMap::Flags flags) : _flags(flags)\n{\nCorrade::Utility::Resource rs_shaders(\"RobotDARTShaders\");\nconst Magnum::GL::Version version = Magnum::GL::Version::GL320;\nMagnum::GL::Shader vert = Magnum::Shaders::Implementation::createCompatibilityShader(\nrs_shaders, version, Magnum::GL::Shader::Type::Vertex);\nMagnum::GL::Shader geom = Magnum::Shaders::Implementation::createCompatibilityShader(\nrs_shaders, version, Magnum::GL::Shader::Type::Geometry);\nMagnum::GL::Shader frag = Magnum::Shaders::Implementation::createCompatibilityShader(\nrs_shaders, version, Magnum::GL::Shader::Type::Fragment);\nstd::string defines = \"#define POSITION_ATTRIBUTE_LOCATION \" + std::to_string(Position::Location) + \"\\n\";\ndefines += \"#define TEXTURECOORDINATES_ATTRIBUTE_LOCATION \" + std::to_string(TextureCoordinates::Location) + \"\\n\";\nvert.addSource(flags ? \"#define TEXTURED\\n\" : \"\")\n.addSource(defines)\n.addSource(rs_shaders.get(\"CubeMap.vert\"));\ngeom.addSource(flags ? \"#define TEXTURED\\n\" : \"\")\n.addSource(rs_shaders.get(\"CubeMap.geom\"));\nfrag.addSource(flags ? \"#define TEXTURED\\n\" : \"\")\n.addSource(rs_shaders.get(\"CubeMap.frag\"));\nCORRADE_INTERNAL_ASSERT_OUTPUT(Magnum::GL::Shader::compile({vert, geom, frag}));\nattachShaders({vert, geom, frag});\nif (!Magnum::GL::Context::current().isExtensionSupported<Magnum::GL::Extensions::ARB::explicit_attrib_location>(version)) {\nbindAttributeLocation(Position::Location, \"position\");\nif (flags)\nbindAttributeLocation(TextureCoordinates::Location, \"textureCoords\");\n}\nCORRADE_INTERNAL_ASSERT_OUTPUT(link());\nif (!Magnum::GL::Context::current().isExtensionSupported<Magnum::GL::Extensions::ARB::explicit_uniform_location>(version)) {\n_transformation_matrix_uniform = uniformLocation(\"transformationMatrix\");\n_shadow_matrices_uniform = uniformLocation(\"shadowMatrices[0]\");\n_light_position_uniform = uniformLocation(\"lightPosition\");\n_far_plane_uniform = uniformLocation(\"farPlane\");\n_light_index_uniform = uniformLocation(\"lightIndex\");\n_diffuse_color_uniform = uniformLocation(\"diffuseColor\");\n}\n}\nCubeMap::CubeMap(Magnum::NoCreateT) noexcept : Magnum::GL::AbstractShaderProgram{Magnum::NoCreate} {}\nCubeMap::Flags CubeMap::flags() const { return _flags; }\nCubeMap& CubeMap::set_transformation_matrix(const Magnum::Matrix4& matrix)\n{\nsetUniform(_transformation_matrix_uniform, matrix);\nreturn *this;\n}\nCubeMap& CubeMap::set_shadow_matrices(Magnum::Matrix4 matrices[6])\n{\nfor (size_t i = 0; i < 6; i++)\nsetUniform(_shadow_matrices_uniform + i, matrices[i]);\nreturn *this;\n}\nCubeMap& CubeMap::set_light_position(const Magnum::Vector3& position)\n{\nsetUniform(_light_position_uniform, position);\nreturn *this;\n}\nCubeMap& CubeMap::set_far_plane(Magnum::Float far_plane)\n{\nsetUniform(_far_plane_uniform, far_plane);\nreturn *this;\n}\nCubeMap& CubeMap::set_light_index(Magnum::Int index)\n{\nsetUniform(_light_index_uniform, index);\nreturn *this;\n}\nCubeMap& CubeMap::set_material(Material& material)\n{\nif (material.has_diffuse_texture() && (_flags & Flag::DiffuseTexture)) {\n(*material.diffuse_texture()).bind(DiffuseTextureLayer);\nsetUniform(_diffuse_color_uniform, Magnum::Color4{1.0f});\n}\nelse\nsetUniform(_diffuse_color_uniform, material.diffuse_color());\nreturn *this;\n}\n} // namespace gs\n} // namespace magnum\n} // namespace gui\n} // namespace robot_dart\n
"},{"location":"api/cube__map_8hpp/","title":"File cube_map.hpp","text":"

FileList > gs > cube_map.hpp

Go to the source code of this file

"},{"location":"api/cube__map_8hpp/#namespaces","title":"Namespaces","text":"Type Name namespace robot_dart namespace gui namespace magnum namespace gs"},{"location":"api/cube__map_8hpp/#classes","title":"Classes","text":"Type Name class CubeMap

The documentation for this class was generated from the following file robot_dart/gui/magnum/gs/cube_map.hpp

"},{"location":"api/cube__map_8hpp_source/","title":"File cube_map.hpp","text":"

File List > gs > cube_map.hpp

Go to the documentation of this file

#ifndef ROBOT_DART_GUI_MAGNUM_GS_CUBE_MAP_HPP\n#define ROBOT_DART_GUI_MAGNUM_GS_CUBE_MAP_HPP\n#include <robot_dart/gui/magnum/gs/material.hpp>\n#include <Corrade/Containers/ArrayView.h>\n#include <Corrade/Containers/Reference.h>\n#include <Corrade/Utility/Assert.h>\n#include <Magnum/GL/AbstractShaderProgram.h>\n#include <Magnum/Math/Color.h>\n#include <Magnum/Math/Matrix4.h>\n#include <Magnum/Shaders/Generic.h>\nnamespace robot_dart {\nnamespace gui {\nnamespace magnum {\nnamespace gs {\nclass CubeMap : public Magnum::GL::AbstractShaderProgram {\npublic:\nusing Position = Magnum::Shaders::Generic3D::Position;\nusing TextureCoordinates = Magnum::Shaders::Generic3D::TextureCoordinates;\nenum class Flag : Magnum::UnsignedByte {\nDiffuseTexture = 1 << 0, };\nusing Flags = Magnum::Containers::EnumSet<Flag>;\nexplicit CubeMap(Flags flags = {});\nexplicit CubeMap(Magnum::NoCreateT) noexcept;\nFlags flags() const;\nCubeMap& set_transformation_matrix(const Magnum::Matrix4& matrix);\nCubeMap& set_shadow_matrices(Magnum::Matrix4 matrices[6]);\nCubeMap& set_light_position(const Magnum::Vector3& position);\nCubeMap& set_far_plane(Magnum::Float far_plane);\nCubeMap& set_light_index(Magnum::Int index);\nCubeMap& set_material(Material& material);\nprivate:\nFlags _flags;\nMagnum::Int _transformation_matrix_uniform{0},\n_shadow_matrices_uniform{5},\n_light_position_uniform{1},\n_far_plane_uniform{2},\n_light_index_uniform{3},\n_diffuse_color_uniform{4};\n};\nCORRADE_ENUMSET_OPERATORS(CubeMap::Flags)\n} // namespace gs\n} // namespace magnum\n} // namespace gui\n} // namespace robot_dart\n#endif\n
"},{"location":"api/cube__map__color_8cpp/","title":"File cube_map_color.cpp","text":"

FileList > gs > cube_map_color.cpp

Go to the source code of this file

"},{"location":"api/cube__map__color_8cpp/#namespaces","title":"Namespaces","text":"Type Name namespace robot_dart namespace gui namespace magnum namespace gs

The documentation for this class was generated from the following file robot_dart/gui/magnum/gs/cube_map_color.cpp

"},{"location":"api/cube__map__color_8cpp_source/","title":"File cube_map_color.cpp","text":"

File List > gs > cube_map_color.cpp

Go to the documentation of this file

#include \"cube_map_color.hpp\"\n#include \"create_compatibility_shader.hpp\"\n#include <Magnum/GL/CubeMapTextureArray.h>\n#include <Magnum/GL/Texture.h>\nnamespace robot_dart {\nnamespace gui {\nnamespace magnum {\nnamespace gs {\nCubeMapColor::CubeMapColor(CubeMapColor::Flags flags) : _flags(flags)\n{\nCorrade::Utility::Resource rs_shaders(\"RobotDARTShaders\");\nconst Magnum::GL::Version version = Magnum::GL::Version::GL320;\nMagnum::GL::Shader vert = Magnum::Shaders::Implementation::createCompatibilityShader(\nrs_shaders, version, Magnum::GL::Shader::Type::Vertex);\nMagnum::GL::Shader geom = Magnum::Shaders::Implementation::createCompatibilityShader(\nrs_shaders, version, Magnum::GL::Shader::Type::Geometry);\nMagnum::GL::Shader frag = Magnum::Shaders::Implementation::createCompatibilityShader(\nrs_shaders, version, Magnum::GL::Shader::Type::Fragment);\nstd::string defines = \"#define POSITION_ATTRIBUTE_LOCATION \" + std::to_string(Position::Location) + \"\\n\";\ndefines += \"#define TEXTURECOORDINATES_ATTRIBUTE_LOCATION \" + std::to_string(TextureCoordinates::Location) + \"\\n\";\nvert.addSource(flags ? \"#define TEXTURED\\n\" : \"\")\n.addSource(defines)\n.addSource(rs_shaders.get(\"CubeMap.vert\"));\ngeom.addSource(flags ? \"#define TEXTURED\\n\" : \"\")\n.addSource(rs_shaders.get(\"CubeMap.geom\"));\nfrag.addSource(flags ? \"#define TEXTURED\\n\" : \"\")\n.addSource(rs_shaders.get(\"CubeMapColor.frag\"));\nCORRADE_INTERNAL_ASSERT_OUTPUT(Magnum::GL::Shader::compile({vert, geom, frag}));\nattachShaders({vert, geom, frag});\nif (!Magnum::GL::Context::current().isExtensionSupported<Magnum::GL::Extensions::ARB::explicit_attrib_location>(version)) {\nbindAttributeLocation(Position::Location, \"position\");\nif (flags)\nbindAttributeLocation(TextureCoordinates::Location, \"textureCoords\");\n}\nCORRADE_INTERNAL_ASSERT_OUTPUT(link());\nif (!Magnum::GL::Context::current().isExtensionSupported<Magnum::GL::Extensions::ARB::explicit_uniform_location>(version)) {\n_transformation_matrix_uniform = uniformLocation(\"transformationMatrix\");\n_shadow_matrices_uniform = uniformLocation(\"shadowMatrices[0]\");\n_light_position_uniform = uniformLocation(\"lightPosition\");\n_far_plane_uniform = uniformLocation(\"farPlane\");\n_light_index_uniform = uniformLocation(\"lightIndex\");\n_diffuse_color_uniform = uniformLocation(\"diffuseColor\");\n}\nif (!Magnum::GL::Context::current()\n.isExtensionSupported<Magnum::GL::Extensions::ARB::shading_language_420pack>(version)) {\nsetUniform(uniformLocation(\"cubeMapTextures\"), _cube_map_textures_location);\nif (flags) {\nif (flags & Flag::DiffuseTexture)\nsetUniform(uniformLocation(\"diffuseTexture\"), DiffuseTextureLayer);\n}\n}\n}\nCubeMapColor::CubeMapColor(Magnum::NoCreateT) noexcept : Magnum::GL::AbstractShaderProgram{Magnum::NoCreate} {}\nCubeMapColor::Flags CubeMapColor::flags() const { return _flags; }\nCubeMapColor& CubeMapColor::set_transformation_matrix(const Magnum::Matrix4& matrix)\n{\nsetUniform(_transformation_matrix_uniform, matrix);\nreturn *this;\n}\nCubeMapColor& CubeMapColor::set_shadow_matrices(Magnum::Matrix4 matrices[6])\n{\nfor (size_t i = 0; i < 6; i++)\nsetUniform(_shadow_matrices_uniform + i, matrices[i]);\nreturn *this;\n}\nCubeMapColor& CubeMapColor::set_light_position(const Magnum::Vector3& position)\n{\nsetUniform(_light_position_uniform, position);\nreturn *this;\n}\nCubeMapColor& CubeMapColor::set_far_plane(Magnum::Float far_plane)\n{\nsetUniform(_far_plane_uniform, far_plane);\nreturn *this;\n}\nCubeMapColor& CubeMapColor::set_light_index(Magnum::Int index)\n{\nsetUniform(_light_index_uniform, index);\nreturn *this;\n}\nCubeMapColor& CubeMapColor::set_material(Material& material)\n{\nif (material.has_diffuse_texture() && (_flags & Flag::DiffuseTexture)) {\n(*material.diffuse_texture()).bind(DiffuseTextureLayer);\nsetUniform(_diffuse_color_uniform, Magnum::Color4{1.0f});\n}\nelse\nsetUniform(_diffuse_color_uniform, material.diffuse_color());\nreturn *this;\n}\nCubeMapColor& CubeMapColor::bind_cube_map_texture(Magnum::GL::CubeMapTextureArray& texture)\n{\ntexture.bind(_cube_map_textures_location);\nreturn *this;\n}\n} // namespace gs\n} // namespace magnum\n} // namespace gui\n} // namespace robot_dart\n
"},{"location":"api/cube__map__color_8hpp/","title":"File cube_map_color.hpp","text":"

FileList > gs > cube_map_color.hpp

Go to the source code of this file

"},{"location":"api/cube__map__color_8hpp/#namespaces","title":"Namespaces","text":"Type Name namespace robot_dart namespace gui namespace magnum namespace gs"},{"location":"api/cube__map__color_8hpp/#classes","title":"Classes","text":"Type Name class CubeMapColor

The documentation for this class was generated from the following file robot_dart/gui/magnum/gs/cube_map_color.hpp

"},{"location":"api/cube__map__color_8hpp_source/","title":"File cube_map_color.hpp","text":"

File List > gs > cube_map_color.hpp

Go to the documentation of this file

#ifndef ROBOT_DART_GUI_MAGNUM_GS_CUBE_MAP_COLOR_HPP\n#define ROBOT_DART_GUI_MAGNUM_GS_CUBE_MAP_COLOR_HPP\n#include <robot_dart/gui/magnum/gs/material.hpp>\n#include <Corrade/Containers/ArrayView.h>\n#include <Corrade/Containers/Reference.h>\n#include <Corrade/Utility/Assert.h>\n#include <Magnum/GL/AbstractShaderProgram.h>\n#include <Magnum/Math/Color.h>\n#include <Magnum/Math/Matrix4.h>\n#include <Magnum/Shaders/Generic.h>\nnamespace robot_dart {\nnamespace gui {\nnamespace magnum {\nnamespace gs {\nclass CubeMapColor : public Magnum::GL::AbstractShaderProgram {\npublic:\nusing Position = Magnum::Shaders::Generic3D::Position;\nusing TextureCoordinates = Magnum::Shaders::Generic3D::TextureCoordinates;\nenum class Flag : Magnum::UnsignedByte {\nDiffuseTexture = 1 << 0, };\nusing Flags = Magnum::Containers::EnumSet<Flag>;\nexplicit CubeMapColor(Flags flags = {});\nexplicit CubeMapColor(Magnum::NoCreateT) noexcept;\nFlags flags() const;\nCubeMapColor& set_transformation_matrix(const Magnum::Matrix4& matrix);\nCubeMapColor& set_shadow_matrices(Magnum::Matrix4 matrices[6]);\nCubeMapColor& set_light_position(const Magnum::Vector3& position);\nCubeMapColor& set_far_plane(Magnum::Float far_plane);\nCubeMapColor& set_light_index(Magnum::Int index);\nCubeMapColor& set_material(Material& material);\nCubeMapColor& bind_cube_map_texture(Magnum::GL::CubeMapTextureArray& texture);\nprivate:\nFlags _flags;\nMagnum::Int _transformation_matrix_uniform{0},\n_shadow_matrices_uniform{5},\n_light_position_uniform{1},\n_far_plane_uniform{2},\n_light_index_uniform{3},\n_diffuse_color_uniform{4},\n_cube_map_textures_location{2};\n};\nCORRADE_ENUMSET_OPERATORS(CubeMapColor::Flags)\n} // namespace gs\n} // namespace magnum\n} // namespace gui\n} // namespace robot_dart\n#endif\n
"},{"location":"api/magnum_2gs_2helper_8cpp/","title":"File helper.cpp","text":"

FileList > gs > helper.cpp

Go to the source code of this file

"},{"location":"api/magnum_2gs_2helper_8cpp/#namespaces","title":"Namespaces","text":"Type Name namespace robot_dart namespace gui namespace magnum namespace gs

The documentation for this class was generated from the following file robot_dart/gui/magnum/gs/helper.cpp

"},{"location":"api/magnum_2gs_2helper_8cpp_source/","title":"File helper.cpp","text":"

File List > gs > helper.cpp

Go to the documentation of this file

#include \"helper.hpp\"\n#include <Corrade/Containers/ArrayViewStl.h>\n#include <Corrade/Containers/StridedArrayView.h>\n#include <Corrade/Utility/Algorithms.h>\n#include <Magnum/Math/Color.h>\n#include <Magnum/Math/PackingBatch.h>\nnamespace robot_dart {\nnamespace gui {\nnamespace magnum {\nnamespace gs {\nImage rgb_from_image(Magnum::Image2D* image)\n{\nImage img;\nimg.width = image->size().x();\nimg.height = image->size().y();\nimg.channels = 3;\nimg.data.resize(image->size().product() * sizeof(Magnum::Color3ub));\nCorrade::Containers::StridedArrayView2D<const Magnum::Color3ub> src = image->pixels<Magnum::Color3ub>().flipped<0>();\nCorrade::Containers::StridedArrayView2D<Magnum::Color3ub> dst{Corrade::Containers::arrayCast<Magnum::Color3ub>(Corrade::Containers::arrayView(img.data)), {std::size_t(image->size().y()), std::size_t(image->size().x())}};\nCorrade::Utility::copy(src, dst);\nreturn img;\n}\nGrayscaleImage depth_from_image(Magnum::Image2D* image, bool linearize, Magnum::Float near_plane, Magnum::Float far_plane)\n{\nGrayscaleImage img;\nimg.width = image->size().x();\nimg.height = image->size().y();\nimg.data.resize(image->size().product() * sizeof(uint8_t));\nstd::vector<Magnum::Float> data = std::vector<Magnum::Float>(image->size().product());\nCorrade::Containers::StridedArrayView2D<const Magnum::Float> src = image->pixels<Magnum::Float>().flipped<0>();\nCorrade::Containers::StridedArrayView2D<Magnum::Float> dst{Corrade::Containers::arrayCast<Magnum::Float>(Corrade::Containers::arrayView(data)), {std::size_t(image->size().y()), std::size_t(image->size().x())}};\nCorrade::Utility::copy(src, dst);\nif (linearize) {\nfor (auto& depth : data)\ndepth = (2.f * near_plane) / (far_plane + near_plane - depth * (far_plane - near_plane));\n}\nCorrade::Containers::StridedArrayView2D<uint8_t> new_dst{Corrade::Containers::arrayCast<uint8_t>(Corrade::Containers::arrayView(img.data)), {std::size_t(image->size().y()), std::size_t(image->size().x())}};\nMagnum::Math::packInto(dst, new_dst);\nreturn img;\n}\nDepthImage depth_array_from_image(Magnum::Image2D* image, Magnum::Float near_plane, Magnum::Float far_plane)\n{\nDepthImage img;\nimg.width = image->size().x();\nimg.height = image->size().y();\nstd::vector<Magnum::Float> data = std::vector<Magnum::Float>(image->size().product());\nCorrade::Containers::StridedArrayView2D<const Magnum::Float> src = image->pixels<Magnum::Float>().flipped<0>();\nCorrade::Containers::StridedArrayView2D<Magnum::Float> dst{Corrade::Containers::arrayCast<Magnum::Float>(Corrade::Containers::arrayView(data)), {std::size_t(image->size().y()), std::size_t(image->size().x())}};\nCorrade::Utility::copy(src, dst);\nimg.data = std::vector<double>(data.begin(), data.end());\ndouble zNear = static_cast<double>(near_plane);\ndouble zFar = static_cast<double>(far_plane);\n// zNear * zFar / (zFar + d * (zNear - zFar));\nfor (auto& depth : img.data)\n// depth = (2. * zNear) / (zFar + zNear - depth * (zFar - zNear));\ndepth = (zNear * zFar) / (zFar - depth * (zFar - zNear));\nreturn img;\n}\n} // namespace gs\n} // namespace magnum\n} // namespace gui\n} // namespace robot_dart\n
"},{"location":"api/magnum_2gs_2helper_8hpp/","title":"File helper.hpp","text":"

FileList > gs > helper.hpp

Go to the source code of this file

"},{"location":"api/magnum_2gs_2helper_8hpp/#namespaces","title":"Namespaces","text":"Type Name namespace robot_dart namespace gui namespace magnum namespace gs

The documentation for this class was generated from the following file robot_dart/gui/magnum/gs/helper.hpp

"},{"location":"api/magnum_2gs_2helper_8hpp_source/","title":"File helper.hpp","text":"

File List > gs > helper.hpp

Go to the documentation of this file

#ifndef ROBOT_DART_GUI_MAGNUM_GS_HELPER_HPP\n#define ROBOT_DART_GUI_MAGNUM_GS_HELPER_HPP\n#include <robot_dart/gui/helper.hpp>\n#include <vector>\n#include <Magnum/Image.h>\nnamespace robot_dart {\nnamespace gui {\nnamespace magnum {\nnamespace gs {\nImage rgb_from_image(Magnum::Image2D* image);\nGrayscaleImage depth_from_image(Magnum::Image2D* image, bool linearize = false, Magnum::Float near_plane = 0.f, Magnum::Float far_plane = 100.f);\nDepthImage depth_array_from_image(Magnum::Image2D* image, Magnum::Float near_plane = 0.f, Magnum::Float far_plane = 100.f);\n} // namespace gs\n} // namespace magnum\n} // namespace gui\n} // namespace robot_dart\n#endif\n
"},{"location":"api/light_8cpp/","title":"File light.cpp","text":"

FileList > gs > light.cpp

Go to the source code of this file

"},{"location":"api/light_8cpp/#namespaces","title":"Namespaces","text":"Type Name namespace robot_dart namespace gui namespace magnum namespace gs

The documentation for this class was generated from the following file robot_dart/gui/magnum/gs/light.cpp

"},{"location":"api/light_8cpp_source/","title":"File light.cpp","text":"

File List > gs > light.cpp

Go to the documentation of this file

#include \"light.hpp\"\n#include <Magnum/GL/Texture.h>\nnamespace robot_dart {\nnamespace gui {\nnamespace magnum {\nnamespace gs {\nLight::Light() : _position(Magnum::Vector4{0.f, 0.f, 0.f, 1.f}),\n_transformed_position(_position),\n_material(Material()),\n_spot_direction(Magnum::Vector3{1.f, 0.f, 0.f}),\n_spot_exponent(1.f),\n_spot_cut_off(Magnum::Math::Constants<Magnum::Float>::pi()),\n_attenuation(Magnum::Vector4{0.f, 0.f, 1.f, 1.f}),\n_cast_shadows(true) {}\nLight::Light(const Magnum::Vector4& position, const Material& material, const Magnum::Vector3& spot_direction,\nMagnum::Float spot_exponent, Magnum::Float spot_cut_off, const Magnum::Vector4& attenuation, bool cast_shadows) : _position(position),\n_transformed_position(_position),\n_material(material),\n_spot_direction(spot_direction),\n_spot_exponent(spot_exponent),\n_spot_cut_off(spot_cut_off),\n_attenuation(attenuation),\n_cast_shadows(cast_shadows) {}\n// Magnum::Vector4& Light::position();\nMagnum::Vector4 Light::position() const { return _position; }\nMagnum::Vector4& Light::transformed_position() { return _transformed_position; }\nMagnum::Vector4 Light::transformed_position() const { return _transformed_position; }\nMaterial& Light::material() { return _material; }\nMaterial Light::material() const { return _material; }\n// Magnum::Vector3& Light::spot_direction() { return _spot_direction; }\nMagnum::Vector3 Light::spot_direction() const { return _spot_direction; }\nMagnum::Vector3& Light::transformed_spot_direction() { return _transformed_spot_direction; }\nMagnum::Vector3 Light::transformed_spot_direction() const { return _transformed_spot_direction; }\nMagnum::Float& Light::spot_exponent() { return _spot_exponent; }\nMagnum::Float Light::spot_exponent() const { return _spot_exponent; }\nMagnum::Float& Light::spot_cut_off() { return _spot_cut_off; }\nMagnum::Float Light::spot_cut_off() const { return _spot_cut_off; }\nMagnum::Vector4& Light::attenuation() { return _attenuation; }\nMagnum::Vector4 Light::attenuation() const { return _attenuation; }\nMagnum::Matrix4 Light::shadow_matrix() const { return _shadow_transform; }\nbool Light::casts_shadows() const { return _cast_shadows; }\nLight& Light::set_position(const Magnum::Vector4& position)\n{\n_position = position;\n_transformed_position = position;\nreturn *this;\n}\nLight& Light::set_transformed_position(const Magnum::Vector4& transformed_position)\n{\n_transformed_position = transformed_position;\nreturn *this;\n}\nLight& Light::set_material(const Material& material)\n{\n_material = material;\nreturn *this;\n}\nLight& Light::set_spot_direction(const Magnum::Vector3& spot_direction)\n{\n_spot_direction = spot_direction;\n_transformed_spot_direction = _spot_direction;\nreturn *this;\n}\nLight& Light::set_transformed_spot_direction(const Magnum::Vector3& transformed_spot_direction)\n{\n_transformed_spot_direction = transformed_spot_direction;\nreturn *this;\n}\nLight& Light::set_spot_exponent(Magnum::Float spot_exponent)\n{\n_spot_exponent = spot_exponent;\nreturn *this;\n}\nLight& Light::set_spot_cut_off(Magnum::Float spot_cut_off)\n{\n_spot_cut_off = spot_cut_off;\nreturn *this;\n}\nLight& Light::set_attenuation(const Magnum::Vector4& attenuation)\n{\n_attenuation = attenuation;\nreturn *this;\n}\nLight& Light::set_shadow_matrix(const Magnum::Matrix4& shadowTransform)\n{\n_shadow_transform = shadowTransform;\nreturn *this;\n}\nLight& Light::set_casts_shadows(bool cast_shadows)\n{\n_cast_shadows = cast_shadows;\nreturn *this;\n}\n} // namespace gs\n} // namespace magnum\n} // namespace gui\n} // namespace robot_dart\n
"},{"location":"api/light_8hpp/","title":"File light.hpp","text":"

FileList > gs > light.hpp

Go to the source code of this file

"},{"location":"api/light_8hpp/#namespaces","title":"Namespaces","text":"Type Name namespace robot_dart namespace gui namespace magnum namespace gs"},{"location":"api/light_8hpp/#classes","title":"Classes","text":"Type Name class Light

The documentation for this class was generated from the following file robot_dart/gui/magnum/gs/light.hpp

"},{"location":"api/light_8hpp_source/","title":"File light.hpp","text":"

File List > gs > light.hpp

Go to the documentation of this file

#ifndef ROBOT_DART_GUI_MAGNUM_GS_LIGHT_HPP\n#define ROBOT_DART_GUI_MAGNUM_GS_LIGHT_HPP\n#include <robot_dart/gui/magnum/gs/material.hpp>\n#include <Magnum/Math/Matrix4.h>\nnamespace robot_dart {\nnamespace gui {\nnamespace magnum {\nnamespace gs {\nclass Light {\npublic:\nLight();\nLight(const Magnum::Vector4& position, const Material& material, const Magnum::Vector3& spot_direction,\nMagnum::Float spot_exponent, Magnum::Float spot_cut_off, const Magnum::Vector4& attenuation, bool cast_shadows = true);\n// Magnum::Vector4& position();\nMagnum::Vector4 position() const;\nMagnum::Vector4& transformed_position();\nMagnum::Vector4 transformed_position() const;\nMaterial& material();\nMaterial material() const;\n// Magnum::Vector3& spot_direction();\nMagnum::Vector3 spot_direction() const;\nMagnum::Vector3& transformed_spot_direction();\nMagnum::Vector3 transformed_spot_direction() const;\nMagnum::Float& spot_exponent();\nMagnum::Float spot_exponent() const;\nMagnum::Float& spot_cut_off();\nMagnum::Float spot_cut_off() const;\nMagnum::Vector4& attenuation();\nMagnum::Vector4 attenuation() const;\nMagnum::Matrix4 shadow_matrix() const;\nbool casts_shadows() const;\nLight& set_position(const Magnum::Vector4& position);\nLight& set_transformed_position(const Magnum::Vector4& transformed_position);\nLight& set_material(const Material& material);\nLight& set_spot_direction(const Magnum::Vector3& spot_direction);\nLight& set_transformed_spot_direction(const Magnum::Vector3& transformed_spot_direction);\nLight& set_spot_exponent(Magnum::Float spot_exponent);\nLight& set_spot_cut_off(Magnum::Float spot_cut_off);\nLight& set_attenuation(const Magnum::Vector4& attenuation);\nLight& set_shadow_matrix(const Magnum::Matrix4& shadowTransform);\nLight& set_casts_shadows(bool cast_shadows);\nprotected:\n// Position for point-lights and spot-lights\n// Direction for directional lights (if position.w == 0)\nMagnum::Vector4 _position;\n// TO-DO: Handle dirtiness of transformed position\nMagnum::Vector4 _transformed_position;\nMaterial _material;\nMagnum::Vector3 _spot_direction;\n// TO-DO: Handle dirtiness of transformed spot direction\nMagnum::Vector3 _transformed_spot_direction;\nMagnum::Float _spot_exponent, _spot_cut_off;\n// Attenuation is: intensity/(constant + d * (linear + quadratic * d)\n// where d is the distance from the light position to the vertex position.\n//\n// (constant,linear,quadratic,intensity)\nMagnum::Vector4 _attenuation;\n// Shadow-Matrix\nMagnum::Matrix4 _shadow_transform{};\n// Whether it casts shadows\nbool _cast_shadows = true;\n};\n// Helpers for creating lights\ninline Light create_point_light(const Magnum::Vector3& position, const Material& material,\nMagnum::Float intensity, const Magnum::Vector3& attenuationTerms)\n{\nLight light;\nlight.set_material(material);\nlight.set_position(Magnum::Vector4{position, 1.f})\n.set_attenuation(Magnum::Vector4{attenuationTerms, intensity});\nreturn light;\n}\ninline Light create_spot_light(const Magnum::Vector3& position, const Material& material,\nconst Magnum::Vector3& spot_direction, Magnum::Float spot_exponent, Magnum::Float spot_cut_off,\nMagnum::Float intensity, const Magnum::Vector3& attenuationTerms)\n{\nreturn Light(Magnum::Vector4{position, 1.f}, material, spot_direction, spot_exponent, spot_cut_off,\nMagnum::Vector4{attenuationTerms, intensity});\n}\ninline Light create_directional_light(\nconst Magnum::Vector3& direction, const Material& material)\n{\nLight light;\nlight.set_material(material);\nlight.set_position(Magnum::Vector4{direction, 0.f});\nreturn light;\n}\n} // namespace gs\n} // namespace magnum\n} // namespace gui\n} // namespace robot_dart\n#endif\n
"},{"location":"api/material_8cpp/","title":"File material.cpp","text":"

FileList > gs > material.cpp

Go to the source code of this file

"},{"location":"api/material_8cpp/#namespaces","title":"Namespaces","text":"Type Name namespace robot_dart namespace gui namespace magnum namespace gs

The documentation for this class was generated from the following file robot_dart/gui/magnum/gs/material.cpp

"},{"location":"api/material_8cpp_source/","title":"File material.cpp","text":"

File List > gs > material.cpp

Go to the documentation of this file

#include \"material.hpp\"\n#include <Magnum/GL/Texture.h>\nnamespace robot_dart {\nnamespace gui {\nnamespace magnum {\nnamespace gs {\nMaterial::Material() : _ambient(Magnum::Color4{0.f, 0.f, 0.f, 1.f}),\n_diffuse(Magnum::Color4{0.f, 0.f, 0.f, 1.f}),\n_specular(Magnum::Color4{0.f, 0.f, 0.f, 1.f}),\n_shininess(2000.f) {}\nMaterial::Material(const Magnum::Color4& ambient, const Magnum::Color4& diffuse,\nconst Magnum::Color4& specular, Magnum::Float shininess) : _ambient(ambient),\n_diffuse(diffuse),\n_specular(specular),\n_shininess(shininess) {}\nMaterial::Material(Magnum::GL::Texture2D* ambient_texture,\nMagnum::GL::Texture2D* diffuse_texture,\nMagnum::GL::Texture2D* specular_texture, Magnum::Float shininess) : _ambient(Magnum::Color4{0.f, 0.f, 0.f, 1.f}),\n_diffuse(Magnum::Color4{0.f, 0.f, 0.f, 1.f}),\n_specular(Magnum::Color4{0.f, 0.f, 0.f, 1.f}),\n_shininess(shininess),\n_ambient_texture(ambient_texture),\n_diffuse_texture(diffuse_texture),\n_specular_texture(specular_texture) {}\nMagnum::Color4& Material::ambient_color() { return _ambient; }\nMagnum::Color4 Material::ambient_color() const { return _ambient; }\nMagnum::Color4& Material::diffuse_color() { return _diffuse; }\nMagnum::Color4 Material::diffuse_color() const { return _diffuse; }\nMagnum::Color4& Material::specular_color() { return _specular; }\nMagnum::Color4 Material::specular_color() const { return _specular; }\nMagnum::Float& Material::shininess() { return _shininess; }\nMagnum::Float Material::shininess() const { return _shininess; }\nMagnum::GL::Texture2D* Material::ambient_texture() { return _ambient_texture; }\nMagnum::GL::Texture2D* Material::diffuse_texture() { return _diffuse_texture; }\nMagnum::GL::Texture2D* Material::specular_texture() { return _specular_texture; }\nbool Material::has_ambient_texture() const { return _ambient_texture != NULL; }\nbool Material::has_diffuse_texture() const { return _diffuse_texture != NULL; }\nbool Material::has_specular_texture() const { return _specular_texture != NULL; }\nMaterial& Material::set_ambient_color(const Magnum::Color4& ambient)\n{\n_ambient = ambient;\nreturn *this;\n}\nMaterial& Material::set_diffuse_color(const Magnum::Color4& diffuse)\n{\n_diffuse = diffuse;\nreturn *this;\n}\nMaterial& Material::set_specular_color(const Magnum::Color4& specular)\n{\n_specular = specular;\nreturn *this;\n}\nMaterial& Material::set_shininess(Magnum::Float shininess)\n{\n_shininess = shininess;\nreturn *this;\n}\nMaterial& Material::set_ambient_texture(Magnum::GL::Texture2D* ambient_texture)\n{\n_ambient_texture = ambient_texture;\nreturn *this;\n}\nMaterial& Material::set_diffuse_texture(Magnum::GL::Texture2D* diffuse_texture)\n{\n_diffuse_texture = diffuse_texture;\nreturn *this;\n}\nMaterial& Material::set_specular_texture(Magnum::GL::Texture2D* specular_texture)\n{\n_specular_texture = specular_texture;\nreturn *this;\n}\n} // namespace gs\n} // namespace magnum\n} // namespace gui\n} // namespace robot_dart\n
"},{"location":"api/material_8hpp/","title":"File material.hpp","text":"

FileList > gs > material.hpp

Go to the source code of this file

"},{"location":"api/material_8hpp/#namespaces","title":"Namespaces","text":"Type Name namespace robot_dart namespace gui namespace magnum namespace gs"},{"location":"api/material_8hpp/#classes","title":"Classes","text":"Type Name class Material

The documentation for this class was generated from the following file robot_dart/gui/magnum/gs/material.hpp

"},{"location":"api/material_8hpp_source/","title":"File material.hpp","text":"

File List > gs > material.hpp

Go to the documentation of this file

#ifndef ROBOT_DART_GUI_MAGNUM_GS_MATERIAL_HPP\n#define ROBOT_DART_GUI_MAGNUM_GS_MATERIAL_HPP\n#include <Corrade/Containers/Optional.h>\n#include <Magnum/GL/GL.h>\n#include <Magnum/Magnum.h>\n#include <Magnum/Math/Color.h>\nnamespace robot_dart {\nnamespace gui {\nnamespace magnum {\nnamespace gs {\nclass Material {\npublic:\nMaterial();\nMaterial(const Magnum::Color4& ambient, const Magnum::Color4& diffuse,\nconst Magnum::Color4& specular, Magnum::Float shininess);\nMaterial(Magnum::GL::Texture2D* ambient_texture,\nMagnum::GL::Texture2D* diffuse_texture,\nMagnum::GL::Texture2D* specular_texture, Magnum::Float shininess);\nMagnum::Color4& ambient_color();\nMagnum::Color4 ambient_color() const;\nMagnum::Color4& diffuse_color();\nMagnum::Color4 diffuse_color() const;\nMagnum::Color4& specular_color();\nMagnum::Color4 specular_color() const;\nMagnum::Float& shininess();\nMagnum::Float shininess() const;\nMagnum::GL::Texture2D* ambient_texture();\nMagnum::GL::Texture2D* diffuse_texture();\nMagnum::GL::Texture2D* specular_texture();\nbool has_ambient_texture() const;\nbool has_diffuse_texture() const;\nbool has_specular_texture() const;\nMaterial& set_ambient_color(const Magnum::Color4& ambient);\nMaterial& set_diffuse_color(const Magnum::Color4& diffuse);\nMaterial& set_specular_color(const Magnum::Color4& specular);\nMaterial& set_shininess(Magnum::Float shininess);\nMaterial& set_ambient_texture(Magnum::GL::Texture2D* ambient_texture);\nMaterial& set_diffuse_texture(Magnum::GL::Texture2D* diffuse_texture);\nMaterial& set_specular_texture(Magnum::GL::Texture2D* specular_texture);\nprotected:\nMagnum::Color4 _ambient, _diffuse, _specular;\nMagnum::Float _shininess;\nMagnum::GL::Texture2D* _ambient_texture = NULL;\nMagnum::GL::Texture2D* _diffuse_texture = NULL;\nMagnum::GL::Texture2D* _specular_texture = NULL;\n};\n} // namespace gs\n} // namespace magnum\n} // namespace gui\n} // namespace robot_dart\n#endif\n
"},{"location":"api/phong__multi__light_8cpp/","title":"File phong_multi_light.cpp","text":"

FileList > gs > phong_multi_light.cpp

Go to the source code of this file

"},{"location":"api/phong__multi__light_8cpp/#namespaces","title":"Namespaces","text":"Type Name namespace robot_dart namespace gui namespace magnum namespace gs

The documentation for this class was generated from the following file robot_dart/gui/magnum/gs/phong_multi_light.cpp

"},{"location":"api/phong__multi__light_8cpp_source/","title":"File phong_multi_light.cpp","text":"

File List > gs > phong_multi_light.cpp

Go to the documentation of this file

#include \"phong_multi_light.hpp\"\n#include \"create_compatibility_shader.hpp\"\n#include <Magnum/GL/CubeMapTextureArray.h>\n#include <Magnum/GL/Texture.h>\n#include <Magnum/GL/TextureArray.h>\nnamespace robot_dart {\nnamespace gui {\nnamespace magnum {\nnamespace gs {\nPhongMultiLight::PhongMultiLight(PhongMultiLight::Flags flags, Magnum::Int max_lights) : _flags(flags), _max_lights(max_lights)\n{\nCorrade::Utility::Resource rs_shaders(\"RobotDARTShaders\");\nconst Magnum::GL::Version version = Magnum::GL::Version::GL320;\nMagnum::GL::Shader vert = Magnum::Shaders::Implementation::createCompatibilityShader(\nrs_shaders, version, Magnum::GL::Shader::Type::Vertex);\nMagnum::GL::Shader frag = Magnum::Shaders::Implementation::createCompatibilityShader(\nrs_shaders, version, Magnum::GL::Shader::Type::Fragment);\nstd::string defines = \"#define LIGHT_COUNT \" + std::to_string(_max_lights) + \"\\n\";\ndefines += \"#define POSITION_ATTRIBUTE_LOCATION \" + std::to_string(Position::Location) + \"\\n\";\ndefines += \"#define NORMAL_ATTRIBUTE_LOCATION \" + std::to_string(Normal::Location) + \"\\n\";\ndefines += \"#define TEXTURECOORDINATES_ATTRIBUTE_LOCATION \" + std::to_string(TextureCoordinates::Location) + \"\\n\";\nvert.addSource(flags ? \"#define TEXTURED\\n\" : \"\")\n.addSource(defines)\n.addSource(rs_shaders.get(\"PhongMultiLight.vert\"));\nfrag.addSource(flags & Flag::AmbientTexture ? \"#define AMBIENT_TEXTURE\\n\" : \"\")\n.addSource(flags & Flag::DiffuseTexture ? \"#define DIFFUSE_TEXTURE\\n\" : \"\")\n.addSource(flags & Flag::SpecularTexture ? \"#define SPECULAR_TEXTURE\\n\" : \"\")\n.addSource(defines)\n.addSource(rs_shaders.get(\"PhongMultiLight.frag\"));\nCORRADE_INTERNAL_ASSERT_OUTPUT(Magnum::GL::Shader::compile({vert, frag}));\nattachShaders({vert, frag});\nif (!Magnum::GL::Context::current().isExtensionSupported<Magnum::GL::Extensions::ARB::explicit_attrib_location>(version)) {\nbindAttributeLocation(Position::Location, \"position\");\nbindAttributeLocation(Normal::Location, \"normal\");\nif (flags)\nbindAttributeLocation(TextureCoordinates::Location, \"textureCoords\");\n}\nCORRADE_INTERNAL_ASSERT_OUTPUT(link());\n/* Get light matrices uniform */\n_lights_matrices_uniform = uniformLocation(\"lightMatrices[0]\");\nif (!Magnum::GL::Context::current().isExtensionSupported<Magnum::GL::Extensions::ARB::explicit_uniform_location>(version)) {\n_transformation_matrix_uniform = uniformLocation(\"transformationMatrix\");\n_projection_matrix_uniform = uniformLocation(\"projectionMatrix\");\n_camera_matrix_uniform = uniformLocation(\"cameraMatrix\");\n_normal_matrix_uniform = uniformLocation(\"normalMatrix\");\n_lights_uniform = uniformLocation(\"lights[0].position\");\n_lights_matrices_uniform = uniformLocation(\"lightMatrices[0]\");\n_ambient_color_uniform = uniformLocation(\"ambientColor\");\n_diffuse_color_uniform = uniformLocation(\"diffuseColor\");\n_specular_color_uniform = uniformLocation(\"specularColor\");\n_shininess_uniform = uniformLocation(\"shininess\");\n_far_plane_uniform = uniformLocation(\"farPlane\");\n_specular_strength_uniform = uniformLocation(\"specularStrength\");\n_is_shadowed_uniform = uniformLocation(\"isShadowed\");\n_transparent_shadows_uniform = uniformLocation(\"drawTransparentShadows\");\n}\nif (!Magnum::GL::Context::current()\n.isExtensionSupported<Magnum::GL::Extensions::ARB::shading_language_420pack>(version)) {\nsetUniform(uniformLocation(\"shadowTextures\"), _shadow_textures_location);\nsetUniform(uniformLocation(\"cubeMapTextures\"), _cube_map_textures_location);\nsetUniform(uniformLocation(\"shadowColorTextures\"), _shadow_color_textures_location);\nsetUniform(uniformLocation(\"cubeMapColorTextures\"), _cube_map_color_textures_location);\nif (flags) {\nif (flags & Flag::AmbientTexture)\nsetUniform(uniformLocation(\"ambientTexture\"), AmbientTextureLayer);\nif (flags & Flag::DiffuseTexture)\nsetUniform(uniformLocation(\"diffuseTexture\"), DiffuseTextureLayer);\nif (flags & Flag::SpecularTexture)\nsetUniform(uniformLocation(\"specularTexture\"), SpecularTextureLayer);\n}\n}\n/* Set defaults (normally they are set in shader code itself, but just in case) */\nMaterial material;\n/* Default to fully opaque white so we can see the textures */\nif (flags & Flag::AmbientTexture)\nmaterial.set_ambient_color(Magnum::Color4{1.0f});\nelse\nmaterial.set_ambient_color(Magnum::Color4{0.0f, 1.0f});\nif (flags & Flag::DiffuseTexture)\nmaterial.set_diffuse_color(Magnum::Color4{1.0f});\nmaterial.set_specular_color(Magnum::Color4{1.0f});\nmaterial.set_shininess(80.0f);\nset_material(material);\n/* Lights defaults need to be set by code */\n/* All lights are disabled i.e., color equal to black */\nLight light;\nfor (Magnum::Int i = 0; i < _max_lights; i++)\nset_light(i, light);\n}\nPhongMultiLight::PhongMultiLight(Magnum::NoCreateT) noexcept : Magnum::GL::AbstractShaderProgram{Magnum::NoCreate} {}\nPhongMultiLight::Flags PhongMultiLight::flags() const { return _flags; }\nPhongMultiLight& PhongMultiLight::set_material(Material& material)\n{\n// TO-DO: Check if we should do this or let the user define the proper\n// material\nif (material.has_ambient_texture() && (_flags & Flag::AmbientTexture)) {\n(*material.ambient_texture()).bind(AmbientTextureLayer);\nsetUniform(_ambient_color_uniform, Magnum::Color4{1.0f});\n}\nelse\nsetUniform(_ambient_color_uniform, material.ambient_color());\nif (material.has_diffuse_texture() && (_flags & Flag::DiffuseTexture)) {\n(*material.diffuse_texture()).bind(DiffuseTextureLayer);\nsetUniform(_diffuse_color_uniform, Magnum::Color4{1.0f});\n}\nelse\nsetUniform(_diffuse_color_uniform, material.diffuse_color());\nif (material.has_specular_texture() && (_flags & Flag::SpecularTexture)) {\n(*material.specular_texture()).bind(SpecularTextureLayer);\nsetUniform(_specular_color_uniform, Magnum::Color4{1.0f});\n}\nelse\nsetUniform(_specular_color_uniform, material.specular_color());\nsetUniform(_shininess_uniform, material.shininess());\nreturn *this;\n}\nPhongMultiLight& PhongMultiLight::set_light(Magnum::Int i, const Light& light)\n{\nCORRADE_INTERNAL_ASSERT(i >= 0 && i < _max_lights);\nMagnum::Vector4 attenuation = light.attenuation();\n// light position\nsetUniform(_lights_uniform + i * _light_loc_size, light.transformed_position());\n// light material\nsetUniform(_lights_uniform + i * _light_loc_size + 1, light.material().ambient_color());\nsetUniform(_lights_uniform + i * _light_loc_size + 2, light.material().diffuse_color());\nsetUniform(_lights_uniform + i * _light_loc_size + 3, light.material().specular_color());\n// spotlight properties\nsetUniform(_lights_uniform + i * _light_loc_size + 4, light.transformed_spot_direction());\nsetUniform(_lights_uniform + i * _light_loc_size + 5, light.spot_exponent());\nsetUniform(_lights_uniform + i * _light_loc_size + 6, light.spot_cut_off());\n// intesity\nsetUniform(_lights_uniform + i * _light_loc_size + 7, attenuation[3]);\n// constant attenuation term\nsetUniform(_lights_uniform + i * _light_loc_size + 8, attenuation[0]);\n// linear attenuation term\nsetUniform(_lights_uniform + i * _light_loc_size + 9, attenuation[1]);\n// quadratic attenuation term\nsetUniform(_lights_uniform + i * _light_loc_size + 10, attenuation[2]);\n// world position\nsetUniform(_lights_uniform + i * _light_loc_size + 11, light.position());\n// casts shadows?\nsetUniform(_lights_uniform + i * _light_loc_size + 12, light.casts_shadows());\nsetUniform(_lights_matrices_uniform + i, light.shadow_matrix());\nreturn *this;\n}\nPhongMultiLight& PhongMultiLight::set_transformation_matrix(const Magnum::Matrix4& matrix)\n{\nsetUniform(_transformation_matrix_uniform, matrix);\nreturn *this;\n}\nPhongMultiLight& PhongMultiLight::set_camera_matrix(const Magnum::Matrix4& matrix)\n{\nsetUniform(_camera_matrix_uniform, matrix);\nreturn *this;\n}\nPhongMultiLight& PhongMultiLight::set_normal_matrix(const Magnum::Matrix3x3& matrix)\n{\nsetUniform(_normal_matrix_uniform, matrix);\nreturn *this;\n}\nPhongMultiLight& PhongMultiLight::set_projection_matrix(const Magnum::Matrix4& matrix)\n{\nsetUniform(_projection_matrix_uniform, matrix);\nreturn *this;\n}\nPhongMultiLight& PhongMultiLight::set_far_plane(Magnum::Float far_plane)\n{\nsetUniform(_far_plane_uniform, far_plane);\nreturn *this;\n}\nPhongMultiLight& PhongMultiLight::set_is_shadowed(bool shadows)\n{\nsetUniform(_is_shadowed_uniform, shadows);\nreturn *this;\n}\nPhongMultiLight& PhongMultiLight::set_transparent_shadows(bool shadows)\n{\nsetUniform(_transparent_shadows_uniform, shadows);\nreturn *this;\n}\nPhongMultiLight& PhongMultiLight::set_specular_strength(Magnum::Float specular_strength)\n{\nsetUniform(_specular_strength_uniform, std::max(0.f, specular_strength));\nreturn *this;\n}\nPhongMultiLight& PhongMultiLight::bind_shadow_texture(Magnum::GL::Texture2DArray& texture)\n{\ntexture.bind(_shadow_textures_location);\nreturn *this;\n}\nPhongMultiLight& PhongMultiLight::bind_shadow_color_texture(Magnum::GL::Texture2DArray& texture)\n{\ntexture.bind(_shadow_color_textures_location);\nreturn *this;\n}\nPhongMultiLight& PhongMultiLight::bind_cube_map_texture(Magnum::GL::CubeMapTextureArray& texture)\n{\ntexture.bind(_cube_map_textures_location);\nreturn *this;\n}\nPhongMultiLight& PhongMultiLight::bind_cube_map_color_texture(Magnum::GL::CubeMapTextureArray& texture)\n{\ntexture.bind(_cube_map_color_textures_location);\nreturn *this;\n}\nMagnum::Int PhongMultiLight::max_lights() const { return _max_lights; }\n} // namespace gs\n} // namespace magnum\n} // namespace gui\n} // namespace robot_dart\n
"},{"location":"api/phong__multi__light_8hpp/","title":"File phong_multi_light.hpp","text":"

FileList > gs > phong_multi_light.hpp

Go to the source code of this file

"},{"location":"api/phong__multi__light_8hpp/#namespaces","title":"Namespaces","text":"Type Name namespace robot_dart namespace gui namespace magnum namespace gs"},{"location":"api/phong__multi__light_8hpp/#classes","title":"Classes","text":"Type Name class PhongMultiLight

The documentation for this class was generated from the following file robot_dart/gui/magnum/gs/phong_multi_light.hpp

"},{"location":"api/phong__multi__light_8hpp_source/","title":"File phong_multi_light.hpp","text":"

File List > gs > phong_multi_light.hpp

Go to the documentation of this file

#ifndef ROBOT_DART_GUI_MAGNUM_GS_PHONG_MULTI_LIGHT_HPP\n#define ROBOT_DART_GUI_MAGNUM_GS_PHONG_MULTI_LIGHT_HPP\n#include <robot_dart/gui/magnum/gs/light.hpp>\n#include <Corrade/Containers/ArrayView.h>\n#include <Corrade/Containers/Reference.h>\n#include <Corrade/Utility/Assert.h>\n#include <Magnum/GL/AbstractShaderProgram.h>\n#include <Magnum/Math/Color.h>\n#include <Magnum/Math/Matrix4.h>\n#include <Magnum/Shaders/Generic.h>\nnamespace robot_dart {\nnamespace gui {\nnamespace magnum {\nnamespace gs {\nclass PhongMultiLight : public Magnum::GL::AbstractShaderProgram {\npublic:\nusing Position = Magnum::Shaders::Generic3D::Position;\nusing Normal = Magnum::Shaders::Generic3D::Normal;\nusing TextureCoordinates = Magnum::Shaders::Generic3D::TextureCoordinates;\nenum class Flag : Magnum::UnsignedByte {\nAmbientTexture = 1 << 0, DiffuseTexture = 1 << 1, SpecularTexture = 1 << 2 };\nusing Flags = Magnum::Containers::EnumSet<Flag>;\nexplicit PhongMultiLight(Flags flags = {}, Magnum::Int max_lights = 10);\nexplicit PhongMultiLight(Magnum::NoCreateT) noexcept;\nFlags flags() const;\nPhongMultiLight& set_material(Material& material);\nPhongMultiLight& set_light(Magnum::Int i, const Light& light);\nPhongMultiLight& set_transformation_matrix(const Magnum::Matrix4& matrix);\nPhongMultiLight& set_camera_matrix(const Magnum::Matrix4& matrix);\nPhongMultiLight& set_normal_matrix(const Magnum::Matrix3x3& matrix);\nPhongMultiLight& set_projection_matrix(const Magnum::Matrix4& matrix);\nPhongMultiLight& set_far_plane(Magnum::Float far_plane);\nPhongMultiLight& set_is_shadowed(bool shadows);\nPhongMultiLight& set_transparent_shadows(bool shadows);\nPhongMultiLight& set_specular_strength(Magnum::Float specular_strength);\nPhongMultiLight& bind_shadow_texture(Magnum::GL::Texture2DArray& texture);\nPhongMultiLight& bind_shadow_color_texture(Magnum::GL::Texture2DArray& texture);\nPhongMultiLight& bind_cube_map_texture(Magnum::GL::CubeMapTextureArray& texture);\nPhongMultiLight& bind_cube_map_color_texture(Magnum::GL::CubeMapTextureArray& texture);\nMagnum::Int max_lights() const;\nprivate:\nFlags _flags;\nMagnum::Int _max_lights = 10;\nMagnum::Int _transformation_matrix_uniform{0}, _camera_matrix_uniform{7}, _projection_matrix_uniform{1}, _normal_matrix_uniform{2},\n_shininess_uniform{3}, _ambient_color_uniform{4}, _diffuse_color_uniform{5}, _specular_color_uniform{6}, _specular_strength_uniform{11},\n_lights_uniform{12}, _lights_matrices_uniform, _far_plane_uniform{8}, _is_shadowed_uniform{9}, _transparent_shadows_uniform{10},\n_shadow_textures_location{3}, _cube_map_textures_location{4}, _shadow_color_textures_location{5}, _cube_map_color_textures_location{6};\nconst Magnum::Int _light_loc_size = 13;\n};\nCORRADE_ENUMSET_OPERATORS(PhongMultiLight::Flags)\n} // namespace gs\n} // namespace magnum\n} // namespace gui\n} // namespace robot_dart\n#endif\n
"},{"location":"api/shadow__map_8cpp/","title":"File shadow_map.cpp","text":"

FileList > gs > shadow_map.cpp

Go to the source code of this file

"},{"location":"api/shadow__map_8cpp/#namespaces","title":"Namespaces","text":"Type Name namespace robot_dart namespace gui namespace magnum namespace gs

The documentation for this class was generated from the following file robot_dart/gui/magnum/gs/shadow_map.cpp

"},{"location":"api/shadow__map_8cpp_source/","title":"File shadow_map.cpp","text":"

File List > gs > shadow_map.cpp

Go to the documentation of this file

#include \"shadow_map.hpp\"\n#include \"create_compatibility_shader.hpp\"\n#include <Magnum/GL/Texture.h>\nnamespace robot_dart {\nnamespace gui {\nnamespace magnum {\nnamespace gs {\nShadowMap::ShadowMap(ShadowMap::Flags flags) : _flags(flags)\n{\nCorrade::Utility::Resource rs_shaders(\"RobotDARTShaders\");\nconst Magnum::GL::Version version = Magnum::GL::Version::GL320;\nMagnum::GL::Shader vert = Magnum::Shaders::Implementation::createCompatibilityShader(\nrs_shaders, version, Magnum::GL::Shader::Type::Vertex);\nMagnum::GL::Shader frag = Magnum::Shaders::Implementation::createCompatibilityShader(\nrs_shaders, version, Magnum::GL::Shader::Type::Fragment);\nstd::string defines = \"#define POSITION_ATTRIBUTE_LOCATION \" + std::to_string(Position::Location) + \"\\n\";\ndefines += \"#define TEXTURECOORDINATES_ATTRIBUTE_LOCATION \" + std::to_string(TextureCoordinates::Location) + \"\\n\";\nvert.addSource(flags ? \"#define TEXTURED\\n\" : \"\")\n.addSource(defines)\n.addSource(rs_shaders.get(\"ShadowMap.vert\"));\nfrag.addSource(flags ? \"#define TEXTURED\\n\" : \"\")\n.addSource(rs_shaders.get(\"ShadowMap.frag\"));\nCORRADE_INTERNAL_ASSERT_OUTPUT(Magnum::GL::Shader::compile({vert, frag}));\nattachShaders({vert, frag});\nif (!Magnum::GL::Context::current().isExtensionSupported<Magnum::GL::Extensions::ARB::explicit_attrib_location>(version)) {\nbindAttributeLocation(Position::Location, \"position\");\nif (flags)\nbindAttributeLocation(TextureCoordinates::Location, \"textureCoords\");\n}\nCORRADE_INTERNAL_ASSERT_OUTPUT(link());\nif (!Magnum::GL::Context::current().isExtensionSupported<Magnum::GL::Extensions::ARB::explicit_uniform_location>(version)) {\n_transformation_matrix_uniform = uniformLocation(\"transformationMatrix\");\n_projection_matrix_uniform = uniformLocation(\"projectionMatrix\");\n_diffuse_color_uniform = uniformLocation(\"diffuseColor\");\n}\nif (!Magnum::GL::Context::current()\n.isExtensionSupported<Magnum::GL::Extensions::ARB::shading_language_420pack>(version)\n&& flags) {\nsetUniform(uniformLocation(\"diffuseTexture\"), DiffuseTextureLayer);\n}\n}\nShadowMap::ShadowMap(Magnum::NoCreateT) noexcept : Magnum::GL::AbstractShaderProgram{Magnum::NoCreate} {}\nShadowMap::Flags ShadowMap::flags() const { return _flags; }\nShadowMap& ShadowMap::set_transformation_matrix(const Magnum::Matrix4& matrix)\n{\nsetUniform(_transformation_matrix_uniform, matrix);\nreturn *this;\n}\nShadowMap& ShadowMap::set_projection_matrix(const Magnum::Matrix4& matrix)\n{\nsetUniform(_projection_matrix_uniform, matrix);\nreturn *this;\n}\nShadowMap& ShadowMap::set_material(Material& material)\n{\nif (material.has_diffuse_texture() && (_flags & Flag::DiffuseTexture)) {\n(*material.diffuse_texture()).bind(DiffuseTextureLayer);\nsetUniform(_diffuse_color_uniform, Magnum::Color4{1.0f});\n}\nelse\nsetUniform(_diffuse_color_uniform, material.diffuse_color());\nreturn *this;\n}\n} // namespace gs\n} // namespace magnum\n} // namespace gui\n} // namespace robot_dart\n
"},{"location":"api/shadow__map_8hpp/","title":"File shadow_map.hpp","text":"

FileList > gs > shadow_map.hpp

Go to the source code of this file

"},{"location":"api/shadow__map_8hpp/#namespaces","title":"Namespaces","text":"Type Name namespace robot_dart namespace gui namespace magnum namespace gs"},{"location":"api/shadow__map_8hpp/#classes","title":"Classes","text":"Type Name class ShadowMap

The documentation for this class was generated from the following file robot_dart/gui/magnum/gs/shadow_map.hpp

"},{"location":"api/shadow__map_8hpp_source/","title":"File shadow_map.hpp","text":"

File List > gs > shadow_map.hpp

Go to the documentation of this file

#ifndef ROBOT_DART_GUI_MAGNUM_GS_SHADOW_MAP_HPP\n#define ROBOT_DART_GUI_MAGNUM_GS_SHADOW_MAP_HPP\n#include <robot_dart/gui/magnum/gs/material.hpp>\n#include <Corrade/Containers/ArrayView.h>\n#include <Corrade/Containers/Reference.h>\n#include <Corrade/Utility/Assert.h>\n#include <Magnum/GL/AbstractShaderProgram.h>\n#include <Magnum/Math/Color.h>\n#include <Magnum/Math/Matrix4.h>\n#include <Magnum/Shaders/Generic.h>\nnamespace robot_dart {\nnamespace gui {\nnamespace magnum {\nnamespace gs {\nclass ShadowMap : public Magnum::GL::AbstractShaderProgram {\npublic:\nusing Position = Magnum::Shaders::Generic3D::Position;\nusing TextureCoordinates = Magnum::Shaders::Generic3D::TextureCoordinates;\nenum class Flag : Magnum::UnsignedByte {\nDiffuseTexture = 1 << 0, };\nusing Flags = Magnum::Containers::EnumSet<Flag>;\nexplicit ShadowMap(Flags flags = {});\nexplicit ShadowMap(Magnum::NoCreateT) noexcept;\nFlags flags() const;\nShadowMap& set_transformation_matrix(const Magnum::Matrix4& matrix);\nShadowMap& set_projection_matrix(const Magnum::Matrix4& matrix);\nShadowMap& set_material(Material& material);\nprivate:\nFlags _flags;\nMagnum::Int _transformation_matrix_uniform{0}, _projection_matrix_uniform{1}, _diffuse_color_uniform{2};\n};\nCORRADE_ENUMSET_OPERATORS(ShadowMap::Flags)\n} // namespace gs\n} // namespace magnum\n} // namespace gui\n} // namespace robot_dart\n#endif\n
"},{"location":"api/shadow__map__color_8cpp/","title":"File shadow_map_color.cpp","text":"

FileList > gs > shadow_map_color.cpp

Go to the source code of this file

"},{"location":"api/shadow__map__color_8cpp/#namespaces","title":"Namespaces","text":"Type Name namespace robot_dart namespace gui namespace magnum namespace gs

The documentation for this class was generated from the following file robot_dart/gui/magnum/gs/shadow_map_color.cpp

"},{"location":"api/shadow__map__color_8cpp_source/","title":"File shadow_map_color.cpp","text":"

File List > gs > shadow_map_color.cpp

Go to the documentation of this file

#include \"shadow_map_color.hpp\"\n#include \"create_compatibility_shader.hpp\"\n#include <Magnum/GL/Texture.h>\nnamespace robot_dart {\nnamespace gui {\nnamespace magnum {\nnamespace gs {\nShadowMapColor::ShadowMapColor(ShadowMapColor::Flags flags) : _flags(flags)\n{\nCorrade::Utility::Resource rs_shaders(\"RobotDARTShaders\");\nconst Magnum::GL::Version version = Magnum::GL::Version::GL320;\nMagnum::GL::Shader vert = Magnum::Shaders::Implementation::createCompatibilityShader(\nrs_shaders, version, Magnum::GL::Shader::Type::Vertex);\nMagnum::GL::Shader frag = Magnum::Shaders::Implementation::createCompatibilityShader(\nrs_shaders, version, Magnum::GL::Shader::Type::Fragment);\nstd::string defines = \"#define POSITION_ATTRIBUTE_LOCATION \" + std::to_string(Position::Location) + \"\\n\";\ndefines += \"#define TEXTURECOORDINATES_ATTRIBUTE_LOCATION \" + std::to_string(TextureCoordinates::Location) + \"\\n\";\nvert.addSource(flags ? \"#define TEXTURED\\n\" : \"\")\n.addSource(defines)\n.addSource(rs_shaders.get(\"ShadowMap.vert\"));\nfrag.addSource(flags ? \"#define TEXTURED\\n\" : \"\")\n.addSource(rs_shaders.get(\"ShadowMapColor.frag\"));\nCORRADE_INTERNAL_ASSERT_OUTPUT(Magnum::GL::Shader::compile({vert, frag}));\nattachShaders({vert, frag});\nif (!Magnum::GL::Context::current().isExtensionSupported<Magnum::GL::Extensions::ARB::explicit_attrib_location>(version)) {\nbindAttributeLocation(Position::Location, \"position\");\nif (flags)\nbindAttributeLocation(TextureCoordinates::Location, \"textureCoords\");\n}\nCORRADE_INTERNAL_ASSERT_OUTPUT(link());\nif (!Magnum::GL::Context::current().isExtensionSupported<Magnum::GL::Extensions::ARB::explicit_uniform_location>(version)) {\n_transformation_matrix_uniform = uniformLocation(\"transformationMatrix\");\n_projection_matrix_uniform = uniformLocation(\"projectionMatrix\");\n_diffuse_color_uniform = uniformLocation(\"diffuseColor\");\n}\nif (!Magnum::GL::Context::current()\n.isExtensionSupported<Magnum::GL::Extensions::ARB::shading_language_420pack>(version)\n&& flags) {\nsetUniform(uniformLocation(\"diffuseTexture\"), DiffuseTextureLayer);\n}\n}\nShadowMapColor::ShadowMapColor(Magnum::NoCreateT) noexcept : Magnum::GL::AbstractShaderProgram{Magnum::NoCreate} {}\nShadowMapColor::Flags ShadowMapColor::flags() const { return _flags; }\nShadowMapColor& ShadowMapColor::set_transformation_matrix(const Magnum::Matrix4& matrix)\n{\nsetUniform(_transformation_matrix_uniform, matrix);\nreturn *this;\n}\nShadowMapColor& ShadowMapColor::set_projection_matrix(const Magnum::Matrix4& matrix)\n{\nsetUniform(_projection_matrix_uniform, matrix);\nreturn *this;\n}\nShadowMapColor& ShadowMapColor::set_material(Material& material)\n{\nif (material.has_diffuse_texture() && (_flags & Flag::DiffuseTexture)) {\n(*material.diffuse_texture()).bind(DiffuseTextureLayer);\nsetUniform(_diffuse_color_uniform, Magnum::Color4{1.0f});\n}\nelse\nsetUniform(_diffuse_color_uniform, material.diffuse_color());\nreturn *this;\n}\n} // namespace gs\n} // namespace magnum\n} // namespace gui\n} // namespace robot_dart\n
"},{"location":"api/shadow__map__color_8hpp/","title":"File shadow_map_color.hpp","text":"

FileList > gs > shadow_map_color.hpp

Go to the source code of this file

"},{"location":"api/shadow__map__color_8hpp/#namespaces","title":"Namespaces","text":"Type Name namespace robot_dart namespace gui namespace magnum namespace gs"},{"location":"api/shadow__map__color_8hpp/#classes","title":"Classes","text":"Type Name class ShadowMapColor

The documentation for this class was generated from the following file robot_dart/gui/magnum/gs/shadow_map_color.hpp

"},{"location":"api/shadow__map__color_8hpp_source/","title":"File shadow_map_color.hpp","text":"

File List > gs > shadow_map_color.hpp

Go to the documentation of this file

#ifndef ROBOT_DART_GUI_MAGNUM_GS_SHADOW_MAP_COLOR_HPP\n#define ROBOT_DART_GUI_MAGNUM_GS_SHADOW_MAP_COLOR_HPP\n#include <robot_dart/gui/magnum/gs/material.hpp>\n#include <Corrade/Containers/ArrayView.h>\n#include <Corrade/Containers/Reference.h>\n#include <Corrade/Utility/Assert.h>\n#include <Magnum/GL/AbstractShaderProgram.h>\n#include <Magnum/Math/Color.h>\n#include <Magnum/Math/Matrix4.h>\n#include <Magnum/Shaders/Generic.h>\nnamespace robot_dart {\nnamespace gui {\nnamespace magnum {\nnamespace gs {\nclass ShadowMapColor : public Magnum::GL::AbstractShaderProgram {\npublic:\nusing Position = Magnum::Shaders::Generic3D::Position;\nusing TextureCoordinates = Magnum::Shaders::Generic3D::TextureCoordinates;\nenum class Flag : Magnum::UnsignedByte {\nDiffuseTexture = 1 << 0, };\nusing Flags = Magnum::Containers::EnumSet<Flag>;\nexplicit ShadowMapColor(Flags flags = {});\nexplicit ShadowMapColor(Magnum::NoCreateT) noexcept;\nFlags flags() const;\nShadowMapColor& set_transformation_matrix(const Magnum::Matrix4& matrix);\nShadowMapColor& set_projection_matrix(const Magnum::Matrix4& matrix);\nShadowMapColor& set_material(Material& material);\nprivate:\nFlags _flags;\nMagnum::Int _transformation_matrix_uniform{0}, _projection_matrix_uniform{1}, _diffuse_color_uniform{2};\n};\nCORRADE_ENUMSET_OPERATORS(ShadowMapColor::Flags)\n} // namespace gs\n} // namespace magnum\n} // namespace gui\n} // namespace robot_dart\n#endif\n
"},{"location":"api/dir_2c74a777547786aaf50e99ba400e19fa/","title":"Dir robot_dart/gui/magnum/sensor","text":"

FileList > gui > magnum > sensor

"},{"location":"api/dir_2c74a777547786aaf50e99ba400e19fa/#files","title":"Files","text":"Type Name file camera.cpp file camera.hpp

The documentation for this class was generated from the following file robot_dart/gui/magnum/sensor/

"},{"location":"api/sensor_2camera_8cpp/","title":"File camera.cpp","text":"

FileList > gui > magnum > sensor > camera.cpp

Go to the source code of this file

"},{"location":"api/sensor_2camera_8cpp/#namespaces","title":"Namespaces","text":"Type Name namespace robot_dart namespace gui namespace magnum namespace sensor

The documentation for this class was generated from the following file robot_dart/gui/magnum/sensor/camera.cpp

"},{"location":"api/sensor_2camera_8cpp_source/","title":"Macro Syntax Error","text":"

Line 46 in Markdown file: unexpected '}'

                    _framebuffer = Magnum::GL::Framebuffer({{}, {w, h}});\n

"},{"location":"api/sensor_2camera_8hpp/","title":"File camera.hpp","text":"

FileList > gui > magnum > sensor > camera.hpp

Go to the source code of this file

"},{"location":"api/sensor_2camera_8hpp/#namespaces","title":"Namespaces","text":"Type Name namespace robot_dart namespace gui namespace magnum namespace sensor namespace sensor"},{"location":"api/sensor_2camera_8hpp/#classes","title":"Classes","text":"Type Name class Camera

The documentation for this class was generated from the following file robot_dart/gui/magnum/sensor/camera.hpp

"},{"location":"api/sensor_2camera_8hpp_source/","title":"File camera.hpp","text":"

File List > gui > magnum > sensor > camera.hpp

Go to the documentation of this file

#ifndef ROBOT_DART_GUI_MAGNUM_SENSOR_CAMERA_HPP\n#define ROBOT_DART_GUI_MAGNUM_SENSOR_CAMERA_HPP\n#include <robot_dart/gui/magnum/base_application.hpp>\n#include <robot_dart/gui/magnum/gs/helper.hpp>\n#include <robot_dart/sensor/sensor.hpp>\n#include <Magnum/GL/Framebuffer.h>\n#include <Magnum/GL/Renderbuffer.h>\n#include <Magnum/PixelFormat.h>\nnamespace robot_dart {\nnamespace gui {\nnamespace magnum {\nnamespace sensor {\nclass Camera : public robot_dart::sensor::Sensor {\npublic:\nCamera(BaseApplication* app, size_t width, size_t height, size_t freq = 30, bool draw_debug = false);\n~Camera() {}\nvoid init() override;\nvoid calculate(double) override;\nstd::string type() const override;\nvoid attach_to_body(dart::dynamics::BodyNode* body, const Eigen::Isometry3d& tf = Eigen::Isometry3d::Identity()) override;\nvoid attach_to_joint(dart::dynamics::Joint*, const Eigen::Isometry3d&) override\n{\nROBOT_DART_WARNING(true, \"You cannot attach a camera to a joint!\");\n}\ngs::Camera& camera() { return *_camera; }\nconst gs::Camera& camera() const { return *_camera; }\nEigen::Matrix3d camera_intrinsic_matrix() const;\nEigen::Matrix4d camera_extrinsic_matrix() const;\nbool drawing_debug() const { return _draw_debug; }\nvoid draw_debug(bool draw = true) { _draw_debug = draw; }\nvoid look_at(const Eigen::Vector3d& camera_pos, const Eigen::Vector3d& look_at = Eigen::Vector3d(0, 0, 0), const Eigen::Vector3d& up = Eigen::Vector3d(0, 0, 1));\n// this will use the default FPS of the camera if fps == -1\nvoid record_video(const std::string& video_fname)\n{\n_camera->record_video(video_fname, _frequency);\n}\nMagnum::Image2D* magnum_image()\n{\nif (_camera->image())\nreturn &(*_camera->image());\nreturn nullptr;\n}\nImage image()\n{\nauto image = magnum_image();\nif (image)\nreturn gs::rgb_from_image(image);\nreturn Image();\n}\nMagnum::Image2D* magnum_depth_image()\n{\nif (_camera->depth_image())\nreturn &(*_camera->depth_image());\nreturn nullptr;\n}\n// This is for visualization purposes\nGrayscaleImage depth_image();\n// Image filled with depth buffer values\nGrayscaleImage raw_depth_image();\n// \"Image\" filled with depth buffer values (this returns an array of doubles)\nDepthImage depth_array();\nprotected:\nMagnum::GL::Framebuffer _framebuffer{Magnum::NoCreate};\nMagnum::PixelFormat _format;\nMagnum::GL::Renderbuffer _color, _depth;\nBaseApplication* _magnum_app;\nsize_t _width, _height;\nstd::unique_ptr<gs::Camera> _camera;\nbool _draw_debug;\n};\n} // namespace sensor\n} // namespace magnum\n} // namespace gui\nnamespace sensor {\nusing gui::magnum::sensor::Camera;\n}\n} // namespace robot_dart\n#endif\n
"},{"location":"api/types_8hpp/","title":"File types.hpp","text":"

FileList > gui > magnum > types.hpp

Go to the source code of this file

"},{"location":"api/types_8hpp/#namespaces","title":"Namespaces","text":"Type Name namespace robot_dart namespace gui namespace magnum

The documentation for this class was generated from the following file robot_dart/gui/magnum/types.hpp

"},{"location":"api/types_8hpp_source/","title":"File types.hpp","text":"

File List > gui > magnum > types.hpp

Go to the documentation of this file

#ifndef ROBOT_DART_GUI_MAGNUM_TYPES_HPP\n#define ROBOT_DART_GUI_MAGNUM_TYPES_HPP\n#include <Magnum/SceneGraph/Camera.h>\n#include <Magnum/SceneGraph/MatrixTransformation3D.h>\n#include <Magnum/SceneGraph/Scene.h>\nnamespace robot_dart {\nnamespace gui {\nnamespace magnum {\nusing Object3D = Magnum::SceneGraph::Object<Magnum::SceneGraph::MatrixTransformation3D>;\nusing Scene3D = Magnum::SceneGraph::Scene<Magnum::SceneGraph::MatrixTransformation3D>;\nusing Camera3D = Magnum::SceneGraph::Camera3D;\n} // namespace magnum\n} // namespace gui\n} // namespace robot_dart\n#endif\n
"},{"location":"api/utils__headers__eigen_8hpp/","title":"File utils_headers_eigen.hpp","text":"

FileList > gui > magnum > utils_headers_eigen.hpp

Go to the source code of this file

The documentation for this class was generated from the following file robot_dart/gui/magnum/utils_headers_eigen.hpp

"},{"location":"api/utils__headers__eigen_8hpp_source/","title":"File utils_headers_eigen.hpp","text":"

File List > gui > magnum > utils_headers_eigen.hpp

Go to the documentation of this file

#ifndef ROBOT_DART_GUI_MAGNUM_UTILS_HEADERS_EXTERNAL_GUI_HPP\n#define ROBOT_DART_GUI_MAGNUM_UTILS_HEADERS_EXTERNAL_GUI_HPP\n#pragma GCC system_header\n#include <Magnum/EigenIntegration/GeometryIntegration.h>\n#include <Magnum/EigenIntegration/Integration.h>\n#endif\n
"},{"location":"api/windowless__gl__application_8cpp/","title":"File windowless_gl_application.cpp","text":"

FileList > gui > magnum > windowless_gl_application.cpp

Go to the source code of this file

"},{"location":"api/windowless__gl__application_8cpp/#namespaces","title":"Namespaces","text":"Type Name namespace robot_dart namespace gui namespace magnum

The documentation for this class was generated from the following file robot_dart/gui/magnum/windowless_gl_application.cpp

"},{"location":"api/windowless__gl__application_8cpp_source/","title":"Macro Syntax Error","text":"

Line 42 in Markdown file: unexpected '}'

                _framebuffer = Magnum::GL::Framebuffer({{}, {w, h}});\n

"},{"location":"api/windowless__gl__application_8hpp/","title":"File windowless_gl_application.hpp","text":"

FileList > gui > magnum > windowless_gl_application.hpp

Go to the source code of this file

"},{"location":"api/windowless__gl__application_8hpp/#namespaces","title":"Namespaces","text":"Type Name namespace robot_dart namespace gui namespace magnum"},{"location":"api/windowless__gl__application_8hpp/#classes","title":"Classes","text":"Type Name class WindowlessGLApplication

The documentation for this class was generated from the following file robot_dart/gui/magnum/windowless_gl_application.hpp

"},{"location":"api/windowless__gl__application_8hpp_source/","title":"File windowless_gl_application.hpp","text":"

File List > gui > magnum > windowless_gl_application.hpp

Go to the documentation of this file

#ifndef ROBOT_DART_GUI_MAGNUM_GLX_APPLICATION_HPP\n#define ROBOT_DART_GUI_MAGNUM_GLX_APPLICATION_HPP\n#include <robot_dart/gui/magnum/base_application.hpp>\n#include <Magnum/GL/Renderbuffer.h>\n#include <Magnum/PixelFormat.h>\nnamespace robot_dart {\nnamespace gui {\nnamespace magnum {\nclass WindowlessGLApplication : public BaseApplication, public Magnum::Platform::WindowlessApplication {\npublic:\nexplicit WindowlessGLApplication(int argc, char** argv, RobotDARTSimu* simu, const GraphicsConfiguration& configuration = GraphicsConfiguration());\n~WindowlessGLApplication();\nvoid render() override;\nprotected:\nRobotDARTSimu* _simu;\nbool _draw_main_camera, _draw_debug;\nMagnum::Color4 _bg_color;\nMagnum::GL::Framebuffer _framebuffer{Magnum::NoCreate};\nMagnum::PixelFormat _format;\nMagnum::GL::Renderbuffer _color{Magnum::NoCreate}, _depth{Magnum::NoCreate};\n// size_t _index = 0;\nvirtual int exec() override { return 0; }\n};\n} // namespace magnum\n} // namespace gui\n} // namespace robot_dart\n#endif\n
"},{"location":"api/windowless__graphics_8cpp/","title":"File windowless_graphics.cpp","text":"

FileList > gui > magnum > windowless_graphics.cpp

Go to the source code of this file

"},{"location":"api/windowless__graphics_8cpp/#namespaces","title":"Namespaces","text":"Type Name namespace robot_dart namespace gui namespace magnum

The documentation for this class was generated from the following file robot_dart/gui/magnum/windowless_graphics.cpp

"},{"location":"api/windowless__graphics_8cpp_source/","title":"File windowless_graphics.cpp","text":"

File List > gui > magnum > windowless_graphics.cpp

Go to the documentation of this file

#include <robot_dart/gui/magnum/windowless_graphics.hpp>\nnamespace robot_dart {\nnamespace gui {\nnamespace magnum {\nvoid WindowlessGraphics::set_simu(RobotDARTSimu* simu)\n{\nBaseGraphics<WindowlessGLApplication>::set_simu(simu);\n// we should not synchronize by default if we want windowless graphics (usually used only for sensors)\nsimu->scheduler().set_sync(false);\n// disable summary text when windowless graphics activated\nsimu->enable_text_panel(false);\nsimu->enable_status_bar(false);\n}\nGraphicsConfiguration WindowlessGraphics::default_configuration()\n{\nGraphicsConfiguration config;\n// by default we do not draw text in windowless mode\nconfig.draw_debug = false;\nconfig.draw_text = false;\nreturn config;\n}\n} // namespace magnum\n} // namespace gui\n} // namespace robot_dart\n
"},{"location":"api/windowless__graphics_8hpp/","title":"File windowless_graphics.hpp","text":"

FileList > gui > magnum > windowless_graphics.hpp

Go to the source code of this file

"},{"location":"api/windowless__graphics_8hpp/#namespaces","title":"Namespaces","text":"Type Name namespace robot_dart namespace gui namespace magnum"},{"location":"api/windowless__graphics_8hpp/#classes","title":"Classes","text":"Type Name class WindowlessGraphics

The documentation for this class was generated from the following file robot_dart/gui/magnum/windowless_graphics.hpp

"},{"location":"api/windowless__graphics_8hpp_source/","title":"File windowless_graphics.hpp","text":"

File List > gui > magnum > windowless_graphics.hpp

Go to the documentation of this file

#ifndef ROBOT_DART_GUI_MAGNUM_WINDOWLESS_GRAPHICS_HPP\n#define ROBOT_DART_GUI_MAGNUM_WINDOWLESS_GRAPHICS_HPP\n#include <robot_dart/gui/magnum/base_graphics.hpp>\n#include <robot_dart/gui/magnum/windowless_gl_application.hpp>\nnamespace robot_dart {\nnamespace gui {\nnamespace magnum {\nclass WindowlessGraphics : public BaseGraphics<WindowlessGLApplication> {\npublic:\nWindowlessGraphics(const GraphicsConfiguration& configuration = default_configuration()) : BaseGraphics<WindowlessGLApplication>(configuration) {}\n~WindowlessGraphics() {}\nvoid set_simu(RobotDARTSimu* simu) override;\nstatic GraphicsConfiguration default_configuration();\n};\n} // namespace magnum\n} // namespace gui\n} // namespace robot_dart\n#endif\n
"},{"location":"api/stb__image__write_8h/","title":"File stb_image_write.h","text":"

FileList > gui > stb_image_write.h

Go to the source code of this file

"},{"location":"api/stb__image__write_8h/#public-types","title":"Public Types","text":"Type Name typedef void stbi_write_func"},{"location":"api/stb__image__write_8h/#public-attributes","title":"Public Attributes","text":"Type Name int stbi_write_force_png_filter int stbi_write_png_compression_level int stbi_write_tga_with_rle"},{"location":"api/stb__image__write_8h/#public-functions","title":"Public Functions","text":"Type Name STBIWDEF void stbi_flip_vertically_on_write (int flip_boolean) STBIWDEF int stbi_write_bmp (char const * filename, int w, int h, int comp, const void * data) STBIWDEF int stbi_write_bmp_to_func (stbi_write_func * func, void * context, int w, int h, int comp, const void * data) STBIWDEF int stbi_write_hdr (char const * filename, int w, int h, int comp, const float * data) STBIWDEF int stbi_write_hdr_to_func (stbi_write_func * func, void * context, int w, int h, int comp, const float * data) STBIWDEF int stbi_write_jpg (char const * filename, int x, int y, int comp, const void * data, int quality) STBIWDEF int stbi_write_jpg_to_func (stbi_write_func * func, void * context, int x, int y, int comp, const void * data, int quality) STBIWDEF int stbi_write_png (char const * filename, int w, int h, int comp, const void * data, int stride_in_bytes) STBIWDEF int stbi_write_png_to_func (stbi_write_func * func, void * context, int w, int h, int comp, const void * data, int stride_in_bytes) STBIWDEF int stbi_write_tga (char const * filename, int w, int h, int comp, const void * data) STBIWDEF int stbi_write_tga_to_func (stbi_write_func * func, void * context, int w, int h, int comp, const void * data)"},{"location":"api/stb__image__write_8h/#macros","title":"Macros","text":"Type Name define STBIWDEF extern"},{"location":"api/stb__image__write_8h/#public-types-documentation","title":"Public Types Documentation","text":""},{"location":"api/stb__image__write_8h/#typedef-stbi_write_func","title":"typedef stbi_write_func","text":"
typedef void stbi_write_func(void *context, void *data, int size);\n
"},{"location":"api/stb__image__write_8h/#public-attributes-documentation","title":"Public Attributes Documentation","text":""},{"location":"api/stb__image__write_8h/#variable-stbi_write_force_png_filter","title":"variable stbi_write_force_png_filter","text":"
int stbi_write_force_png_filter;\n
"},{"location":"api/stb__image__write_8h/#variable-stbi_write_png_compression_level","title":"variable stbi_write_png_compression_level","text":"
int stbi_write_png_compression_level;\n
"},{"location":"api/stb__image__write_8h/#variable-stbi_write_tga_with_rle","title":"variable stbi_write_tga_with_rle","text":"
int stbi_write_tga_with_rle;\n
"},{"location":"api/stb__image__write_8h/#public-functions-documentation","title":"Public Functions Documentation","text":""},{"location":"api/stb__image__write_8h/#function-stbi_flip_vertically_on_write","title":"function stbi_flip_vertically_on_write","text":"
STBIWDEF void stbi_flip_vertically_on_write (\nint flip_boolean\n) 
"},{"location":"api/stb__image__write_8h/#function-stbi_write_bmp","title":"function stbi_write_bmp","text":"
STBIWDEF int stbi_write_bmp (\nchar const * filename,\nint w,\nint h,\nint comp,\nconst void * data\n) 
"},{"location":"api/stb__image__write_8h/#function-stbi_write_bmp_to_func","title":"function stbi_write_bmp_to_func","text":"
STBIWDEF int stbi_write_bmp_to_func (\nstbi_write_func * func,\nvoid * context,\nint w,\nint h,\nint comp,\nconst void * data\n) 
"},{"location":"api/stb__image__write_8h/#function-stbi_write_hdr","title":"function stbi_write_hdr","text":"
STBIWDEF int stbi_write_hdr (\nchar const * filename,\nint w,\nint h,\nint comp,\nconst float * data\n) 
"},{"location":"api/stb__image__write_8h/#function-stbi_write_hdr_to_func","title":"function stbi_write_hdr_to_func","text":"
STBIWDEF int stbi_write_hdr_to_func (\nstbi_write_func * func,\nvoid * context,\nint w,\nint h,\nint comp,\nconst float * data\n) 
"},{"location":"api/stb__image__write_8h/#function-stbi_write_jpg","title":"function stbi_write_jpg","text":"
STBIWDEF int stbi_write_jpg (\nchar const * filename,\nint x,\nint y,\nint comp,\nconst void * data,\nint quality\n) 
"},{"location":"api/stb__image__write_8h/#function-stbi_write_jpg_to_func","title":"function stbi_write_jpg_to_func","text":"
STBIWDEF int stbi_write_jpg_to_func (\nstbi_write_func * func,\nvoid * context,\nint x,\nint y,\nint comp,\nconst void * data,\nint quality\n) 
"},{"location":"api/stb__image__write_8h/#function-stbi_write_png","title":"function stbi_write_png","text":"
STBIWDEF int stbi_write_png (\nchar const * filename,\nint w,\nint h,\nint comp,\nconst void * data,\nint stride_in_bytes\n) 
"},{"location":"api/stb__image__write_8h/#function-stbi_write_png_to_func","title":"function stbi_write_png_to_func","text":"
STBIWDEF int stbi_write_png_to_func (\nstbi_write_func * func,\nvoid * context,\nint w,\nint h,\nint comp,\nconst void * data,\nint stride_in_bytes\n) 
"},{"location":"api/stb__image__write_8h/#function-stbi_write_tga","title":"function stbi_write_tga","text":"
STBIWDEF int stbi_write_tga (\nchar const * filename,\nint w,\nint h,\nint comp,\nconst void * data\n) 
"},{"location":"api/stb__image__write_8h/#function-stbi_write_tga_to_func","title":"function stbi_write_tga_to_func","text":"
STBIWDEF int stbi_write_tga_to_func (\nstbi_write_func * func,\nvoid * context,\nint w,\nint h,\nint comp,\nconst void * data\n) 
"},{"location":"api/stb__image__write_8h/#macro-definition-documentation","title":"Macro Definition Documentation","text":""},{"location":"api/stb__image__write_8h/#define-stbiwdef","title":"define STBIWDEF","text":"
#define STBIWDEF extern\n

The documentation for this class was generated from the following file robot_dart/gui/stb_image_write.h

"},{"location":"api/stb__image__write_8h_source/","title":"File stb_image_write.h","text":"

File List > gui > stb_image_write.h

Go to the documentation of this file

/* stb_image_write - v1.13 - public domain - http://nothings.org/stb\n   writes out PNG/BMP/TGA/JPEG/HDR images to C stdio - Sean Barrett 2010-2015\n                                     no warranty implied; use at your own risk\n   Before #including,\n       #define STB_IMAGE_WRITE_IMPLEMENTATION\n   in the file that you want to have the implementation.\n   Will probably not work correctly with strict-aliasing optimizations.\nABOUT:\n   This header file is a library for writing images to C stdio or a callback.\n   The PNG output is not optimal; it is 20-50% larger than the file\n   written by a decent optimizing implementation; though providing a custom\n   zlib compress function (see STBIW_ZLIB_COMPRESS) can mitigate that.\n   This library is designed for source code compactness and simplicity,\n   not optimal image file size or run-time performance.\nBUILDING:\n   You can #define STBIW_ASSERT(x) before the #include to avoid using assert.h.\n   You can #define STBIW_MALLOC(), STBIW_REALLOC(), and STBIW_FREE() to replace\n   malloc,realloc,free.\n   You can #define STBIW_MEMMOVE() to replace memmove()\n   You can #define STBIW_ZLIB_COMPRESS to use a custom zlib-style compress function\n   for PNG compression (instead of the builtin one), it must have the following signature:\n   unsigned char * my_compress(unsigned char *data, int data_len, int *out_len, int quality);\n   The returned data will be freed with STBIW_FREE() (free() by default),\n   so it must be heap allocated with STBIW_MALLOC() (malloc() by default),\nUNICODE:\n   If compiling for Windows and you wish to use Unicode filenames, compile\n   with\n       #define STBIW_WINDOWS_UTF8\n   and pass utf8-encoded filenames. Call stbiw_convert_wchar_to_utf8 to convert\n   Windows wchar_t filenames to utf8.\nUSAGE:\n   There are five functions, one for each image file format:\n     int stbi_write_png(char const *filename, int w, int h, int comp, const void *data, int stride_in_bytes);\n     int stbi_write_bmp(char const *filename, int w, int h, int comp, const void *data);\n     int stbi_write_tga(char const *filename, int w, int h, int comp, const void *data);\n     int stbi_write_jpg(char const *filename, int w, int h, int comp, const void *data, int quality);\n     int stbi_write_hdr(char const *filename, int w, int h, int comp, const float *data);\n     void stbi_flip_vertically_on_write(int flag); // flag is non-zero to flip data vertically\n   There are also five equivalent functions that use an arbitrary write function. You are\n   expected to open/close your file-equivalent before and after calling these:\n     int stbi_write_png_to_func(stbi_write_func *func, void *context, int w, int h, int comp, const void  *data, int stride_in_bytes);\n     int stbi_write_bmp_to_func(stbi_write_func *func, void *context, int w, int h, int comp, const void  *data);\n     int stbi_write_tga_to_func(stbi_write_func *func, void *context, int w, int h, int comp, const void  *data);\n     int stbi_write_hdr_to_func(stbi_write_func *func, void *context, int w, int h, int comp, const float *data);\n     int stbi_write_jpg_to_func(stbi_write_func *func, void *context, int x, int y, int comp, const void *data, int quality);\n   where the callback is:\n      void stbi_write_func(void *context, void *data, int size);\n   You can configure it with these global variables:\n      int stbi_write_tga_with_rle;             // defaults to true; set to 0 to disable RLE\n      int stbi_write_png_compression_level;    // defaults to 8; set to higher for more compression\n      int stbi_write_force_png_filter;         // defaults to -1; set to 0..5 to force a filter mode\n   You can define STBI_WRITE_NO_STDIO to disable the file variant of these\n   functions, so the library will not use stdio.h at all. However, this will\n   also disable HDR writing, because it requires stdio for formatted output.\n   Each function returns 0 on failure and non-0 on success.\n   The functions create an image file defined by the parameters. The image\n   is a rectangle of pixels stored from left-to-right, top-to-bottom.\n   Each pixel contains 'comp' channels of data stored interleaved with 8-bits\n   per channel, in the following order: 1=Y, 2=YA, 3=RGB, 4=RGBA. (Y is\n   monochrome color.) The rectangle is 'w' pixels wide and 'h' pixels tall.\n   The *data pointer points to the first byte of the top-left-most pixel.\n   For PNG, \"stride_in_bytes\" is the distance in bytes from the first byte of\n   a row of pixels to the first byte of the next row of pixels.\n   PNG creates output files with the same number of components as the input.\n   The BMP format expands Y to RGB in the file format and does not\n   output alpha.\n   PNG supports writing rectangles of data even when the bytes storing rows of\n   data are not consecutive in memory (e.g. sub-rectangles of a larger image),\n   by supplying the stride between the beginning of adjacent rows. The other\n   formats do not. (Thus you cannot write a native-format BMP through the BMP\n   writer, both because it is in BGR order and because it may have padding\n   at the end of the line.)\n   PNG allows you to set the deflate compression level by setting the global\n   variable 'stbi_write_png_compression_level' (it defaults to 8).\n   HDR expects linear float data. Since the format is always 32-bit rgb(e)\n   data, alpha (if provided) is discarded, and for monochrome data it is\n   replicated across all three channels.\n   TGA supports RLE or non-RLE compressed data. To use non-RLE-compressed\n   data, set the global variable 'stbi_write_tga_with_rle' to 0.\n   JPEG does ignore alpha channels in input data; quality is between 1 and 100.\n   Higher quality looks better but results in a bigger image.\n   JPEG baseline (no JPEG progressive).\nCREDITS:\n   Sean Barrett           -    PNG/BMP/TGA \n   Baldur Karlsson        -    HDR\n   Jean-Sebastien Guay    -    TGA monochrome\n   Tim Kelsey             -    misc enhancements\n   Alan Hickman           -    TGA RLE\n   Emmanuel Julien        -    initial file IO callback implementation\n   Jon Olick              -    original jo_jpeg.cpp code\n   Daniel Gibson          -    integrate JPEG, allow external zlib\n   Aarni Koskela          -    allow choosing PNG filter\n   bugfixes:\n      github:Chribba\n      Guillaume Chereau\n      github:jry2\n      github:romigrou\n      Sergio Gonzalez\n      Jonas Karlsson\n      Filip Wasil\n      Thatcher Ulrich\n      github:poppolopoppo\n      Patrick Boettcher\n      github:xeekworx\n      Cap Petschulat\n      Simon Rodriguez\n      Ivan Tikhonov\n      github:ignotion\n      Adam Schackart\nLICENSE\n  See end of file for license information.\n*/\n#pragma GCC system_header\n#ifndef INCLUDE_STB_IMAGE_WRITE_H\n#define INCLUDE_STB_IMAGE_WRITE_H\n#include <stdlib.h>\n// if STB_IMAGE_WRITE_STATIC causes problems, try defining STBIWDEF to 'inline' or 'static inline'\n#ifndef STBIWDEF\n#ifdef STB_IMAGE_WRITE_STATIC\n#define STBIWDEF  static\n#else\n#ifdef __cplusplus\n#define STBIWDEF  extern \"C\"\n#else\n#define STBIWDEF  extern\n#endif\n#endif\n#endif\n#ifndef STB_IMAGE_WRITE_STATIC  // C++ forbids static forward declarations\nextern int stbi_write_tga_with_rle;\nextern int stbi_write_png_compression_level;\nextern int stbi_write_force_png_filter;\n#endif\n#ifndef STBI_WRITE_NO_STDIO\nSTBIWDEF int stbi_write_png(char const *filename, int w, int h, int comp, const void  *data, int stride_in_bytes);\nSTBIWDEF int stbi_write_bmp(char const *filename, int w, int h, int comp, const void  *data);\nSTBIWDEF int stbi_write_tga(char const *filename, int w, int h, int comp, const void  *data);\nSTBIWDEF int stbi_write_hdr(char const *filename, int w, int h, int comp, const float *data);\nSTBIWDEF int stbi_write_jpg(char const *filename, int x, int y, int comp, const void  *data, int quality);\n#ifdef STBI_WINDOWS_UTF8\nSTBIWDEF int stbiw_convert_wchar_to_utf8(char *buffer, size_t bufferlen, const wchar_t* input);\n#endif\n#endif\ntypedef void stbi_write_func(void *context, void *data, int size);\nSTBIWDEF int stbi_write_png_to_func(stbi_write_func *func, void *context, int w, int h, int comp, const void  *data, int stride_in_bytes);\nSTBIWDEF int stbi_write_bmp_to_func(stbi_write_func *func, void *context, int w, int h, int comp, const void  *data);\nSTBIWDEF int stbi_write_tga_to_func(stbi_write_func *func, void *context, int w, int h, int comp, const void  *data);\nSTBIWDEF int stbi_write_hdr_to_func(stbi_write_func *func, void *context, int w, int h, int comp, const float *data);\nSTBIWDEF int stbi_write_jpg_to_func(stbi_write_func *func, void *context, int x, int y, int comp, const void  *data, int quality);\nSTBIWDEF void stbi_flip_vertically_on_write(int flip_boolean);\n#endif//INCLUDE_STB_IMAGE_WRITE_H\n#ifdef STB_IMAGE_WRITE_IMPLEMENTATION\n#ifdef _WIN32\n#ifndef _CRT_SECURE_NO_WARNINGS\n#define _CRT_SECURE_NO_WARNINGS\n#endif\n#ifndef _CRT_NONSTDC_NO_DEPRECATE\n#define _CRT_NONSTDC_NO_DEPRECATE\n#endif\n#endif\n#ifndef STBI_WRITE_NO_STDIO\n#include <stdio.h>\n#endif // STBI_WRITE_NO_STDIO\n#include <stdarg.h>\n#include <stdlib.h>\n#include <string.h>\n#include <math.h>\n#if defined(STBIW_MALLOC) && defined(STBIW_FREE) && (defined(STBIW_REALLOC) || defined(STBIW_REALLOC_SIZED))\n// ok\n#elif !defined(STBIW_MALLOC) && !defined(STBIW_FREE) && !defined(STBIW_REALLOC) && !defined(STBIW_REALLOC_SIZED)\n// ok\n#else\n#error \"Must define all or none of STBIW_MALLOC, STBIW_FREE, and STBIW_REALLOC (or STBIW_REALLOC_SIZED).\"\n#endif\n#ifndef STBIW_MALLOC\n#define STBIW_MALLOC(sz)        malloc(sz)\n#define STBIW_REALLOC(p,newsz)  realloc(p,newsz)\n#define STBIW_FREE(p)           free(p)\n#endif\n#ifndef STBIW_REALLOC_SIZED\n#define STBIW_REALLOC_SIZED(p,oldsz,newsz) STBIW_REALLOC(p,newsz)\n#endif\n#ifndef STBIW_MEMMOVE\n#define STBIW_MEMMOVE(a,b,sz) memmove(a,b,sz)\n#endif\n#ifndef STBIW_ASSERT\n#include <assert.h>\n#define STBIW_ASSERT(x) assert(x)\n#endif\n#define STBIW_UCHAR(x) (unsigned char) ((x) & 0xff)\n#ifdef STB_IMAGE_WRITE_STATIC\nstatic int stbi__flip_vertically_on_write=0;\nstatic int stbi_write_png_compression_level = 8;\nstatic int stbi_write_tga_with_rle = 1;\nstatic int stbi_write_force_png_filter = -1;\n#else\nint stbi_write_png_compression_level = 8;\nint stbi__flip_vertically_on_write=0;\nint stbi_write_tga_with_rle = 1;\nint stbi_write_force_png_filter = -1;\n#endif\nSTBIWDEF void stbi_flip_vertically_on_write(int flag)\n{\nstbi__flip_vertically_on_write = flag;\n}\ntypedef struct\n{\nstbi_write_func *func;\nvoid *context;\n} stbi__write_context;\n// initialize a callback-based context\nstatic void stbi__start_write_callbacks(stbi__write_context *s, stbi_write_func *c, void *context)\n{\ns->func    = c;\ns->context = context;\n}\n#ifndef STBI_WRITE_NO_STDIO\nstatic void stbi__stdio_write(void *context, void *data, int size)\n{\nfwrite(data,1,size,(FILE*) context);\n}\n#if defined(_MSC_VER) && defined(STBI_WINDOWS_UTF8)\n#ifdef __cplusplus\n#define STBIW_EXTERN extern \"C\"\n#else\n#define STBIW_EXTERN extern\n#endif\nSTBIW_EXTERN __declspec(dllimport) int __stdcall MultiByteToWideChar(unsigned int cp, unsigned long flags, const char *str, int cbmb, wchar_t *widestr, int cchwide);\nSTBIW_EXTERN __declspec(dllimport) int __stdcall WideCharToMultiByte(unsigned int cp, unsigned long flags, const wchar_t *widestr, int cchwide, char *str, int cbmb, const char *defchar, int *used_default);\nSTBIWDEF int stbiw_convert_wchar_to_utf8(char *buffer, size_t bufferlen, const wchar_t* input)\n{\nreturn WideCharToMultiByte(65001 /* UTF8 */, 0, input, -1, buffer, (int) bufferlen, NULL, NULL);\n}\n#endif\nstatic FILE *stbiw__fopen(char const *filename, char const *mode)\n{\nFILE *f;\n#if defined(_MSC_VER) && defined(STBI_WINDOWS_UTF8)\nwchar_t wMode[64];\nwchar_t wFilename[1024];\nif (0 == MultiByteToWideChar(65001 /* UTF8 */, 0, filename, -1, wFilename, sizeof(wFilename)))\nreturn 0;\nif (0 == MultiByteToWideChar(65001 /* UTF8 */, 0, mode, -1, wMode, sizeof(wMode)))\nreturn 0;\n#if _MSC_VER >= 1400\nif (0 != _wfopen_s(&f, wFilename, wMode))\nf = 0;\n#else\nf = _wfopen(wFilename, wMode);\n#endif\n#elif defined(_MSC_VER) && _MSC_VER >= 1400\nif (0 != fopen_s(&f, filename, mode))\nf=0;\n#else\nf = fopen(filename, mode);\n#endif\nreturn f;\n}\nstatic int stbi__start_write_file(stbi__write_context *s, const char *filename)\n{\nFILE *f = stbiw__fopen(filename, \"wb\");\nstbi__start_write_callbacks(s, stbi__stdio_write, (void *) f);\nreturn f != NULL;\n}\nstatic void stbi__end_write_file(stbi__write_context *s)\n{\nfclose((FILE *)s->context);\n}\n#endif // !STBI_WRITE_NO_STDIO\ntypedef unsigned int stbiw_uint32;\ntypedef int stb_image_write_test[sizeof(stbiw_uint32)==4 ? 1 : -1];\nstatic void stbiw__writefv(stbi__write_context *s, const char *fmt, va_list v)\n{\nwhile (*fmt) {\nswitch (*fmt++) {\ncase ' ': break;\ncase '1': { unsigned char x = STBIW_UCHAR(va_arg(v, int));\ns->func(s->context,&x,1);\nbreak; }\ncase '2': { int x = va_arg(v,int);\nunsigned char b[2];\nb[0] = STBIW_UCHAR(x);\nb[1] = STBIW_UCHAR(x>>8);\ns->func(s->context,b,2);\nbreak; }\ncase '4': { stbiw_uint32 x = va_arg(v,int);\nunsigned char b[4];\nb[0]=STBIW_UCHAR(x);\nb[1]=STBIW_UCHAR(x>>8);\nb[2]=STBIW_UCHAR(x>>16);\nb[3]=STBIW_UCHAR(x>>24);\ns->func(s->context,b,4);\nbreak; }\ndefault:\nSTBIW_ASSERT(0);\nreturn;\n}\n}\n}\nstatic void stbiw__writef(stbi__write_context *s, const char *fmt, ...)\n{\nva_list v;\nva_start(v, fmt);\nstbiw__writefv(s, fmt, v);\nva_end(v);\n}\nstatic void stbiw__putc(stbi__write_context *s, unsigned char c)\n{\ns->func(s->context, &c, 1);\n}\nstatic void stbiw__write3(stbi__write_context *s, unsigned char a, unsigned char b, unsigned char c)\n{\nunsigned char arr[3];\narr[0] = a; arr[1] = b; arr[2] = c;\ns->func(s->context, arr, 3);\n}\nstatic void stbiw__write_pixel(stbi__write_context *s, int rgb_dir, int comp, int write_alpha, int expand_mono, unsigned char *d)\n{\nunsigned char bg[3] = { 255, 0, 255}, px[3];\nint k;\nif (write_alpha < 0)\ns->func(s->context, &d[comp - 1], 1);\nswitch (comp) {\ncase 2: // 2 pixels = mono + alpha, alpha is written separately, so same as 1-channel case\ncase 1:\nif (expand_mono)\nstbiw__write3(s, d[0], d[0], d[0]); // monochrome bmp\nelse\ns->func(s->context, d, 1);  // monochrome TGA\nbreak;\ncase 4:\nif (!write_alpha) {\n// composite against pink background\nfor (k = 0; k < 3; ++k)\npx[k] = bg[k] + ((d[k] - bg[k]) * d[3]) / 255;\nstbiw__write3(s, px[1 - rgb_dir], px[1], px[1 + rgb_dir]);\nbreak;\n}\n/* FALLTHROUGH */\ncase 3:\nstbiw__write3(s, d[1 - rgb_dir], d[1], d[1 + rgb_dir]);\nbreak;\n}\nif (write_alpha > 0)\ns->func(s->context, &d[comp - 1], 1);\n}\nstatic void stbiw__write_pixels(stbi__write_context *s, int rgb_dir, int vdir, int x, int y, int comp, void *data, int write_alpha, int scanline_pad, int expand_mono)\n{\nstbiw_uint32 zero = 0;\nint i,j, j_end;\nif (y <= 0)\nreturn;\nif (stbi__flip_vertically_on_write)\nvdir *= -1;\nif (vdir < 0) {\nj_end = -1; j = y-1;\n} else {\nj_end =  y; j = 0;\n}\nfor (; j != j_end; j += vdir) {\nfor (i=0; i < x; ++i) {\nunsigned char *d = (unsigned char *) data + (j*x+i)*comp;\nstbiw__write_pixel(s, rgb_dir, comp, write_alpha, expand_mono, d);\n}\ns->func(s->context, &zero, scanline_pad);\n}\n}\nstatic int stbiw__outfile(stbi__write_context *s, int rgb_dir, int vdir, int x, int y, int comp, int expand_mono, void *data, int alpha, int pad, const char *fmt, ...)\n{\nif (y < 0 || x < 0) {\nreturn 0;\n} else {\nva_list v;\nva_start(v, fmt);\nstbiw__writefv(s, fmt, v);\nva_end(v);\nstbiw__write_pixels(s,rgb_dir,vdir,x,y,comp,data,alpha,pad, expand_mono);\nreturn 1;\n}\n}\nstatic int stbi_write_bmp_core(stbi__write_context *s, int x, int y, int comp, const void *data)\n{\nint pad = (-x*3) & 3;\nreturn stbiw__outfile(s,-1,-1,x,y,comp,1,(void *) data,0,pad,\n\"11 4 22 4\" \"4 44 22 444444\",\n'B', 'M', 14+40+(x*3+pad)*y, 0,0, 14+40,  // file header\n40, x,y, 1,24, 0,0,0,0,0,0);             // bitmap header\n}\nSTBIWDEF int stbi_write_bmp_to_func(stbi_write_func *func, void *context, int x, int y, int comp, const void *data)\n{\nstbi__write_context s;\nstbi__start_write_callbacks(&s, func, context);\nreturn stbi_write_bmp_core(&s, x, y, comp, data);\n}\n#ifndef STBI_WRITE_NO_STDIO\nSTBIWDEF int stbi_write_bmp(char const *filename, int x, int y, int comp, const void *data)\n{\nstbi__write_context s;\nif (stbi__start_write_file(&s,filename)) {\nint r = stbi_write_bmp_core(&s, x, y, comp, data);\nstbi__end_write_file(&s);\nreturn r;\n} else\nreturn 0;\n}\n#endif \nstatic int stbi_write_tga_core(stbi__write_context *s, int x, int y, int comp, void *data)\n{\nint has_alpha = (comp == 2 || comp == 4);\nint colorbytes = has_alpha ? comp-1 : comp;\nint format = colorbytes < 2 ? 3 : 2; // 3 color channels (RGB/RGBA) = 2, 1 color channel (Y/YA) = 3\nif (y < 0 || x < 0)\nreturn 0;\nif (!stbi_write_tga_with_rle) {\nreturn stbiw__outfile(s, -1, -1, x, y, comp, 0, (void *) data, has_alpha, 0,\n\"111 221 2222 11\", 0, 0, format, 0, 0, 0, 0, 0, x, y, (colorbytes + has_alpha) * 8, has_alpha * 8);\n} else {\nint i,j,k;\nint jend, jdir;\nstbiw__writef(s, \"111 221 2222 11\", 0,0,format+8, 0,0,0, 0,0,x,y, (colorbytes + has_alpha) * 8, has_alpha * 8);\nif (stbi__flip_vertically_on_write) {\nj = 0;\njend = y;\njdir = 1;\n} else {\nj = y-1;\njend = -1;\njdir = -1;\n}\nfor (; j != jend; j += jdir) {\nunsigned char *row = (unsigned char *) data + j * x * comp;\nint len;\nfor (i = 0; i < x; i += len) {\nunsigned char *begin = row + i * comp;\nint diff = 1;\nlen = 1;\nif (i < x - 1) {\n++len;\ndiff = memcmp(begin, row + (i + 1) * comp, comp);\nif (diff) {\nconst unsigned char *prev = begin;\nfor (k = i + 2; k < x && len < 128; ++k) {\nif (memcmp(prev, row + k * comp, comp)) {\nprev += comp;\n++len;\n} else {\n--len;\nbreak;\n}\n}\n} else {\nfor (k = i + 2; k < x && len < 128; ++k) {\nif (!memcmp(begin, row + k * comp, comp)) {\n++len;\n} else {\nbreak;\n}\n}\n}\n}\nif (diff) {\nunsigned char header = STBIW_UCHAR(len - 1);\ns->func(s->context, &header, 1);\nfor (k = 0; k < len; ++k) {\nstbiw__write_pixel(s, -1, comp, has_alpha, 0, begin + k * comp);\n}\n} else {\nunsigned char header = STBIW_UCHAR(len - 129);\ns->func(s->context, &header, 1);\nstbiw__write_pixel(s, -1, comp, has_alpha, 0, begin);\n}\n}\n}\n}\nreturn 1;\n}\nSTBIWDEF int stbi_write_tga_to_func(stbi_write_func *func, void *context, int x, int y, int comp, const void *data)\n{\nstbi__write_context s;\nstbi__start_write_callbacks(&s, func, context);\nreturn stbi_write_tga_core(&s, x, y, comp, (void *) data);\n}\n#ifndef STBI_WRITE_NO_STDIO\nSTBIWDEF int stbi_write_tga(char const *filename, int x, int y, int comp, const void *data)\n{\nstbi__write_context s;\nif (stbi__start_write_file(&s,filename)) {\nint r = stbi_write_tga_core(&s, x, y, comp, (void *) data);\nstbi__end_write_file(&s);\nreturn r;\n} else\nreturn 0;\n}\n#endif\n// *************************************************************************************************\n// Radiance RGBE HDR writer\n// by Baldur Karlsson\n#define stbiw__max(a, b)  ((a) > (b) ? (a) : (b))\nstatic void stbiw__linear_to_rgbe(unsigned char *rgbe, float *linear)\n{\nint exponent;\nfloat maxcomp = stbiw__max(linear[0], stbiw__max(linear[1], linear[2]));\nif (maxcomp < 1e-32f) {\nrgbe[0] = rgbe[1] = rgbe[2] = rgbe[3] = 0;\n} else {\nfloat normalize = (float) frexp(maxcomp, &exponent) * 256.0f/maxcomp;\nrgbe[0] = (unsigned char)(linear[0] * normalize);\nrgbe[1] = (unsigned char)(linear[1] * normalize);\nrgbe[2] = (unsigned char)(linear[2] * normalize);\nrgbe[3] = (unsigned char)(exponent + 128);\n}\n}\nstatic void stbiw__write_run_data(stbi__write_context *s, int length, unsigned char databyte)\n{\nunsigned char lengthbyte = STBIW_UCHAR(length+128);\nSTBIW_ASSERT(length+128 <= 255);\ns->func(s->context, &lengthbyte, 1);\ns->func(s->context, &databyte, 1);\n}\nstatic void stbiw__write_dump_data(stbi__write_context *s, int length, unsigned char *data)\n{\nunsigned char lengthbyte = STBIW_UCHAR(length);\nSTBIW_ASSERT(length <= 128); // inconsistent with spec but consistent with official code\ns->func(s->context, &lengthbyte, 1);\ns->func(s->context, data, length);\n}\nstatic void stbiw__write_hdr_scanline(stbi__write_context *s, int width, int ncomp, unsigned char *scratch, float *scanline)\n{\nunsigned char scanlineheader[4] = { 2, 2, 0, 0 };\nunsigned char rgbe[4];\nfloat linear[3];\nint x;\nscanlineheader[2] = (width&0xff00)>>8;\nscanlineheader[3] = (width&0x00ff);\n/* skip RLE for images too small or large */\nif (width < 8 || width >= 32768) {\nfor (x=0; x < width; x++) {\nswitch (ncomp) {\ncase 4: /* fallthrough */\ncase 3: linear[2] = scanline[x*ncomp + 2];\nlinear[1] = scanline[x*ncomp + 1];\nlinear[0] = scanline[x*ncomp + 0];\nbreak;\ndefault:\nlinear[0] = linear[1] = linear[2] = scanline[x*ncomp + 0];\nbreak;\n}\nstbiw__linear_to_rgbe(rgbe, linear);\ns->func(s->context, rgbe, 4);\n}\n} else {\nint c,r;\n/* encode into scratch buffer */\nfor (x=0; x < width; x++) {\nswitch(ncomp) {\ncase 4: /* fallthrough */\ncase 3: linear[2] = scanline[x*ncomp + 2];\nlinear[1] = scanline[x*ncomp + 1];\nlinear[0] = scanline[x*ncomp + 0];\nbreak;\ndefault:\nlinear[0] = linear[1] = linear[2] = scanline[x*ncomp + 0];\nbreak;\n}\nstbiw__linear_to_rgbe(rgbe, linear);\nscratch[x + width*0] = rgbe[0];\nscratch[x + width*1] = rgbe[1];\nscratch[x + width*2] = rgbe[2];\nscratch[x + width*3] = rgbe[3];\n}\ns->func(s->context, scanlineheader, 4);\n/* RLE each component separately */\nfor (c=0; c < 4; c++) {\nunsigned char *comp = &scratch[width*c];\nx = 0;\nwhile (x < width) {\n// find first run\nr = x;\nwhile (r+2 < width) {\nif (comp[r] == comp[r+1] && comp[r] == comp[r+2])\nbreak;\n++r;\n}\nif (r+2 >= width)\nr = width;\n// dump up to first run\nwhile (x < r) {\nint len = r-x;\nif (len > 128) len = 128;\nstbiw__write_dump_data(s, len, &comp[x]);\nx += len;\n}\n// if there's a run, output it\nif (r+2 < width) { // same test as what we break out of in search loop, so only true if we break'd\n// find next byte after run\nwhile (r < width && comp[r] == comp[x])\n++r;\n// output run up to r\nwhile (x < r) {\nint len = r-x;\nif (len > 127) len = 127;\nstbiw__write_run_data(s, len, comp[x]);\nx += len;\n}\n}\n}\n}\n}\n}\nstatic int stbi_write_hdr_core(stbi__write_context *s, int x, int y, int comp, float *data)\n{\nif (y <= 0 || x <= 0 || data == NULL)\nreturn 0;\nelse {\n// Each component is stored separately. Allocate scratch space for full output scanline.\nunsigned char *scratch = (unsigned char *) STBIW_MALLOC(x*4);\nint i, len;\nchar buffer[128];\nchar header[] = \"#?RADIANCE\\n# Written by stb_image_write.h\\nFORMAT=32-bit_rle_rgbe\\n\";\ns->func(s->context, header, sizeof(header)-1);\n#ifdef __STDC_WANT_SECURE_LIB__\nlen = sprintf_s(buffer, sizeof(buffer), \"EXPOSURE=          1.0000000000000\\n\\n-Y %d +X %d\\n\", y, x);\n#else\nlen = sprintf(buffer, \"EXPOSURE=          1.0000000000000\\n\\n-Y %d +X %d\\n\", y, x);\n#endif\ns->func(s->context, buffer, len);\nfor(i=0; i < y; i++)\nstbiw__write_hdr_scanline(s, x, comp, scratch, data + comp*x*(stbi__flip_vertically_on_write ? y-1-i : i));\nSTBIW_FREE(scratch);\nreturn 1;\n}\n}\nSTBIWDEF int stbi_write_hdr_to_func(stbi_write_func *func, void *context, int x, int y, int comp, const float *data)\n{\nstbi__write_context s;\nstbi__start_write_callbacks(&s, func, context);\nreturn stbi_write_hdr_core(&s, x, y, comp, (float *) data);\n}\n#ifndef STBI_WRITE_NO_STDIO\nSTBIWDEF int stbi_write_hdr(char const *filename, int x, int y, int comp, const float *data)\n{\nstbi__write_context s;\nif (stbi__start_write_file(&s,filename)) {\nint r = stbi_write_hdr_core(&s, x, y, comp, (float *) data);\nstbi__end_write_file(&s);\nreturn r;\n} else\nreturn 0;\n}\n#endif // STBI_WRITE_NO_STDIO\n//\n// PNG writer\n//\n#ifndef STBIW_ZLIB_COMPRESS\n// stretchy buffer; stbiw__sbpush() == vector<>::push_back() -- stbiw__sbcount() == vector<>::size()\n#define stbiw__sbraw(a) ((int *) (a) - 2)\n#define stbiw__sbm(a)   stbiw__sbraw(a)[0]\n#define stbiw__sbn(a)   stbiw__sbraw(a)[1]\n#define stbiw__sbneedgrow(a,n)  ((a)==0 || stbiw__sbn(a)+n >= stbiw__sbm(a))\n#define stbiw__sbmaybegrow(a,n) (stbiw__sbneedgrow(a,(n)) ? stbiw__sbgrow(a,n) : 0)\n#define stbiw__sbgrow(a,n)  stbiw__sbgrowf((void **) &(a), (n), sizeof(*(a)))\n#define stbiw__sbpush(a, v)      (stbiw__sbmaybegrow(a,1), (a)[stbiw__sbn(a)++] = (v))\n#define stbiw__sbcount(a)        ((a) ? stbiw__sbn(a) : 0)\n#define stbiw__sbfree(a)         ((a) ? STBIW_FREE(stbiw__sbraw(a)),0 : 0)\nstatic void *stbiw__sbgrowf(void **arr, int increment, int itemsize)\n{\nint m = *arr ? 2*stbiw__sbm(*arr)+increment : increment+1;\nvoid *p = STBIW_REALLOC_SIZED(*arr ? stbiw__sbraw(*arr) : 0, *arr ? (stbiw__sbm(*arr)*itemsize + sizeof(int)*2) : 0, itemsize * m + sizeof(int)*2);\nSTBIW_ASSERT(p);\nif (p) {\nif (!*arr) ((int *) p)[1] = 0;\n*arr = (void *) ((int *) p + 2);\nstbiw__sbm(*arr) = m;\n}\nreturn *arr;\n}\nstatic unsigned char *stbiw__zlib_flushf(unsigned char *data, unsigned int *bitbuffer, int *bitcount)\n{\nwhile (*bitcount >= 8) {\nstbiw__sbpush(data, STBIW_UCHAR(*bitbuffer));\n*bitbuffer >>= 8;\n*bitcount -= 8;\n}\nreturn data;\n}\nstatic int stbiw__zlib_bitrev(int code, int codebits)\n{\nint res=0;\nwhile (codebits--) {\nres = (res << 1) | (code & 1);\ncode >>= 1;\n}\nreturn res;\n}\nstatic unsigned int stbiw__zlib_countm(unsigned char *a, unsigned char *b, int limit)\n{\nint i;\nfor (i=0; i < limit && i < 258; ++i)\nif (a[i] != b[i]) break;\nreturn i;\n}\nstatic unsigned int stbiw__zhash(unsigned char *data)\n{\nstbiw_uint32 hash = data[0] + (data[1] << 8) + (data[2] << 16);\nhash ^= hash << 3;\nhash += hash >> 5;\nhash ^= hash << 4;\nhash += hash >> 17;\nhash ^= hash << 25;\nhash += hash >> 6;\nreturn hash;\n}\n#define stbiw__zlib_flush() (out = stbiw__zlib_flushf(out, &bitbuf, &bitcount))\n#define stbiw__zlib_add(code,codebits) \\\n      (bitbuf |= (code) << bitcount, bitcount += (codebits), stbiw__zlib_flush())\n#define stbiw__zlib_huffa(b,c)  stbiw__zlib_add(stbiw__zlib_bitrev(b,c),c)\n// default huffman tables\n#define stbiw__zlib_huff1(n)  stbiw__zlib_huffa(0x30 + (n), 8)\n#define stbiw__zlib_huff2(n)  stbiw__zlib_huffa(0x190 + (n)-144, 9)\n#define stbiw__zlib_huff3(n)  stbiw__zlib_huffa(0 + (n)-256,7)\n#define stbiw__zlib_huff4(n)  stbiw__zlib_huffa(0xc0 + (n)-280,8)\n#define stbiw__zlib_huff(n)  ((n) <= 143 ? stbiw__zlib_huff1(n) : (n) <= 255 ? stbiw__zlib_huff2(n) : (n) <= 279 ? stbiw__zlib_huff3(n) : stbiw__zlib_huff4(n))\n#define stbiw__zlib_huffb(n) ((n) <= 143 ? stbiw__zlib_huff1(n) : stbiw__zlib_huff2(n))\n#define stbiw__ZHASH   16384\n#endif // STBIW_ZLIB_COMPRESS\nSTBIWDEF unsigned char * stbi_zlib_compress(unsigned char *data, int data_len, int *out_len, int quality)\n{\n#ifdef STBIW_ZLIB_COMPRESS\n// user provided a zlib compress implementation, use that\nreturn STBIW_ZLIB_COMPRESS(data, data_len, out_len, quality);\n#else // use builtin\nstatic unsigned short lengthc[] = { 3,4,5,6,7,8,9,10,11,13,15,17,19,23,27,31,35,43,51,59,67,83,99,115,131,163,195,227,258, 259 };\nstatic unsigned char  lengtheb[]= { 0,0,0,0,0,0,0, 0, 1, 1, 1, 1, 2, 2, 2, 2, 3, 3, 3, 3, 4, 4, 4,  4,  5,  5,  5,  5,  0 };\nstatic unsigned short distc[]   = { 1,2,3,4,5,7,9,13,17,25,33,49,65,97,129,193,257,385,513,769,1025,1537,2049,3073,4097,6145,8193,12289,16385,24577, 32768 };\nstatic unsigned char  disteb[]  = { 0,0,0,0,1,1,2,2,3,3,4,4,5,5,6,6,7,7,8,8,9,9,10,10,11,11,12,12,13,13 };\nunsigned int bitbuf=0;\nint i,j, bitcount=0;\nunsigned char *out = NULL;\nunsigned char ***hash_table = (unsigned char***) STBIW_MALLOC(stbiw__ZHASH * sizeof(unsigned char**));\nif (hash_table == NULL)\nreturn NULL;\nif (quality < 5) quality = 5;\nstbiw__sbpush(out, 0x78);   // DEFLATE 32K window\nstbiw__sbpush(out, 0x5e);   // FLEVEL = 1\nstbiw__zlib_add(1,1);  // BFINAL = 1\nstbiw__zlib_add(1,2);  // BTYPE = 1 -- fixed huffman\nfor (i=0; i < stbiw__ZHASH; ++i)\nhash_table[i] = NULL;\ni=0;\nwhile (i < data_len-3) {\n// hash next 3 bytes of data to be compressed\nint h = stbiw__zhash(data+i)&(stbiw__ZHASH-1), best=3;\nunsigned char *bestloc = 0;\nunsigned char **hlist = hash_table[h];\nint n = stbiw__sbcount(hlist);\nfor (j=0; j < n; ++j) {\nif (hlist[j]-data > i-32768) { // if entry lies within window\nint d = stbiw__zlib_countm(hlist[j], data+i, data_len-i);\nif (d >= best) { best=d; bestloc=hlist[j]; }\n}\n}\n// when hash table entry is too long, delete half the entries\nif (hash_table[h] && stbiw__sbn(hash_table[h]) == 2*quality) {\nSTBIW_MEMMOVE(hash_table[h], hash_table[h]+quality, sizeof(hash_table[h][0])*quality);\nstbiw__sbn(hash_table[h]) = quality;\n}\nstbiw__sbpush(hash_table[h],data+i);\nif (bestloc) {\n// \"lazy matching\" - check match at *next* byte, and if it's better, do cur byte as literal\nh = stbiw__zhash(data+i+1)&(stbiw__ZHASH-1);\nhlist = hash_table[h];\nn = stbiw__sbcount(hlist);\nfor (j=0; j < n; ++j) {\nif (hlist[j]-data > i-32767) {\nint e = stbiw__zlib_countm(hlist[j], data+i+1, data_len-i-1);\nif (e > best) { // if next match is better, bail on current match\nbestloc = NULL;\nbreak;\n}\n}\n}\n}\nif (bestloc) {\nint d = (int) (data+i - bestloc); // distance back\nSTBIW_ASSERT(d <= 32767 && best <= 258);\nfor (j=0; best > lengthc[j+1]-1; ++j);\nstbiw__zlib_huff(j+257);\nif (lengtheb[j]) stbiw__zlib_add(best - lengthc[j], lengtheb[j]);\nfor (j=0; d > distc[j+1]-1; ++j);\nstbiw__zlib_add(stbiw__zlib_bitrev(j,5),5);\nif (disteb[j]) stbiw__zlib_add(d - distc[j], disteb[j]);\ni += best;\n} else {\nstbiw__zlib_huffb(data[i]);\n++i;\n}\n}\n// write out final bytes\nfor (;i < data_len; ++i)\nstbiw__zlib_huffb(data[i]);\nstbiw__zlib_huff(256); // end of block\n// pad with 0 bits to byte boundary\nwhile (bitcount)\nstbiw__zlib_add(0,1);\nfor (i=0; i < stbiw__ZHASH; ++i)\n(void) stbiw__sbfree(hash_table[i]);\nSTBIW_FREE(hash_table);\n{\n// compute adler32 on input\nunsigned int s1=1, s2=0;\nint blocklen = (int) (data_len % 5552);\nj=0;\nwhile (j < data_len) {\nfor (i=0; i < blocklen; ++i) { s1 += data[j+i]; s2 += s1; }\ns1 %= 65521; s2 %= 65521;\nj += blocklen;\nblocklen = 5552;\n}\nstbiw__sbpush(out, STBIW_UCHAR(s2 >> 8));\nstbiw__sbpush(out, STBIW_UCHAR(s2));\nstbiw__sbpush(out, STBIW_UCHAR(s1 >> 8));\nstbiw__sbpush(out, STBIW_UCHAR(s1));\n}\n*out_len = stbiw__sbn(out);\n// make returned pointer freeable\nSTBIW_MEMMOVE(stbiw__sbraw(out), out, *out_len);\nreturn (unsigned char *) stbiw__sbraw(out);\n#endif // STBIW_ZLIB_COMPRESS\n}\nstatic unsigned int stbiw__crc32(unsigned char *buffer, int len)\n{\n#ifdef STBIW_CRC32\nreturn STBIW_CRC32(buffer, len);\n#else\nstatic unsigned int crc_table[256] =\n{\n0x00000000, 0x77073096, 0xEE0E612C, 0x990951BA, 0x076DC419, 0x706AF48F, 0xE963A535, 0x9E6495A3,\n0x0eDB8832, 0x79DCB8A4, 0xE0D5E91E, 0x97D2D988, 0x09B64C2B, 0x7EB17CBD, 0xE7B82D07, 0x90BF1D91,\n0x1DB71064, 0x6AB020F2, 0xF3B97148, 0x84BE41DE, 0x1ADAD47D, 0x6DDDE4EB, 0xF4D4B551, 0x83D385C7,\n0x136C9856, 0x646BA8C0, 0xFD62F97A, 0x8A65C9EC, 0x14015C4F, 0x63066CD9, 0xFA0F3D63, 0x8D080DF5,\n0x3B6E20C8, 0x4C69105E, 0xD56041E4, 0xA2677172, 0x3C03E4D1, 0x4B04D447, 0xD20D85FD, 0xA50AB56B,\n0x35B5A8FA, 0x42B2986C, 0xDBBBC9D6, 0xACBCF940, 0x32D86CE3, 0x45DF5C75, 0xDCD60DCF, 0xABD13D59,\n0x26D930AC, 0x51DE003A, 0xC8D75180, 0xBFD06116, 0x21B4F4B5, 0x56B3C423, 0xCFBA9599, 0xB8BDA50F,\n0x2802B89E, 0x5F058808, 0xC60CD9B2, 0xB10BE924, 0x2F6F7C87, 0x58684C11, 0xC1611DAB, 0xB6662D3D,\n0x76DC4190, 0x01DB7106, 0x98D220BC, 0xEFD5102A, 0x71B18589, 0x06B6B51F, 0x9FBFE4A5, 0xE8B8D433,\n0x7807C9A2, 0x0F00F934, 0x9609A88E, 0xE10E9818, 0x7F6A0DBB, 0x086D3D2D, 0x91646C97, 0xE6635C01,\n0x6B6B51F4, 0x1C6C6162, 0x856530D8, 0xF262004E, 0x6C0695ED, 0x1B01A57B, 0x8208F4C1, 0xF50FC457,\n0x65B0D9C6, 0x12B7E950, 0x8BBEB8EA, 0xFCB9887C, 0x62DD1DDF, 0x15DA2D49, 0x8CD37CF3, 0xFBD44C65,\n0x4DB26158, 0x3AB551CE, 0xA3BC0074, 0xD4BB30E2, 0x4ADFA541, 0x3DD895D7, 0xA4D1C46D, 0xD3D6F4FB,\n0x4369E96A, 0x346ED9FC, 0xAD678846, 0xDA60B8D0, 0x44042D73, 0x33031DE5, 0xAA0A4C5F, 0xDD0D7CC9,\n0x5005713C, 0x270241AA, 0xBE0B1010, 0xC90C2086, 0x5768B525, 0x206F85B3, 0xB966D409, 0xCE61E49F,\n0x5EDEF90E, 0x29D9C998, 0xB0D09822, 0xC7D7A8B4, 0x59B33D17, 0x2EB40D81, 0xB7BD5C3B, 0xC0BA6CAD,\n0xEDB88320, 0x9ABFB3B6, 0x03B6E20C, 0x74B1D29A, 0xEAD54739, 0x9DD277AF, 0x04DB2615, 0x73DC1683,\n0xE3630B12, 0x94643B84, 0x0D6D6A3E, 0x7A6A5AA8, 0xE40ECF0B, 0x9309FF9D, 0x0A00AE27, 0x7D079EB1,\n0xF00F9344, 0x8708A3D2, 0x1E01F268, 0x6906C2FE, 0xF762575D, 0x806567CB, 0x196C3671, 0x6E6B06E7,\n0xFED41B76, 0x89D32BE0, 0x10DA7A5A, 0x67DD4ACC, 0xF9B9DF6F, 0x8EBEEFF9, 0x17B7BE43, 0x60B08ED5,\n0xD6D6A3E8, 0xA1D1937E, 0x38D8C2C4, 0x4FDFF252, 0xD1BB67F1, 0xA6BC5767, 0x3FB506DD, 0x48B2364B,\n0xD80D2BDA, 0xAF0A1B4C, 0x36034AF6, 0x41047A60, 0xDF60EFC3, 0xA867DF55, 0x316E8EEF, 0x4669BE79,\n0xCB61B38C, 0xBC66831A, 0x256FD2A0, 0x5268E236, 0xCC0C7795, 0xBB0B4703, 0x220216B9, 0x5505262F,\n0xC5BA3BBE, 0xB2BD0B28, 0x2BB45A92, 0x5CB36A04, 0xC2D7FFA7, 0xB5D0CF31, 0x2CD99E8B, 0x5BDEAE1D,\n0x9B64C2B0, 0xEC63F226, 0x756AA39C, 0x026D930A, 0x9C0906A9, 0xEB0E363F, 0x72076785, 0x05005713,\n0x95BF4A82, 0xE2B87A14, 0x7BB12BAE, 0x0CB61B38, 0x92D28E9B, 0xE5D5BE0D, 0x7CDCEFB7, 0x0BDBDF21,\n0x86D3D2D4, 0xF1D4E242, 0x68DDB3F8, 0x1FDA836E, 0x81BE16CD, 0xF6B9265B, 0x6FB077E1, 0x18B74777,\n0x88085AE6, 0xFF0F6A70, 0x66063BCA, 0x11010B5C, 0x8F659EFF, 0xF862AE69, 0x616BFFD3, 0x166CCF45,\n0xA00AE278, 0xD70DD2EE, 0x4E048354, 0x3903B3C2, 0xA7672661, 0xD06016F7, 0x4969474D, 0x3E6E77DB,\n0xAED16A4A, 0xD9D65ADC, 0x40DF0B66, 0x37D83BF0, 0xA9BCAE53, 0xDEBB9EC5, 0x47B2CF7F, 0x30B5FFE9,\n0xBDBDF21C, 0xCABAC28A, 0x53B39330, 0x24B4A3A6, 0xBAD03605, 0xCDD70693, 0x54DE5729, 0x23D967BF,\n0xB3667A2E, 0xC4614AB8, 0x5D681B02, 0x2A6F2B94, 0xB40BBE37, 0xC30C8EA1, 0x5A05DF1B, 0x2D02EF8D\n};\nunsigned int crc = ~0u;\nint i;\nfor (i=0; i < len; ++i)\ncrc = (crc >> 8) ^ crc_table[buffer[i] ^ (crc & 0xff)];\nreturn ~crc;\n#endif\n}\n#define stbiw__wpng4(o,a,b,c,d) ((o)[0]=STBIW_UCHAR(a),(o)[1]=STBIW_UCHAR(b),(o)[2]=STBIW_UCHAR(c),(o)[3]=STBIW_UCHAR(d),(o)+=4)\n#define stbiw__wp32(data,v) stbiw__wpng4(data, (v)>>24,(v)>>16,(v)>>8,(v));\n#define stbiw__wptag(data,s) stbiw__wpng4(data, s[0],s[1],s[2],s[3])\nstatic void stbiw__wpcrc(unsigned char **data, int len)\n{\nunsigned int crc = stbiw__crc32(*data - len - 4, len+4);\nstbiw__wp32(*data, crc);\n}\nstatic unsigned char stbiw__paeth(int a, int b, int c)\n{\nint p = a + b - c, pa = abs(p-a), pb = abs(p-b), pc = abs(p-c);\nif (pa <= pb && pa <= pc) return STBIW_UCHAR(a);\nif (pb <= pc) return STBIW_UCHAR(b);\nreturn STBIW_UCHAR(c);\n}\n// @OPTIMIZE: provide an option that always forces left-predict or paeth predict\nstatic void stbiw__encode_png_line(unsigned char *pixels, int stride_bytes, int width, int height, int y, int n, int filter_type, signed char *line_buffer)\n{\nstatic int mapping[] = { 0,1,2,3,4 };\nstatic int firstmap[] = { 0,1,0,5,6 };\nint *mymap = (y != 0) ? mapping : firstmap;\nint i;\nint type = mymap[filter_type];\nunsigned char *z = pixels + stride_bytes * (stbi__flip_vertically_on_write ? height-1-y : y);\nint signed_stride = stbi__flip_vertically_on_write ? -stride_bytes : stride_bytes;\nif (type==0) {\nmemcpy(line_buffer, z, width*n);\nreturn;\n}\n// first loop isn't optimized since it's just one pixel    \nfor (i = 0; i < n; ++i) {\nswitch (type) {\ncase 1: line_buffer[i] = z[i]; break;\ncase 2: line_buffer[i] = z[i] - z[i-signed_stride]; break;\ncase 3: line_buffer[i] = z[i] - (z[i-signed_stride]>>1); break;\ncase 4: line_buffer[i] = (signed char) (z[i] - stbiw__paeth(0,z[i-signed_stride],0)); break;\ncase 5: line_buffer[i] = z[i]; break;\ncase 6: line_buffer[i] = z[i]; break;\n}\n}\nswitch (type) {\ncase 1: for (i=n; i < width*n; ++i) line_buffer[i] = z[i] - z[i-n]; break;\ncase 2: for (i=n; i < width*n; ++i) line_buffer[i] = z[i] - z[i-signed_stride]; break;\ncase 3: for (i=n; i < width*n; ++i) line_buffer[i] = z[i] - ((z[i-n] + z[i-signed_stride])>>1); break;\ncase 4: for (i=n; i < width*n; ++i) line_buffer[i] = z[i] - stbiw__paeth(z[i-n], z[i-signed_stride], z[i-signed_stride-n]); break;\ncase 5: for (i=n; i < width*n; ++i) line_buffer[i] = z[i] - (z[i-n]>>1); break;\ncase 6: for (i=n; i < width*n; ++i) line_buffer[i] = z[i] - stbiw__paeth(z[i-n], 0,0); break;\n}\n}\nSTBIWDEF unsigned char *stbi_write_png_to_mem(const unsigned char *pixels, int stride_bytes, int x, int y, int n, int *out_len)\n{\nint force_filter = stbi_write_force_png_filter;\nint ctype[5] = { -1, 0, 4, 2, 6 };\nunsigned char sig[8] = { 137,80,78,71,13,10,26,10 };\nunsigned char *out,*o, *filt, *zlib;\nsigned char *line_buffer;\nint j,zlen;\nif (stride_bytes == 0)\nstride_bytes = x * n;\nif (force_filter >= 5) {\nforce_filter = -1;\n}\nfilt = (unsigned char *) STBIW_MALLOC((x*n+1) * y); if (!filt) return 0;\nline_buffer = (signed char *) STBIW_MALLOC(x * n); if (!line_buffer) { STBIW_FREE(filt); return 0; }\nfor (j=0; j < y; ++j) {\nint filter_type;\nif (force_filter > -1) {\nfilter_type = force_filter;\nstbiw__encode_png_line((unsigned char*)(pixels), stride_bytes, x, y, j, n, force_filter, line_buffer);\n} else { // Estimate the best filter by running through all of them:\nint best_filter = 0, best_filter_val = 0x7fffffff, est, i;\nfor (filter_type = 0; filter_type < 5; filter_type++) {\nstbiw__encode_png_line((unsigned char*)(pixels), stride_bytes, x, y, j, n, filter_type, line_buffer);\n// Estimate the entropy of the line using this filter; the less, the better.\nest = 0;\nfor (i = 0; i < x*n; ++i) {\nest += abs((signed char) line_buffer[i]);\n}\nif (est < best_filter_val) {\nbest_filter_val = est;\nbest_filter = filter_type;\n}\n}\nif (filter_type != best_filter) {  // If the last iteration already got us the best filter, don't redo it\nstbiw__encode_png_line((unsigned char*)(pixels), stride_bytes, x, y, j, n, best_filter, line_buffer);\nfilter_type = best_filter;\n}\n}\n// when we get here, filter_type contains the filter type, and line_buffer contains the data\nfilt[j*(x*n+1)] = (unsigned char) filter_type;\nSTBIW_MEMMOVE(filt+j*(x*n+1)+1, line_buffer, x*n);\n}\nSTBIW_FREE(line_buffer);\nzlib = stbi_zlib_compress(filt, y*( x*n+1), &zlen, stbi_write_png_compression_level);\nSTBIW_FREE(filt);\nif (!zlib) return 0;\n// each tag requires 12 bytes of overhead\nout = (unsigned char *) STBIW_MALLOC(8 + 12+13 + 12+zlen + 12);\nif (!out) return 0;\n*out_len = 8 + 12+13 + 12+zlen + 12;\no=out;\nSTBIW_MEMMOVE(o,sig,8); o+= 8;\nstbiw__wp32(o, 13); // header length\nstbiw__wptag(o, \"IHDR\");\nstbiw__wp32(o, x);\nstbiw__wp32(o, y);\n*o++ = 8;\n*o++ = STBIW_UCHAR(ctype[n]);\n*o++ = 0;\n*o++ = 0;\n*o++ = 0;\nstbiw__wpcrc(&o,13);\nstbiw__wp32(o, zlen);\nstbiw__wptag(o, \"IDAT\");\nSTBIW_MEMMOVE(o, zlib, zlen);\no += zlen;\nSTBIW_FREE(zlib);\nstbiw__wpcrc(&o, zlen);\nstbiw__wp32(o,0);\nstbiw__wptag(o, \"IEND\");\nstbiw__wpcrc(&o,0);\nSTBIW_ASSERT(o == out + *out_len);\nreturn out;\n}\n#ifndef STBI_WRITE_NO_STDIO\nSTBIWDEF int stbi_write_png(char const *filename, int x, int y, int comp, const void *data, int stride_bytes)\n{\nFILE *f;\nint len;\nunsigned char *png = stbi_write_png_to_mem((const unsigned char *) data, stride_bytes, x, y, comp, &len);\nif (png == NULL) return 0;\nf = stbiw__fopen(filename, \"wb\");\nif (!f) { STBIW_FREE(png); return 0; }\nfwrite(png, 1, len, f);\nfclose(f);\nSTBIW_FREE(png);\nreturn 1;\n}\n#endif\nSTBIWDEF int stbi_write_png_to_func(stbi_write_func *func, void *context, int x, int y, int comp, const void *data, int stride_bytes)\n{\nint len;\nunsigned char *png = stbi_write_png_to_mem((const unsigned char *) data, stride_bytes, x, y, comp, &len);\nif (png == NULL) return 0;\nfunc(context, png, len);\nSTBIW_FREE(png);\nreturn 1;\n}\n/* ***************************************************************************\n *\n * JPEG writer\n *\n * This is based on Jon Olick's jo_jpeg.cpp:\n * public domain Simple, Minimalistic JPEG writer - http://www.jonolick.com/code.html\n */\nstatic const unsigned char stbiw__jpg_ZigZag[] = { 0,1,5,6,14,15,27,28,2,4,7,13,16,26,29,42,3,8,12,17,25,30,41,43,9,11,18,\n24,31,40,44,53,10,19,23,32,39,45,52,54,20,22,33,38,46,51,55,60,21,34,37,47,50,56,59,61,35,36,48,49,57,58,62,63 };\nstatic void stbiw__jpg_writeBits(stbi__write_context *s, int *bitBufP, int *bitCntP, const unsigned short *bs) {\nint bitBuf = *bitBufP, bitCnt = *bitCntP;\nbitCnt += bs[1];\nbitBuf |= bs[0] << (24 - bitCnt);\nwhile(bitCnt >= 8) {\nunsigned char c = (bitBuf >> 16) & 255;\nstbiw__putc(s, c);\nif(c == 255) {\nstbiw__putc(s, 0);\n}\nbitBuf <<= 8;\nbitCnt -= 8;\n}\n*bitBufP = bitBuf;\n*bitCntP = bitCnt;\n}\nstatic void stbiw__jpg_DCT(float *d0p, float *d1p, float *d2p, float *d3p, float *d4p, float *d5p, float *d6p, float *d7p) {\nfloat d0 = *d0p, d1 = *d1p, d2 = *d2p, d3 = *d3p, d4 = *d4p, d5 = *d5p, d6 = *d6p, d7 = *d7p;\nfloat z1, z2, z3, z4, z5, z11, z13;\nfloat tmp0 = d0 + d7;\nfloat tmp7 = d0 - d7;\nfloat tmp1 = d1 + d6;\nfloat tmp6 = d1 - d6;\nfloat tmp2 = d2 + d5;\nfloat tmp5 = d2 - d5;\nfloat tmp3 = d3 + d4;\nfloat tmp4 = d3 - d4;\n// Even part\nfloat tmp10 = tmp0 + tmp3;   // phase 2\nfloat tmp13 = tmp0 - tmp3;\nfloat tmp11 = tmp1 + tmp2;\nfloat tmp12 = tmp1 - tmp2;\nd0 = tmp10 + tmp11;       // phase 3\nd4 = tmp10 - tmp11;\nz1 = (tmp12 + tmp13) * 0.707106781f; // c4\nd2 = tmp13 + z1;       // phase 5\nd6 = tmp13 - z1;\n// Odd part\ntmp10 = tmp4 + tmp5;       // phase 2\ntmp11 = tmp5 + tmp6;\ntmp12 = tmp6 + tmp7;\n// The rotator is modified from fig 4-8 to avoid extra negations.\nz5 = (tmp10 - tmp12) * 0.382683433f; // c6\nz2 = tmp10 * 0.541196100f + z5; // c2-c6\nz4 = tmp12 * 1.306562965f + z5; // c2+c6\nz3 = tmp11 * 0.707106781f; // c4\nz11 = tmp7 + z3;      // phase 5\nz13 = tmp7 - z3;\n*d5p = z13 + z2;         // phase 6\n*d3p = z13 - z2;\n*d1p = z11 + z4;\n*d7p = z11 - z4;\n*d0p = d0;  *d2p = d2;  *d4p = d4;  *d6p = d6;\n}\nstatic void stbiw__jpg_calcBits(int val, unsigned short bits[2]) {\nint tmp1 = val < 0 ? -val : val;\nval = val < 0 ? val-1 : val;\nbits[1] = 1;\nwhile(tmp1 >>= 1) {\n++bits[1];\n}\nbits[0] = val & ((1<<bits[1])-1);\n}\nstatic int stbiw__jpg_processDU(stbi__write_context *s, int *bitBuf, int *bitCnt, float *CDU, float *fdtbl, int DC, const unsigned short HTDC[256][2], const unsigned short HTAC[256][2]) {\nconst unsigned short EOB[2] = { HTAC[0x00][0], HTAC[0x00][1] };\nconst unsigned short M16zeroes[2] = { HTAC[0xF0][0], HTAC[0xF0][1] };\nint dataOff, i, diff, end0pos;\nint DU[64];\n// DCT rows\nfor(dataOff=0; dataOff<64; dataOff+=8) {\nstbiw__jpg_DCT(&CDU[dataOff], &CDU[dataOff+1], &CDU[dataOff+2], &CDU[dataOff+3], &CDU[dataOff+4], &CDU[dataOff+5], &CDU[dataOff+6], &CDU[dataOff+7]);\n}\n// DCT columns\nfor(dataOff=0; dataOff<8; ++dataOff) {\nstbiw__jpg_DCT(&CDU[dataOff], &CDU[dataOff+8], &CDU[dataOff+16], &CDU[dataOff+24], &CDU[dataOff+32], &CDU[dataOff+40], &CDU[dataOff+48], &CDU[dataOff+56]);\n}\n// Quantize/descale/zigzag the coefficients\nfor(i=0; i<64; ++i) {\nfloat v = CDU[i]*fdtbl[i];\n// DU[stbiw__jpg_ZigZag[i]] = (int)(v < 0 ? ceilf(v - 0.5f) : floorf(v + 0.5f));\n// ceilf() and floorf() are C99, not C89, but I /think/ they're not needed here anyway?\nDU[stbiw__jpg_ZigZag[i]] = (int)(v < 0 ? v - 0.5f : v + 0.5f);\n}\n// Encode DC\ndiff = DU[0] - DC;\nif (diff == 0) {\nstbiw__jpg_writeBits(s, bitBuf, bitCnt, HTDC[0]);\n} else {\nunsigned short bits[2];\nstbiw__jpg_calcBits(diff, bits);\nstbiw__jpg_writeBits(s, bitBuf, bitCnt, HTDC[bits[1]]);\nstbiw__jpg_writeBits(s, bitBuf, bitCnt, bits);\n}\n// Encode ACs\nend0pos = 63;\nfor(; (end0pos>0)&&(DU[end0pos]==0); --end0pos) {\n}\n// end0pos = first element in reverse order !=0\nif(end0pos == 0) {\nstbiw__jpg_writeBits(s, bitBuf, bitCnt, EOB);\nreturn DU[0];\n}\nfor(i = 1; i <= end0pos; ++i) {\nint startpos = i;\nint nrzeroes;\nunsigned short bits[2];\nfor (; DU[i]==0 && i<=end0pos; ++i) {\n}\nnrzeroes = i-startpos;\nif ( nrzeroes >= 16 ) {\nint lng = nrzeroes>>4;\nint nrmarker;\nfor (nrmarker=1; nrmarker <= lng; ++nrmarker)\nstbiw__jpg_writeBits(s, bitBuf, bitCnt, M16zeroes);\nnrzeroes &= 15;\n}\nstbiw__jpg_calcBits(DU[i], bits);\nstbiw__jpg_writeBits(s, bitBuf, bitCnt, HTAC[(nrzeroes<<4)+bits[1]]);\nstbiw__jpg_writeBits(s, bitBuf, bitCnt, bits);\n}\nif(end0pos != 63) {\nstbiw__jpg_writeBits(s, bitBuf, bitCnt, EOB);\n}\nreturn DU[0];\n}\nstatic int stbi_write_jpg_core(stbi__write_context *s, int width, int height, int comp, const void* data, int quality) {\n// Constants that don't pollute global namespace\nstatic const unsigned char std_dc_luminance_nrcodes[] = {0,0,1,5,1,1,1,1,1,1,0,0,0,0,0,0,0};\nstatic const unsigned char std_dc_luminance_values[] = {0,1,2,3,4,5,6,7,8,9,10,11};\nstatic const unsigned char std_ac_luminance_nrcodes[] = {0,0,2,1,3,3,2,4,3,5,5,4,4,0,0,1,0x7d};\nstatic const unsigned char std_ac_luminance_values[] = {\n0x01,0x02,0x03,0x00,0x04,0x11,0x05,0x12,0x21,0x31,0x41,0x06,0x13,0x51,0x61,0x07,0x22,0x71,0x14,0x32,0x81,0x91,0xa1,0x08,\n0x23,0x42,0xb1,0xc1,0x15,0x52,0xd1,0xf0,0x24,0x33,0x62,0x72,0x82,0x09,0x0a,0x16,0x17,0x18,0x19,0x1a,0x25,0x26,0x27,0x28,\n0x29,0x2a,0x34,0x35,0x36,0x37,0x38,0x39,0x3a,0x43,0x44,0x45,0x46,0x47,0x48,0x49,0x4a,0x53,0x54,0x55,0x56,0x57,0x58,0x59,\n0x5a,0x63,0x64,0x65,0x66,0x67,0x68,0x69,0x6a,0x73,0x74,0x75,0x76,0x77,0x78,0x79,0x7a,0x83,0x84,0x85,0x86,0x87,0x88,0x89,\n0x8a,0x92,0x93,0x94,0x95,0x96,0x97,0x98,0x99,0x9a,0xa2,0xa3,0xa4,0xa5,0xa6,0xa7,0xa8,0xa9,0xaa,0xb2,0xb3,0xb4,0xb5,0xb6,\n0xb7,0xb8,0xb9,0xba,0xc2,0xc3,0xc4,0xc5,0xc6,0xc7,0xc8,0xc9,0xca,0xd2,0xd3,0xd4,0xd5,0xd6,0xd7,0xd8,0xd9,0xda,0xe1,0xe2,\n0xe3,0xe4,0xe5,0xe6,0xe7,0xe8,0xe9,0xea,0xf1,0xf2,0xf3,0xf4,0xf5,0xf6,0xf7,0xf8,0xf9,0xfa\n};\nstatic const unsigned char std_dc_chrominance_nrcodes[] = {0,0,3,1,1,1,1,1,1,1,1,1,0,0,0,0,0};\nstatic const unsigned char std_dc_chrominance_values[] = {0,1,2,3,4,5,6,7,8,9,10,11};\nstatic const unsigned char std_ac_chrominance_nrcodes[] = {0,0,2,1,2,4,4,3,4,7,5,4,4,0,1,2,0x77};\nstatic const unsigned char std_ac_chrominance_values[] = {\n0x00,0x01,0x02,0x03,0x11,0x04,0x05,0x21,0x31,0x06,0x12,0x41,0x51,0x07,0x61,0x71,0x13,0x22,0x32,0x81,0x08,0x14,0x42,0x91,\n0xa1,0xb1,0xc1,0x09,0x23,0x33,0x52,0xf0,0x15,0x62,0x72,0xd1,0x0a,0x16,0x24,0x34,0xe1,0x25,0xf1,0x17,0x18,0x19,0x1a,0x26,\n0x27,0x28,0x29,0x2a,0x35,0x36,0x37,0x38,0x39,0x3a,0x43,0x44,0x45,0x46,0x47,0x48,0x49,0x4a,0x53,0x54,0x55,0x56,0x57,0x58,\n0x59,0x5a,0x63,0x64,0x65,0x66,0x67,0x68,0x69,0x6a,0x73,0x74,0x75,0x76,0x77,0x78,0x79,0x7a,0x82,0x83,0x84,0x85,0x86,0x87,\n0x88,0x89,0x8a,0x92,0x93,0x94,0x95,0x96,0x97,0x98,0x99,0x9a,0xa2,0xa3,0xa4,0xa5,0xa6,0xa7,0xa8,0xa9,0xaa,0xb2,0xb3,0xb4,\n0xb5,0xb6,0xb7,0xb8,0xb9,0xba,0xc2,0xc3,0xc4,0xc5,0xc6,0xc7,0xc8,0xc9,0xca,0xd2,0xd3,0xd4,0xd5,0xd6,0xd7,0xd8,0xd9,0xda,\n0xe2,0xe3,0xe4,0xe5,0xe6,0xe7,0xe8,0xe9,0xea,0xf2,0xf3,0xf4,0xf5,0xf6,0xf7,0xf8,0xf9,0xfa\n};\n// Huffman tables\nstatic const unsigned short YDC_HT[256][2] = { {0,2},{2,3},{3,3},{4,3},{5,3},{6,3},{14,4},{30,5},{62,6},{126,7},{254,8},{510,9}};\nstatic const unsigned short UVDC_HT[256][2] = { {0,2},{1,2},{2,2},{6,3},{14,4},{30,5},{62,6},{126,7},{254,8},{510,9},{1022,10},{2046,11}};\nstatic const unsigned short YAC_HT[256][2] = {\n{10,4},{0,2},{1,2},{4,3},{11,4},{26,5},{120,7},{248,8},{1014,10},{65410,16},{65411,16},{0,0},{0,0},{0,0},{0,0},{0,0},{0,0},\n{12,4},{27,5},{121,7},{502,9},{2038,11},{65412,16},{65413,16},{65414,16},{65415,16},{65416,16},{0,0},{0,0},{0,0},{0,0},{0,0},{0,0},\n{28,5},{249,8},{1015,10},{4084,12},{65417,16},{65418,16},{65419,16},{65420,16},{65421,16},{65422,16},{0,0},{0,0},{0,0},{0,0},{0,0},{0,0},\n{58,6},{503,9},{4085,12},{65423,16},{65424,16},{65425,16},{65426,16},{65427,16},{65428,16},{65429,16},{0,0},{0,0},{0,0},{0,0},{0,0},{0,0},\n{59,6},{1016,10},{65430,16},{65431,16},{65432,16},{65433,16},{65434,16},{65435,16},{65436,16},{65437,16},{0,0},{0,0},{0,0},{0,0},{0,0},{0,0},\n{122,7},{2039,11},{65438,16},{65439,16},{65440,16},{65441,16},{65442,16},{65443,16},{65444,16},{65445,16},{0,0},{0,0},{0,0},{0,0},{0,0},{0,0},\n{123,7},{4086,12},{65446,16},{65447,16},{65448,16},{65449,16},{65450,16},{65451,16},{65452,16},{65453,16},{0,0},{0,0},{0,0},{0,0},{0,0},{0,0},\n{250,8},{4087,12},{65454,16},{65455,16},{65456,16},{65457,16},{65458,16},{65459,16},{65460,16},{65461,16},{0,0},{0,0},{0,0},{0,0},{0,0},{0,0},\n{504,9},{32704,15},{65462,16},{65463,16},{65464,16},{65465,16},{65466,16},{65467,16},{65468,16},{65469,16},{0,0},{0,0},{0,0},{0,0},{0,0},{0,0},\n{505,9},{65470,16},{65471,16},{65472,16},{65473,16},{65474,16},{65475,16},{65476,16},{65477,16},{65478,16},{0,0},{0,0},{0,0},{0,0},{0,0},{0,0},\n{506,9},{65479,16},{65480,16},{65481,16},{65482,16},{65483,16},{65484,16},{65485,16},{65486,16},{65487,16},{0,0},{0,0},{0,0},{0,0},{0,0},{0,0},\n{1017,10},{65488,16},{65489,16},{65490,16},{65491,16},{65492,16},{65493,16},{65494,16},{65495,16},{65496,16},{0,0},{0,0},{0,0},{0,0},{0,0},{0,0},\n{1018,10},{65497,16},{65498,16},{65499,16},{65500,16},{65501,16},{65502,16},{65503,16},{65504,16},{65505,16},{0,0},{0,0},{0,0},{0,0},{0,0},{0,0},\n{2040,11},{65506,16},{65507,16},{65508,16},{65509,16},{65510,16},{65511,16},{65512,16},{65513,16},{65514,16},{0,0},{0,0},{0,0},{0,0},{0,0},{0,0},\n{65515,16},{65516,16},{65517,16},{65518,16},{65519,16},{65520,16},{65521,16},{65522,16},{65523,16},{65524,16},{0,0},{0,0},{0,0},{0,0},{0,0},\n{2041,11},{65525,16},{65526,16},{65527,16},{65528,16},{65529,16},{65530,16},{65531,16},{65532,16},{65533,16},{65534,16},{0,0},{0,0},{0,0},{0,0},{0,0}\n};\nstatic const unsigned short UVAC_HT[256][2] = {\n{0,2},{1,2},{4,3},{10,4},{24,5},{25,5},{56,6},{120,7},{500,9},{1014,10},{4084,12},{0,0},{0,0},{0,0},{0,0},{0,0},{0,0},\n{11,4},{57,6},{246,8},{501,9},{2038,11},{4085,12},{65416,16},{65417,16},{65418,16},{65419,16},{0,0},{0,0},{0,0},{0,0},{0,0},{0,0},\n{26,5},{247,8},{1015,10},{4086,12},{32706,15},{65420,16},{65421,16},{65422,16},{65423,16},{65424,16},{0,0},{0,0},{0,0},{0,0},{0,0},{0,0},\n{27,5},{248,8},{1016,10},{4087,12},{65425,16},{65426,16},{65427,16},{65428,16},{65429,16},{65430,16},{0,0},{0,0},{0,0},{0,0},{0,0},{0,0},\n{58,6},{502,9},{65431,16},{65432,16},{65433,16},{65434,16},{65435,16},{65436,16},{65437,16},{65438,16},{0,0},{0,0},{0,0},{0,0},{0,0},{0,0},\n{59,6},{1017,10},{65439,16},{65440,16},{65441,16},{65442,16},{65443,16},{65444,16},{65445,16},{65446,16},{0,0},{0,0},{0,0},{0,0},{0,0},{0,0},\n{121,7},{2039,11},{65447,16},{65448,16},{65449,16},{65450,16},{65451,16},{65452,16},{65453,16},{65454,16},{0,0},{0,0},{0,0},{0,0},{0,0},{0,0},\n{122,7},{2040,11},{65455,16},{65456,16},{65457,16},{65458,16},{65459,16},{65460,16},{65461,16},{65462,16},{0,0},{0,0},{0,0},{0,0},{0,0},{0,0},\n{249,8},{65463,16},{65464,16},{65465,16},{65466,16},{65467,16},{65468,16},{65469,16},{65470,16},{65471,16},{0,0},{0,0},{0,0},{0,0},{0,0},{0,0},\n{503,9},{65472,16},{65473,16},{65474,16},{65475,16},{65476,16},{65477,16},{65478,16},{65479,16},{65480,16},{0,0},{0,0},{0,0},{0,0},{0,0},{0,0},\n{504,9},{65481,16},{65482,16},{65483,16},{65484,16},{65485,16},{65486,16},{65487,16},{65488,16},{65489,16},{0,0},{0,0},{0,0},{0,0},{0,0},{0,0},\n{505,9},{65490,16},{65491,16},{65492,16},{65493,16},{65494,16},{65495,16},{65496,16},{65497,16},{65498,16},{0,0},{0,0},{0,0},{0,0},{0,0},{0,0},\n{506,9},{65499,16},{65500,16},{65501,16},{65502,16},{65503,16},{65504,16},{65505,16},{65506,16},{65507,16},{0,0},{0,0},{0,0},{0,0},{0,0},{0,0},\n{2041,11},{65508,16},{65509,16},{65510,16},{65511,16},{65512,16},{65513,16},{65514,16},{65515,16},{65516,16},{0,0},{0,0},{0,0},{0,0},{0,0},{0,0},\n{16352,14},{65517,16},{65518,16},{65519,16},{65520,16},{65521,16},{65522,16},{65523,16},{65524,16},{65525,16},{0,0},{0,0},{0,0},{0,0},{0,0},\n{1018,10},{32707,15},{65526,16},{65527,16},{65528,16},{65529,16},{65530,16},{65531,16},{65532,16},{65533,16},{65534,16},{0,0},{0,0},{0,0},{0,0},{0,0}\n};\nstatic const int YQT[] = {16,11,10,16,24,40,51,61,12,12,14,19,26,58,60,55,14,13,16,24,40,57,69,56,14,17,22,29,51,87,80,62,18,22,\n37,56,68,109,103,77,24,35,55,64,81,104,113,92,49,64,78,87,103,121,120,101,72,92,95,98,112,100,103,99};\nstatic const int UVQT[] = {17,18,24,47,99,99,99,99,18,21,26,66,99,99,99,99,24,26,56,99,99,99,99,99,47,66,99,99,99,99,99,99,\n99,99,99,99,99,99,99,99,99,99,99,99,99,99,99,99,99,99,99,99,99,99,99,99,99,99,99,99,99,99,99,99};\nstatic const float aasf[] = { 1.0f * 2.828427125f, 1.387039845f * 2.828427125f, 1.306562965f * 2.828427125f, 1.175875602f * 2.828427125f, 1.0f * 2.828427125f, 0.785694958f * 2.828427125f, 0.541196100f * 2.828427125f, 0.275899379f * 2.828427125f };\nint row, col, i, k;\nfloat fdtbl_Y[64], fdtbl_UV[64];\nunsigned char YTable[64], UVTable[64];\nif(!data || !width || !height || comp > 4 || comp < 1) {\nreturn 0;\n}\nquality = quality ? quality : 90;\nquality = quality < 1 ? 1 : quality > 100 ? 100 : quality;\nquality = quality < 50 ? 5000 / quality : 200 - quality * 2;\nfor(i = 0; i < 64; ++i) {\nint uvti, yti = (YQT[i]*quality+50)/100;\nYTable[stbiw__jpg_ZigZag[i]] = (unsigned char) (yti < 1 ? 1 : yti > 255 ? 255 : yti);\nuvti = (UVQT[i]*quality+50)/100;\nUVTable[stbiw__jpg_ZigZag[i]] = (unsigned char) (uvti < 1 ? 1 : uvti > 255 ? 255 : uvti);\n}\nfor(row = 0, k = 0; row < 8; ++row) {\nfor(col = 0; col < 8; ++col, ++k) {\nfdtbl_Y[k]  = 1 / (YTable [stbiw__jpg_ZigZag[k]] * aasf[row] * aasf[col]);\nfdtbl_UV[k] = 1 / (UVTable[stbiw__jpg_ZigZag[k]] * aasf[row] * aasf[col]);\n}\n}\n// Write Headers\n{\nstatic const unsigned char head0[] = { 0xFF,0xD8,0xFF,0xE0,0,0x10,'J','F','I','F',0,1,1,0,0,1,0,1,0,0,0xFF,0xDB,0,0x84,0 };\nstatic const unsigned char head2[] = { 0xFF,0xDA,0,0xC,3,1,0,2,0x11,3,0x11,0,0x3F,0 };\nconst unsigned char head1[] = { 0xFF,0xC0,0,0x11,8,(unsigned char)(height>>8),STBIW_UCHAR(height),(unsigned char)(width>>8),STBIW_UCHAR(width),\n3,1,0x11,0,2,0x11,1,3,0x11,1,0xFF,0xC4,0x01,0xA2,0 };\ns->func(s->context, (void*)head0, sizeof(head0));\ns->func(s->context, (void*)YTable, sizeof(YTable));\nstbiw__putc(s, 1);\ns->func(s->context, UVTable, sizeof(UVTable));\ns->func(s->context, (void*)head1, sizeof(head1));\ns->func(s->context, (void*)(std_dc_luminance_nrcodes+1), sizeof(std_dc_luminance_nrcodes)-1);\ns->func(s->context, (void*)std_dc_luminance_values, sizeof(std_dc_luminance_values));\nstbiw__putc(s, 0x10); // HTYACinfo\ns->func(s->context, (void*)(std_ac_luminance_nrcodes+1), sizeof(std_ac_luminance_nrcodes)-1);\ns->func(s->context, (void*)std_ac_luminance_values, sizeof(std_ac_luminance_values));\nstbiw__putc(s, 1); // HTUDCinfo\ns->func(s->context, (void*)(std_dc_chrominance_nrcodes+1), sizeof(std_dc_chrominance_nrcodes)-1);\ns->func(s->context, (void*)std_dc_chrominance_values, sizeof(std_dc_chrominance_values));\nstbiw__putc(s, 0x11); // HTUACinfo\ns->func(s->context, (void*)(std_ac_chrominance_nrcodes+1), sizeof(std_ac_chrominance_nrcodes)-1);\ns->func(s->context, (void*)std_ac_chrominance_values, sizeof(std_ac_chrominance_values));\ns->func(s->context, (void*)head2, sizeof(head2));\n}\n// Encode 8x8 macroblocks\n{\nstatic const unsigned short fillBits[] = {0x7F, 7};\nconst unsigned char *imageData = (const unsigned char *)data;\nint DCY=0, DCU=0, DCV=0;\nint bitBuf=0, bitCnt=0;\n// comp == 2 is grey+alpha (alpha is ignored)\nint ofsG = comp > 2 ? 1 : 0, ofsB = comp > 2 ? 2 : 0;\nint x, y, pos;\nfor(y = 0; y < height; y += 8) {\nfor(x = 0; x < width; x += 8) {\nfloat YDU[64], UDU[64], VDU[64];\nfor(row = y, pos = 0; row < y+8; ++row) {\n// row >= height => use last input row\nint clamped_row = (row < height) ? row : height - 1;\nint base_p = (stbi__flip_vertically_on_write ? (height-1-clamped_row) : clamped_row)*width*comp;\nfor(col = x; col < x+8; ++col, ++pos) {\nfloat r, g, b;\n// if col >= width => use pixel from last input column\nint p = base_p + ((col < width) ? col : (width-1))*comp;\nr = imageData[p+0];\ng = imageData[p+ofsG];\nb = imageData[p+ofsB];\nYDU[pos]=+0.29900f*r+0.58700f*g+0.11400f*b-128;\nUDU[pos]=-0.16874f*r-0.33126f*g+0.50000f*b;\nVDU[pos]=+0.50000f*r-0.41869f*g-0.08131f*b;\n}\n}\nDCY = stbiw__jpg_processDU(s, &bitBuf, &bitCnt, YDU, fdtbl_Y, DCY, YDC_HT, YAC_HT);\nDCU = stbiw__jpg_processDU(s, &bitBuf, &bitCnt, UDU, fdtbl_UV, DCU, UVDC_HT, UVAC_HT);\nDCV = stbiw__jpg_processDU(s, &bitBuf, &bitCnt, VDU, fdtbl_UV, DCV, UVDC_HT, UVAC_HT);\n}\n}\n// Do the bit alignment of the EOI marker\nstbiw__jpg_writeBits(s, &bitBuf, &bitCnt, fillBits);\n}\n// EOI\nstbiw__putc(s, 0xFF);\nstbiw__putc(s, 0xD9);\nreturn 1;\n}\nSTBIWDEF int stbi_write_jpg_to_func(stbi_write_func *func, void *context, int x, int y, int comp, const void *data, int quality)\n{\nstbi__write_context s;\nstbi__start_write_callbacks(&s, func, context);\nreturn stbi_write_jpg_core(&s, x, y, comp, (void *) data, quality);\n}\n#ifndef STBI_WRITE_NO_STDIO\nSTBIWDEF int stbi_write_jpg(char const *filename, int x, int y, int comp, const void *data, int quality)\n{\nstbi__write_context s;\nif (stbi__start_write_file(&s,filename)) {\nint r = stbi_write_jpg_core(&s, x, y, comp, data, quality);\nstbi__end_write_file(&s);\nreturn r;\n} else\nreturn 0;\n}\n#endif\n#endif // STB_IMAGE_WRITE_IMPLEMENTATION\n/* Revision history\n      1.11  (2019-08-11)\n      1.10  (2019-02-07)\n             support utf8 filenames in Windows; fix warnings and platform ifdefs \n      1.09  (2018-02-11)\n             fix typo in zlib quality API, improve STB_I_W_STATIC in C++\n      1.08  (2018-01-29)\n             add stbi__flip_vertically_on_write, external zlib, zlib quality, choose PNG filter\n      1.07  (2017-07-24)\n             doc fix\n      1.06 (2017-07-23)\n             writing JPEG (using Jon Olick's code)\n      1.05   ???\n      1.04 (2017-03-03)\n             monochrome BMP expansion\n      1.03   ???\n      1.02 (2016-04-02)\n             avoid allocating large structures on the stack\n      1.01 (2016-01-16)\n             STBIW_REALLOC_SIZED: support allocators with no realloc support\n             avoid race-condition in crc initialization\n             minor compile issues\n      1.00 (2015-09-14)\n             installable file IO function\n      0.99 (2015-09-13)\n             warning fixes; TGA rle support\n      0.98 (2015-04-08)\n             added STBIW_MALLOC, STBIW_ASSERT etc\n      0.97 (2015-01-18)\n             fixed HDR asserts, rewrote HDR rle logic\n      0.96 (2015-01-17)\n             add HDR output\n             fix monochrome BMP\n      0.95 (2014-08-17)\n               add monochrome TGA output\n      0.94 (2014-05-31)\n             rename private functions to avoid conflicts with stb_image.h\n      0.93 (2014-05-27)\n             warning fixes\n      0.92 (2010-08-01)\n             casts to unsigned char to fix warnings\n      0.91 (2010-07-17)\n             first public release\n      0.90   first internal release\n*/\n/*\n------------------------------------------------------------------------------\nThis software is available under 2 licenses -- choose whichever you prefer.\n------------------------------------------------------------------------------\nALTERNATIVE A - MIT License\nCopyright (c) 2017 Sean Barrett\nPermission is hereby granted, free of charge, to any person obtaining a copy of \nthis software and associated documentation files (the \"Software\"), to deal in \nthe Software without restriction, including without limitation the rights to \nuse, copy, modify, merge, publish, distribute, sublicense, and/or sell copies \nof the Software, and to permit persons to whom the Software is furnished to do \nso, subject to the following conditions:\nThe above copyright notice and this permission notice shall be included in all \ncopies or substantial portions of the Software.\nTHE SOFTWARE IS PROVIDED \"AS IS\", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR \nIMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, \nFITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE \nAUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER \nLIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, \nOUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE \nSOFTWARE.\n------------------------------------------------------------------------------\nALTERNATIVE B - Public Domain (www.unlicense.org)\nThis is free and unencumbered software released into the public domain.\nAnyone is free to copy, modify, publish, use, compile, sell, or distribute this \nsoftware, either in source code form or as a compiled binary, for any purpose, \ncommercial or non-commercial, and by any means.\nIn jurisdictions that recognize copyright laws, the author or authors of this \nsoftware dedicate any and all copyright interest in the software to the public \ndomain. We make this dedication for the benefit of the public at large and to \nthe detriment of our heirs and successors. We intend this dedication to be an \novert act of relinquishment in perpetuity of all present and future rights to \nthis software under copyright law.\nTHE SOFTWARE IS PROVIDED \"AS IS\", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR \nIMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, \nFITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE \nAUTHORS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER LIABILITY, WHETHER IN AN \nACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN CONNECTION \nWITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE.\n------------------------------------------------------------------------------\n*/\n
"},{"location":"api/dir_087fbdcd93b501a5d3f98df93e9f8cc4/","title":"Dir robot_dart/robots","text":"

FileList > robot_dart > robots

"},{"location":"api/dir_087fbdcd93b501a5d3f98df93e9f8cc4/#files","title":"Files","text":"Type Name file a1.cpp file a1.hpp file arm.hpp file franka.cpp file franka.hpp file hexapod.hpp file icub.cpp file icub.hpp file iiwa.cpp file iiwa.hpp file pendulum.hpp file talos.cpp file talos.hpp file tiago.cpp file tiago.hpp file ur3e.cpp file ur3e.hpp file vx300.hpp

The documentation for this class was generated from the following file robot_dart/robots/

"},{"location":"api/a1_8cpp/","title":"File a1.cpp","text":"

FileList > robot_dart > robots > a1.cpp

Go to the source code of this file

"},{"location":"api/a1_8cpp/#namespaces","title":"Namespaces","text":"Type Name namespace robot_dart namespace robots

The documentation for this class was generated from the following file robot_dart/robots/a1.cpp

"},{"location":"api/a1_8cpp_source/","title":"File a1.cpp","text":"

File List > robot_dart > robots > a1.cpp

Go to the documentation of this file

#include \"robot_dart/robots/a1.hpp\"\n#include \"robot_dart/robot_dart_simu.hpp\"\nnamespace robot_dart {\nnamespace robots {\nA1::A1(size_t frequency, const std::string& urdf, const std::vector<std::pair<std::string, std::string>>& packages)\n: Robot(urdf, packages),\n_imu(std::make_shared<sensor::IMU>(sensor::IMUConfig(body_node(\"imu_link\"), frequency)))\n{\nset_color_mode(\"material\");\nset_self_collision(true);\nset_position_enforced(true);\n// put above ground\nset_base_pose(robot_dart::make_vector({0., 0., 0., 0., 0., 0.5}));\n// standing pose\nauto names = dof_names(true, true, true);\nnames = std::vector<std::string>(names.begin() + 6, names.end());\nset_positions(robot_dart::make_vector({0.0, 0.67, -1.3, -0.0, 0.67, -1.3, 0.0, 0.67, -1.3, -0.0, 0.67, -1.3}), names);\n}\nvoid A1::reset()\n{\nRobot::reset();\n// put above ground\nset_base_pose(robot_dart::make_vector({0., 0., 0., 0., 0., 0.5}));\n// standing pose\nauto names = dof_names(true, true, true);\nnames = std::vector<std::string>(names.begin() + 6, names.end());\nset_positions(robot_dart::make_vector({0.0, 0.67, -1.3, -0.0, 0.67, -1.3, 0.0, 0.67, -1.3, -0.0, 0.67, -1.3}), names);\n}\n} // namespace robots\n} // namespace robot_dart\n
"},{"location":"api/a1_8hpp/","title":"File a1.hpp","text":"

FileList > robot_dart > robots > a1.hpp

Go to the source code of this file

"},{"location":"api/a1_8hpp/#namespaces","title":"Namespaces","text":"Type Name namespace robot_dart namespace robots"},{"location":"api/a1_8hpp/#classes","title":"Classes","text":"Type Name class A1

The documentation for this class was generated from the following file robot_dart/robots/a1.hpp

"},{"location":"api/a1_8hpp_source/","title":"File a1.hpp","text":"

File List > robot_dart > robots > a1.hpp

Go to the documentation of this file

#ifndef ROBOT_DART_ROBOTS_A1_HPP\n#define ROBOT_DART_ROBOTS_A1_HPP\n#include \"robot_dart/robot.hpp\"\n#include \"robot_dart/sensor/imu.hpp\"\nnamespace robot_dart {\nnamespace robots {\nclass A1 : public Robot {\npublic:\nA1(size_t frequency = 1000, const std::string& urdf = \"unitree_a1/a1.urdf\", const std::vector<std::pair<std::string, std::string>>& packages = ('a1_description', 'unitree_a1/a1_description'));\nvoid reset() override;\nconst sensor::IMU& imu() const { return *_imu; }\nprotected:\nstd::shared_ptr<sensor::IMU> _imu;\n};\n} // namespace robots\n} // namespace robot_dart\n#endif\n
"},{"location":"api/arm_8hpp/","title":"File arm.hpp","text":"

FileList > robot_dart > robots > arm.hpp

Go to the source code of this file

"},{"location":"api/arm_8hpp/#namespaces","title":"Namespaces","text":"Type Name namespace robot_dart namespace robots"},{"location":"api/arm_8hpp/#classes","title":"Classes","text":"Type Name class Arm

The documentation for this class was generated from the following file robot_dart/robots/arm.hpp

"},{"location":"api/arm_8hpp_source/","title":"File arm.hpp","text":"

File List > robot_dart > robots > arm.hpp

Go to the documentation of this file

#ifndef ROBOT_DART_ROBOTS_ARM_HPP\n#define ROBOT_DART_ROBOTS_ARM_HPP\n#include \"robot_dart/robot.hpp\"\nnamespace robot_dart {\nnamespace robots {\nclass Arm : public Robot {\npublic:\nArm(const std::string& urdf = \"arm.urdf\") : Robot(urdf)\n{\nfix_to_world();\nset_position_enforced(true);\n}\n};\n} // namespace robots\n} // namespace robot_dart\n#endif\n
"},{"location":"api/franka_8cpp/","title":"File franka.cpp","text":"

FileList > robot_dart > robots > franka.cpp

Go to the source code of this file

"},{"location":"api/franka_8cpp/#namespaces","title":"Namespaces","text":"Type Name namespace robot_dart namespace robots

The documentation for this class was generated from the following file robot_dart/robots/franka.cpp

"},{"location":"api/franka_8cpp_source/","title":"File franka.cpp","text":"

File List > robot_dart > robots > franka.cpp

Go to the documentation of this file

#include \"robot_dart/robots/franka.hpp\"\n#include \"robot_dart/robot_dart_simu.hpp\"\nnamespace robot_dart {\nnamespace robots {\nFranka::Franka(size_t frequency, const std::string& urdf, const std::vector<std::pair<std::string, std::string>>& packages)\n: Robot(urdf, packages),\n_ft_wrist(std::make_shared<sensor::ForceTorque>(joint(\"panda_link7\"), frequency))\n{\nfix_to_world();\nset_position_enforced(true);\nset_color_mode(\"material\");\n}\nvoid Franka::_post_addition(RobotDARTSimu* simu)\n{\n// We do not want to add sensors if we are a ghost robot\nif (ghost())\nreturn;\nsimu->add_sensor(_ft_wrist);\n}\nvoid Franka::_post_removal(RobotDARTSimu* simu)\n{\nsimu->remove_sensor(_ft_wrist);\n}\n} // namespace robots\n} // namespace robot_dart\n
"},{"location":"api/franka_8hpp/","title":"File franka.hpp","text":"

FileList > robot_dart > robots > franka.hpp

Go to the source code of this file

"},{"location":"api/franka_8hpp/#namespaces","title":"Namespaces","text":"Type Name namespace robot_dart namespace robots"},{"location":"api/franka_8hpp/#classes","title":"Classes","text":"Type Name class Franka

The documentation for this class was generated from the following file robot_dart/robots/franka.hpp

"},{"location":"api/franka_8hpp_source/","title":"File franka.hpp","text":"

File List > robot_dart > robots > franka.hpp

Go to the documentation of this file

#ifndef ROBOT_DART_ROBOTS_FRANKA_HPP\n#define ROBOT_DART_ROBOTS_FRANKA_HPP\n#include \"robot_dart/robot.hpp\"\n#include \"robot_dart/sensor/force_torque.hpp\"\nnamespace robot_dart {\nnamespace robots {\nclass Franka : public Robot {\npublic:\nFranka(size_t frequency = 1000, const std::string& urdf = \"franka/franka.urdf\", const std::vector<std::pair<std::string, std::string>>& packages = ('franka_description', 'franka/franka_description'));\nconst sensor::ForceTorque& ft_wrist() const { return *_ft_wrist; }\nprotected:\nstd::shared_ptr<sensor::ForceTorque> _ft_wrist;\nvoid _post_addition(RobotDARTSimu* simu) override;\nvoid _post_removal(RobotDARTSimu* simu) override;\n};\n} // namespace robots\n} // namespace robot_dart\n#endif\n
"},{"location":"api/hexapod_8hpp/","title":"File hexapod.hpp","text":"

FileList > robot_dart > robots > hexapod.hpp

Go to the source code of this file

"},{"location":"api/hexapod_8hpp/#namespaces","title":"Namespaces","text":"Type Name namespace robot_dart namespace robots"},{"location":"api/hexapod_8hpp/#classes","title":"Classes","text":"Type Name class Hexapod

The documentation for this class was generated from the following file robot_dart/robots/hexapod.hpp

"},{"location":"api/hexapod_8hpp_source/","title":"File hexapod.hpp","text":"

File List > robot_dart > robots > hexapod.hpp

Go to the documentation of this file

#ifndef ROBOT_DART_ROBOTS_HEXAPOD_HPP\n#define ROBOT_DART_ROBOTS_HEXAPOD_HPP\n#include \"robot_dart/robot.hpp\"\nnamespace robot_dart {\nnamespace robots {\nclass Hexapod : public Robot {\npublic:\nHexapod(const std::string& urdf = \"pexod.urdf\") : Robot(urdf)\n{\nset_position_enforced(true);\nskeleton()->enableSelfCollisionCheck();\nset_base_pose(robot_dart::make_vector({0., 0., 0., 0., 0., 0.2}));\n}\nvoid reset() override\n{\nRobot::reset();\nset_base_pose(robot_dart::make_vector({0., 0., 0., 0., 0., 0.2}));\n}\n};\n} // namespace robots\n} // namespace robot_dart\n#endif\n
"},{"location":"api/icub_8cpp/","title":"File icub.cpp","text":"

FileList > robot_dart > robots > icub.cpp

Go to the source code of this file

"},{"location":"api/icub_8cpp/#namespaces","title":"Namespaces","text":"Type Name namespace robot_dart namespace robots

The documentation for this class was generated from the following file robot_dart/robots/icub.cpp

"},{"location":"api/icub_8cpp_source/","title":"File icub.cpp","text":"

File List > robot_dart > robots > icub.cpp

Go to the documentation of this file

#include \"robot_dart/robots/icub.hpp\"\n#include \"robot_dart/robot_dart_simu.hpp\"\nnamespace robot_dart {\nnamespace robots {\nICub::ICub(size_t frequency, const std::string& urdf, const std::vector<std::pair<std::string, std::string>>& packages)\n: Robot(urdf, packages),\n_imu(std::make_shared<sensor::IMU>(sensor::IMUConfig(body_node(\"head\"), frequency))),\n_ft_foot_left(std::make_shared<sensor::ForceTorque>(joint(\"l_ankle_roll\"), frequency)),\n_ft_foot_right(std::make_shared<sensor::ForceTorque>(joint(\"r_ankle_roll\"), frequency))\n{\nset_color_mode(\"material\");\nset_position_enforced(true);\n// position iCub\nset_base_pose(robot_dart::make_vector({0., 0., M_PI / 2., 0., 0., 0.46}));\n}\nvoid ICub::reset()\n{\nRobot::reset();\n// position iCub\nset_base_pose(robot_dart::make_vector({0., 0., M_PI / 2., 0., 0., 0.46}));\n}\nvoid ICub::_post_addition(RobotDARTSimu* simu)\n{\n// We do not want to add sensors if we are a ghost robot\nif (ghost())\nreturn;\nsimu->add_sensor(_imu);\nsimu->add_sensor(_ft_foot_left);\nsimu->add_sensor(_ft_foot_right);\n}\nvoid ICub::_post_removal(RobotDARTSimu* simu)\n{\nsimu->remove_sensor(_imu);\nsimu->remove_sensor(_ft_foot_left);\nsimu->remove_sensor(_ft_foot_right);\n}\n} // namespace robots\n} // namespace robot_dart\n
"},{"location":"api/icub_8hpp/","title":"File icub.hpp","text":"

FileList > robot_dart > robots > icub.hpp

Go to the source code of this file

"},{"location":"api/icub_8hpp/#namespaces","title":"Namespaces","text":"Type Name namespace robot_dart namespace robots"},{"location":"api/icub_8hpp/#classes","title":"Classes","text":"Type Name class ICub

The documentation for this class was generated from the following file robot_dart/robots/icub.hpp

"},{"location":"api/icub_8hpp_source/","title":"File icub.hpp","text":"

File List > robot_dart > robots > icub.hpp

Go to the documentation of this file

#ifndef ROBOT_DART_ROBOTS_ICUB_HPP\n#define ROBOT_DART_ROBOTS_ICUB_HPP\n#include \"robot_dart/robot.hpp\"\n#include \"robot_dart/sensor/force_torque.hpp\"\n#include \"robot_dart/sensor/imu.hpp\"\nnamespace robot_dart {\nnamespace robots {\nclass ICub : public Robot {\npublic:\nICub(size_t frequency = 1000, const std::string& urdf = \"icub/icub.urdf\", const std::vector<std::pair<std::string, std::string>>& packages = ('icub_description', 'icub/icub_description'));\nvoid reset() override;\nconst sensor::IMU& imu() const { return *_imu; }\nconst sensor::ForceTorque& ft_foot_left() const { return *_ft_foot_left; }\nconst sensor::ForceTorque& ft_foot_right() const { return *_ft_foot_right; }\nprotected:\nstd::shared_ptr<sensor::IMU> _imu;\nstd::shared_ptr<sensor::ForceTorque> _ft_foot_left;\nstd::shared_ptr<sensor::ForceTorque> _ft_foot_right;\nvoid _post_addition(RobotDARTSimu* simu) override;\nvoid _post_removal(RobotDARTSimu* simu) override;\n};\n} // namespace robots\n} // namespace robot_dart\n#endif\n
"},{"location":"api/iiwa_8cpp/","title":"File iiwa.cpp","text":"

FileList > robot_dart > robots > iiwa.cpp

Go to the source code of this file

"},{"location":"api/iiwa_8cpp/#namespaces","title":"Namespaces","text":"Type Name namespace robot_dart namespace robots

The documentation for this class was generated from the following file robot_dart/robots/iiwa.cpp

"},{"location":"api/iiwa_8cpp_source/","title":"File iiwa.cpp","text":"

File List > robot_dart > robots > iiwa.cpp

Go to the documentation of this file

#include \"robot_dart/robots/iiwa.hpp\"\n#include \"robot_dart/robot_dart_simu.hpp\"\nnamespace robot_dart {\nnamespace robots {\nIiwa::Iiwa(size_t frequency, const std::string& urdf, const std::vector<std::pair<std::string, std::string>>& packages)\n: Robot(urdf, packages),\n_ft_wrist(std::make_shared<sensor::ForceTorque>(joint(\"iiwa_joint_ee\"), frequency))\n{\nfix_to_world();\nset_position_enforced(true);\n}\nvoid Iiwa::_post_addition(RobotDARTSimu* simu)\n{\n// We do not want to add sensors if we are a ghost robot\nif (ghost())\nreturn;\nsimu->add_sensor(_ft_wrist);\n}\nvoid Iiwa::_post_removal(RobotDARTSimu* simu)\n{\nsimu->remove_sensor(_ft_wrist);\n}\n} // namespace robots\n} // namespace robot_dart\n
"},{"location":"api/iiwa_8hpp/","title":"File iiwa.hpp","text":"

FileList > robot_dart > robots > iiwa.hpp

Go to the source code of this file

"},{"location":"api/iiwa_8hpp/#namespaces","title":"Namespaces","text":"Type Name namespace robot_dart namespace robots"},{"location":"api/iiwa_8hpp/#classes","title":"Classes","text":"Type Name class Iiwa

The documentation for this class was generated from the following file robot_dart/robots/iiwa.hpp

"},{"location":"api/iiwa_8hpp_source/","title":"File iiwa.hpp","text":"

File List > robot_dart > robots > iiwa.hpp

Go to the documentation of this file

#ifndef ROBOT_DART_ROBOTS_IIWA_HPP\n#define ROBOT_DART_ROBOTS_IIWA_HPP\n#include \"robot_dart/robot.hpp\"\n#include \"robot_dart/sensor/force_torque.hpp\"\nnamespace robot_dart {\nnamespace robots {\nclass Iiwa : public Robot {\npublic:\nIiwa(size_t frequency = 1000, const std::string& urdf = \"iiwa/iiwa.urdf\", const std::vector<std::pair<std::string, std::string>>& packages = ('iiwa_description', 'iiwa/iiwa_description'));\nconst sensor::ForceTorque& ft_wrist() const { return *_ft_wrist; }\nprotected:\nstd::shared_ptr<sensor::ForceTorque> _ft_wrist;\nvoid _post_addition(RobotDARTSimu* simu) override;\nvoid _post_removal(RobotDARTSimu* simu) override;\n};\n} // namespace robots\n} // namespace robot_dart\n#endif\n
"},{"location":"api/pendulum_8hpp/","title":"File pendulum.hpp","text":"

FileList > robot_dart > robots > pendulum.hpp

Go to the source code of this file

"},{"location":"api/pendulum_8hpp/#namespaces","title":"Namespaces","text":"Type Name namespace robot_dart namespace robots"},{"location":"api/pendulum_8hpp/#classes","title":"Classes","text":"Type Name class Pendulum

The documentation for this class was generated from the following file robot_dart/robots/pendulum.hpp

"},{"location":"api/pendulum_8hpp_source/","title":"File pendulum.hpp","text":"

File List > robot_dart > robots > pendulum.hpp

Go to the documentation of this file

#ifndef ROBOT_DART_ROBOTS_PENDULUM_HPP\n#define ROBOT_DART_ROBOTS_PENDULUM_HPP\n#include \"robot_dart/robot.hpp\"\nnamespace robot_dart {\nnamespace robots {\nclass Pendulum : public Robot {\npublic:\nPendulum(const std::string& urdf = \"pendulum.urdf\") : Robot(urdf)\n{\nfix_to_world();\nset_position_enforced(true);\nset_positions(robot_dart::make_vector({M_PI}));\n}\n};\n} // namespace robots\n} // namespace robot_dart\n#endif\n
"},{"location":"api/talos_8cpp/","title":"File talos.cpp","text":"

FileList > robot_dart > robots > talos.cpp

Go to the source code of this file

"},{"location":"api/talos_8cpp/#namespaces","title":"Namespaces","text":"Type Name namespace robot_dart namespace robots

The documentation for this class was generated from the following file robot_dart/robots/talos.cpp

"},{"location":"api/talos_8cpp_source/","title":"File talos.cpp","text":"

File List > robot_dart > robots > talos.cpp

Go to the documentation of this file

#include \"robot_dart/robots/talos.hpp\"\n#include \"robot_dart/robot_dart_simu.hpp\"\nnamespace robot_dart {\nnamespace robots {\nTalos::Talos(size_t frequency, const std::string& urdf, const std::vector<std::pair<std::string, std::string>>& packages)\n: Robot(urdf, packages),\n_imu(std::make_shared<sensor::IMU>(sensor::IMUConfig(body_node(\"imu_link\"), frequency))),\n_ft_foot_left(std::make_shared<sensor::ForceTorque>(joint(\"leg_left_6_joint\"), frequency, \"parent_to_child\")),\n_ft_foot_right(std::make_shared<sensor::ForceTorque>(joint(\"leg_right_6_joint\"), frequency, \"parent_to_child\")),\n_ft_wrist_left(std::make_shared<sensor::ForceTorque>(joint(\"wrist_left_ft_joint\"), frequency, \"parent_to_child\")),\n_ft_wrist_right(std::make_shared<sensor::ForceTorque>(joint(\"wrist_right_ft_joint\"), frequency, \"parent_to_child\")),\n_frequency(frequency)\n{\n// use position/torque limits\nset_position_enforced(true);\n// position Talos\nset_base_pose(robot_dart::make_vector({0., 0., M_PI / 2., 0., 0., 1.1}));\n}\nvoid Talos::reset()\n{\nRobot::reset();\n// position Talos\nset_base_pose(robot_dart::make_vector({0., 0., M_PI / 2., 0., 0., 1.1}));\n}\nvoid Talos::_post_addition(RobotDARTSimu* simu)\n{\n// We do not want to add sensors if we are a ghost robot\nif (ghost())\nreturn;\nsimu->add_sensor(_imu);\nsimu->add_sensor(_ft_foot_left);\nsimu->add_sensor(_ft_foot_right);\nsimu->add_sensor(_ft_wrist_left);\nsimu->add_sensor(_ft_wrist_right);\n// torques sensors\nstd::vector<std::string> joints = {\n// torso\n\"torso_1_joint\",\n\"torso_2_joint\",\n// arm_left\n\"arm_left_1_joint\", \"arm_left_2_joint\",\n\"arm_left_3_joint\", \"arm_left_4_joint\",\n// arm_right\n\"arm_right_1_joint\", \"arm_right_2_joint\",\n\"arm_right_3_joint\", \"arm_right_4_joint\",\n// leg_left\n\"leg_left_1_joint\", \"leg_left_2_joint\", \"leg_left_3_joint\",\n\"leg_left_4_joint\", \"leg_left_5_joint\", \"leg_left_6_joint\",\n// leg_right\n\"leg_right_1_joint\", \"leg_right_2_joint\", \"leg_right_3_joint\",\n\"leg_right_4_joint\", \"leg_right_5_joint\", \"leg_right_6_joint\"\n};\nfor (auto& s : joints) {\nauto t = std::make_shared<sensor::Torque>(joint(s), _frequency);\n_torques[s] = t;\nsimu->add_sensor(t);\n}\n}\nvoid Talos::_post_removal(RobotDARTSimu* simu)\n{\nsimu->remove_sensor(_imu);\nsimu->remove_sensor(_ft_foot_left);\nsimu->remove_sensor(_ft_foot_right);\nsimu->remove_sensor(_ft_wrist_left);\nsimu->remove_sensor(_ft_wrist_right);\nfor (auto& t : _torques) {\nsimu->remove_sensor(t.second);\n}\n}\nvoid TalosFastCollision::_post_addition(RobotDARTSimu* simu)\n{\nTalos::_post_addition(simu);\nauto vec = TalosFastCollision::collision_vec();\nfor (auto& t : vec) {\nsimu->set_collision_masks(simu->robots().size() - 1, std::get<0>(t), std::get<1>(t), std::get<2>(t));\n}\n}\nstd::vector<std::tuple<std::string, uint32_t, uint32_t>> TalosFastCollision::collision_vec()\n{\nstd::vector<std::tuple<std::string, uint32_t, uint32_t>> vec;\nvec.push_back(std::make_tuple(\"leg_right_6_link\", 0x1, 0x1 | 0x4 | 0x8 | 0x10 | 0x20 | 0x40 | 0x80 | 0x100 | 0x200 | 0x400 | 0x800 | 0x1000 | 0x2000 | 0x4000 | 0x8000 | 0x10000));\nvec.push_back(std::make_tuple(\"leg_right_4_link\", 0x2, 0x2 | 0x4 | 0x8 | 0x10 | 0x20 | 0x40 | 0x80 | 0x100 | 0x200 | 0x400 | 0x800 | 0x1000 | 0x2000 | 0x4000 | 0x8000 | 0x10000));\nvec.push_back(std::make_tuple(\"leg_left_6_link\", 0x4, 0x1 | 0x2 | 0x4 | 0x10 | 0x20 | 0x40 | 0x80 | 0x100 | 0x200 | 0x400 | 0x800 | 0x1000 | 0x2000 | 0x4000 | 0x8000 | 0x10000));\nvec.push_back(std::make_tuple(\"leg_left_4_link\", 0x8, 0x1 | 0x2 | 0x8 | 0x10 | 0x20 | 0x40 | 0x80 | 0x100 | 0x200 | 0x400 | 0x800 | 0x1000 | 0x2000 | 0x4000 | 0x8000 | 0x10000));\nvec.push_back(std::make_tuple(\"leg_left_1_link\", 0x10, 0x1 | 0x2 | 0x4 | 0x8 | 0x10 | 0x40 | 0x80 | 0x100 | 0x200 | 0x400 | 0x800 | 0x1000 | 0x2000 | 0x4000 | 0x8000 | 0x10000));\nvec.push_back(std::make_tuple(\"leg_left_3_link\", 0x20, 0x1 | 0x2 | 0x4 | 0x8 | 0x20 | 0x40 | 0x80 | 0x100 | 0x200 | 0x400 | 0x800 | 0x1000 | 0x2000 | 0x4000 | 0x8000 | 0x10000));\nvec.push_back(std::make_tuple(\"leg_right_1_link\", 0x40, 0x1 | 0x2 | 0x4 | 0x8 | 0x10 | 0x20 | 0x40 | 0x100 | 0x200 | 0x400 | 0x800 | 0x1000 | 0x2000 | 0x4000 | 0x8000 | 0x10000));\nvec.push_back(std::make_tuple(\"leg_right_3_link\", 0x80, 0x1 | 0x2 | 0x4 | 0x8 | 0x10 | 0x20 | 0x80 | 0x100 | 0x200 | 0x400 | 0x800 | 0x1000 | 0x2000 | 0x4000 | 0x8000 | 0x10000));\nvec.push_back(std::make_tuple(\"arm_left_7_link\", 0x100, 0x1 | 0x2 | 0x4 | 0x8 | 0x10 | 0x20 | 0x40 | 0x80 | 0x100 | 0x400 | 0x800 | 0x1000 | 0x2000 | 0x4000 | 0x8000 | 0x10000));\nvec.push_back(std::make_tuple(\"arm_left_5_link\", 0x200, 0x1 | 0x2 | 0x4 | 0x8 | 0x10 | 0x20 | 0x40 | 0x80 | 0x200 | 0x400 | 0x800 | 0x1000 | 0x2000 | 0x4000 | 0x8000 | 0x10000));\nvec.push_back(std::make_tuple(\"arm_right_7_link\", 0x400, 0x1 | 0x2 | 0x4 | 0x8 | 0x10 | 0x20 | 0x40 | 0x80 | 0x100 | 0x200 | 0x400 | 0x1000 | 0x2000 | 0x4000 | 0x8000 | 0x10000));\nvec.push_back(std::make_tuple(\"arm_right_5_link\", 0x800, 0x1 | 0x2 | 0x4 | 0x8 | 0x10 | 0x20 | 0x40 | 0x80 | 0x100 | 0x200 | 0x800 | 0x1000 | 0x2000 | 0x4000 | 0x8000 | 0x10000));\nvec.push_back(std::make_tuple(\"torso_2_link\", 0x1000, 0x1 | 0x2 | 0x4 | 0x8 | 0x10 | 0x20 | 0x40 | 0x80 | 0x100 | 0x200 | 0x800 | 0x1000 | 0x4000 | 0x8000));\nvec.push_back(std::make_tuple(\"base_link\", 0x2000, 0x1 | 0x2 | 0x4 | 0x8 | 0x10 | 0x20 | 0x40 | 0x80 | 0x100 | 0x200 | 0x800 | 0x2000 | 0x10000));\nvec.push_back(std::make_tuple(\"leg_right_2_link\", 0x4000, 0x1 | 0x2 | 0x4 | 0x8 | 0x10 | 0x20 | 0x40 | 0x80 | 0x100 | 0x200 | 0x800 | 0x1000 | 0x4000 | 0x8000 | 0x10000));\nvec.push_back(std::make_tuple(\"leg_left_2_link\", 0x8000, 0x1 | 0x2 | 0x4 | 0x8 | 0x10 | 0x20 | 0x40 | 0x80 | 0x100 | 0x200 | 0x800 | 0x1000 | 0x4000 | 0x8000 | 0x10000));\nvec.push_back(std::make_tuple(\"head_2_link\", 0x10000, 0x1 | 0x2 | 0x4 | 0x8 | 0x10 | 0x20 | 0x40 | 0x80 | 0x100 | 0x200 | 0x800 | 0x2000 | 0x4000 | 0x8000 | 0x10000));\nreturn vec;\n}\n} // namespace robots\n} // namespace robot_dart\n
"},{"location":"api/talos_8hpp/","title":"File talos.hpp","text":"

FileList > robot_dart > robots > talos.hpp

Go to the source code of this file

"},{"location":"api/talos_8hpp/#namespaces","title":"Namespaces","text":"Type Name namespace robot_dart namespace robots"},{"location":"api/talos_8hpp/#classes","title":"Classes","text":"Type Name class Talos datasheet: https://pal-robotics.com/wp-content/uploads/2019/07/Datasheet_TALOS.pdf __ class TalosFastCollision class TalosLight

The documentation for this class was generated from the following file robot_dart/robots/talos.hpp

"},{"location":"api/talos_8hpp_source/","title":"File talos.hpp","text":"

File List > robot_dart > robots > talos.hpp

Go to the documentation of this file

#ifndef ROBOT_DART_ROBOTS_TALOS_HPP\n#define ROBOT_DART_ROBOTS_TALOS_HPP\n#include \"robot_dart/robot.hpp\"\n#include \"robot_dart/sensor/force_torque.hpp\"\n#include \"robot_dart/sensor/imu.hpp\"\n#include \"robot_dart/sensor/torque.hpp\"\nnamespace robot_dart {\nnamespace robots {\nclass Talos : public Robot {\npublic:\nTalos(size_t frequency = 1000, const std::string& urdf = \"talos/talos.urdf\", const std::vector<std::pair<std::string, std::string>>& packages = ('talos_description', 'talos/talos_description'));\nvoid reset() override;\nconst sensor::IMU& imu() const { return *_imu; }\nconst sensor::ForceTorque& ft_foot_left() const { return *_ft_foot_left; }\nconst sensor::ForceTorque& ft_foot_right() const { return *_ft_foot_right; }\nconst sensor::ForceTorque& ft_wrist_left() const { return *_ft_wrist_left; }\nconst sensor::ForceTorque& ft_wrist_right() const { return *_ft_wrist_right; }\nusing torque_map_t = std::unordered_map<std::string, std::shared_ptr<sensor::Torque>>;\nconst torque_map_t& torques() const { return _torques; }\nprotected:\nstd::shared_ptr<sensor::IMU> _imu;\nstd::shared_ptr<sensor::ForceTorque> _ft_foot_left;\nstd::shared_ptr<sensor::ForceTorque> _ft_foot_right;\nstd::shared_ptr<sensor::ForceTorque> _ft_wrist_left;\nstd::shared_ptr<sensor::ForceTorque> _ft_wrist_right;\ntorque_map_t _torques;\nsize_t _frequency;\nvoid _post_addition(RobotDARTSimu* simu) override;\nvoid _post_removal(RobotDARTSimu* simu) override;\n};\nclass TalosLight : public Talos {\npublic:\nTalosLight(size_t frequency = 1000, const std::string& urdf = \"talos/talos_fast.urdf\", const std::vector<std::pair<std::string, std::string>>& packages = ('talos_description', 'talos/talos_description')) : Talos(frequency, urdf, packages) {}\n};\n// for talos_fast_collision.urdf or talos_box.urdf which have simple box collision shapes\nclass TalosFastCollision : public Talos {\npublic:\nTalosFastCollision(size_t frequency = 1000, const std::string& urdf = \"talos/talos_fast_collision.urdf\", const std::vector<std::pair<std::string, std::string>>& packages = ('talos_description', 'talos/talos_description')) : Talos(frequency, urdf, packages) { set_self_collision(); }\nstatic std::vector<std::tuple<std::string, uint32_t, uint32_t>> collision_vec();\nprotected:\nvoid _post_addition(RobotDARTSimu* simu) override;\n};\n} // namespace robots\n} // namespace robot_dart\n#endif\n
"},{"location":"api/tiago_8cpp/","title":"File tiago.cpp","text":"

FileList > robot_dart > robots > tiago.cpp

Go to the source code of this file

"},{"location":"api/tiago_8cpp/#namespaces","title":"Namespaces","text":"Type Name namespace robot_dart namespace robots

The documentation for this class was generated from the following file robot_dart/robots/tiago.cpp

"},{"location":"api/tiago_8cpp_source/","title":"File tiago.cpp","text":"

File List > robot_dart > robots > tiago.cpp

Go to the documentation of this file

#include \"robot_dart/robots/tiago.hpp\"\n#include \"robot_dart/robot_dart_simu.hpp\"\nnamespace robot_dart {\nnamespace robots {\nTiago::Tiago(size_t frequency, const std::string& urdf, const std::vector<std::pair<std::string, std::string>>& packages)\n: Robot(urdf, packages),\n_ft_wrist(std::make_shared<sensor::ForceTorque>(joint(\"gripper_tool_joint\"), frequency))\n{\nset_position_enforced(true);\n// We use servo actuators, but not for the caster joints\nset_actuator_types(\"servo\");\n// position Tiago\nset_base_pose(robot_dart::make_vector({0., 0., M_PI / 2., 0., 0., 0.}));\n}\nvoid Tiago::reset()\n{\nRobot::reset();\n// position Tiago\nset_base_pose(robot_dart::make_vector({0., 0., M_PI / 2., 0., 0., 0.}));\n}\nvoid Tiago::set_actuator_types(const std::string& type, const std::vector<std::string>& joint_names, bool override_mimic, bool override_base, bool override_caster)\n{\nauto jt = joint_names;\nif (!override_caster) {\nif (joint_names.size() == 0)\njt = Robot::joint_names();\nfor (const auto& jnt : caster_joints()) {\nauto it = std::find(jt.begin(), jt.end(), jnt);\nif (it != jt.end()) {\njt.erase(it);\n}\n}\n}\nRobot::set_actuator_types(type, jt, override_mimic, override_base);\n}\nvoid Tiago::set_actuator_type(const std::string& type, const std::string& joint_name, bool override_mimic, bool override_base, bool override_caster)\n{\nset_actuator_types(type, {joint_name}, override_mimic, override_base, override_caster);\n}\nvoid Tiago::_post_addition(RobotDARTSimu* simu)\n{\n// We do not want to add sensors if we are a ghost robot\nif (ghost())\nreturn;\nsimu->add_sensor(_ft_wrist);\n}\nvoid Tiago::_post_removal(RobotDARTSimu* simu)\n{\nsimu->remove_sensor(_ft_wrist);\n}\n} // namespace robots\n} // namespace robot_dart\n
"},{"location":"api/tiago_8hpp/","title":"File tiago.hpp","text":"

FileList > robot_dart > robots > tiago.hpp

Go to the source code of this file

"},{"location":"api/tiago_8hpp/#namespaces","title":"Namespaces","text":"Type Name namespace robot_dart namespace robots"},{"location":"api/tiago_8hpp/#classes","title":"Classes","text":"Type Name class Tiago datasheet: https://pal-robotics.com/wp-content/uploads/2021/07/Datasheet-complete_TIAGo-2021.pdf __

The documentation for this class was generated from the following file robot_dart/robots/tiago.hpp

"},{"location":"api/tiago_8hpp_source/","title":"File tiago.hpp","text":"

File List > robot_dart > robots > tiago.hpp

Go to the documentation of this file

#ifndef ROBOT_DART_ROBOTS_TIAGO_HPP\n#define ROBOT_DART_ROBOTS_TIAGO_HPP\n#include \"robot_dart/robot.hpp\"\n#include \"robot_dart/sensor/force_torque.hpp\"\nnamespace robot_dart {\nnamespace robots {\nclass Tiago : public Robot {\npublic:\nTiago(size_t frequency = 1000, const std::string& urdf = \"tiago/tiago_steel.urdf\", const std::vector<std::pair<std::string, std::string>>& packages = ('tiago_description', 'tiago/tiago_description'));\nvoid reset() override;\nconst sensor::ForceTorque& ft_wrist() const { return *_ft_wrist; }\nstd::vector<std::string> caster_joints() const { return {\"caster_back_left_2_joint\", \"caster_back_left_1_joint\", \"caster_back_right_2_joint\", \"caster_back_right_1_joint\", \"caster_front_left_2_joint\", \"caster_front_left_1_joint\", \"caster_front_right_2_joint\", \"caster_front_right_1_joint\"}; }\nvoid set_actuator_types(const std::string& type, const std::vector<std::string>& joint_names = {}, bool override_mimic = false, bool override_base = false, bool override_caster = false);\nvoid set_actuator_type(const std::string& type, const std::string& joint_name, bool override_mimic = false, bool override_base = false, bool override_caster = false);\nprotected:\nstd::shared_ptr<sensor::ForceTorque> _ft_wrist;\nvoid _post_addition(RobotDARTSimu* simu) override;\nvoid _post_removal(RobotDARTSimu* simu) override;\n};\n} // namespace robots\n} // namespace robot_dart\n#endif\n
"},{"location":"api/ur3e_8cpp/","title":"File ur3e.cpp","text":"

FileList > robot_dart > robots > ur3e.cpp

Go to the source code of this file

"},{"location":"api/ur3e_8cpp/#namespaces","title":"Namespaces","text":"Type Name namespace robot_dart namespace robots

The documentation for this class was generated from the following file robot_dart/robots/ur3e.cpp

"},{"location":"api/ur3e_8cpp_source/","title":"File ur3e.cpp","text":"

File List > robot_dart > robots > ur3e.cpp

Go to the documentation of this file

#include \"robot_dart/robots/ur3e.hpp\"\n#include \"robot_dart/robot_dart_simu.hpp\"\nnamespace robot_dart {\nnamespace robots {\nUr3e::Ur3e(size_t frequency, const std::string& urdf, const std::vector<std::pair<std::string, std::string>>& packages)\n: Robot(urdf, packages),\n_ft_wrist(std::make_shared<sensor::ForceTorque>(joint(\"wrist_3-flange\"), frequency))\n{\nfix_to_world();\nset_position_enforced(true);\nset_color_mode(\"material\");\n}\nvoid Ur3e::_post_addition(RobotDARTSimu* simu)\n{\n// We do not want to add sensors if we are a ghost robot\nif (ghost())\nreturn;\nsimu->add_sensor(_ft_wrist);\n}\nvoid Ur3e::_post_removal(RobotDARTSimu* simu)\n{\nsimu->remove_sensor(_ft_wrist);\n}\n} // namespace robots\n} // namespace robot_dart\n
"},{"location":"api/ur3e_8hpp/","title":"File ur3e.hpp","text":"

FileList > robot_dart > robots > ur3e.hpp

Go to the source code of this file

"},{"location":"api/ur3e_8hpp/#namespaces","title":"Namespaces","text":"Type Name namespace robot_dart namespace robots"},{"location":"api/ur3e_8hpp/#classes","title":"Classes","text":"Type Name class Ur3e class Ur3eHand

The documentation for this class was generated from the following file robot_dart/robots/ur3e.hpp

"},{"location":"api/ur3e_8hpp_source/","title":"File ur3e.hpp","text":"

File List > robot_dart > robots > ur3e.hpp

Go to the documentation of this file

#ifndef ROBOT_DART_ROBOTS_UR3E_HPP\n#define ROBOT_DART_ROBOTS_UR3E_HPP\n#include \"robot_dart/robot.hpp\"\n#include \"robot_dart/sensor/force_torque.hpp\"\nnamespace robot_dart {\nnamespace robots {\nclass Ur3e : public Robot {\npublic:\nUr3e(size_t frequency = 1000, const std::string& urdf = \"ur3e/ur3e.urdf\", const std::vector<std::pair<std::string, std::string>>& packages = ('ur3e_description', 'ur3e/ur3e_description'));\nconst sensor::ForceTorque& ft_wrist() const { return *_ft_wrist; }\nprotected:\nstd::shared_ptr<sensor::ForceTorque> _ft_wrist;\nvoid _post_addition(RobotDARTSimu* simu) override;\nvoid _post_removal(RobotDARTSimu* simu) override;\n};\nclass Ur3eHand : public Ur3e {\npublic:\nUr3eHand(size_t frequency = 1000, const std::string& urdf = \"ur3e/ur3e_with_schunk_hand.urdf\", const std::vector<std::pair<std::string, std::string>>& packages = ('ur3e_description', 'ur3e/ur3e_description')) : Ur3e(frequency, urdf, packages) {}\n};\n} // namespace robots\n} // namespace robot_dart\n#endif\n
"},{"location":"api/vx300_8hpp/","title":"File vx300.hpp","text":"

FileList > robot_dart > robots > vx300.hpp

Go to the source code of this file

"},{"location":"api/vx300_8hpp/#namespaces","title":"Namespaces","text":"Type Name namespace robot_dart namespace robots"},{"location":"api/vx300_8hpp/#classes","title":"Classes","text":"Type Name class Vx300

The documentation for this class was generated from the following file robot_dart/robots/vx300.hpp

"},{"location":"api/vx300_8hpp_source/","title":"File vx300.hpp","text":"

File List > robot_dart > robots > vx300.hpp

Go to the documentation of this file

#ifndef ROBOT_DART_ROBOTS_VX300_HPP\n#define ROBOT_DART_ROBOTS_VX300_HPP\n#include \"robot_dart/robot.hpp\"\nnamespace robot_dart {\nnamespace robots {\nclass Vx300 : public Robot {\npublic:\nVx300(const std::string& urdf = \"vx300/vx300.urdf\", const std::vector<std::pair<std::string, std::string>>& packages = ('interbotix_xsarm_descriptions', 'vx300')) : Robot(urdf, packages)\n{\nfix_to_world();\nset_position_enforced(true);\nset_color_mode(\"aspect\");\n}\n};\n} // namespace robots\n} // namespace robot_dart\n#endif\n
"},{"location":"api/dir_d1adb19f0b40b70b30ee0daf1901679b/","title":"Dir robot_dart/sensor","text":"

FileList > robot_dart > sensor

"},{"location":"api/dir_d1adb19f0b40b70b30ee0daf1901679b/#files","title":"Files","text":"Type Name file force_torque.cpp file force_torque.hpp file imu.cpp file imu.hpp file sensor.cpp file sensor.hpp file torque.cpp file torque.hpp

The documentation for this class was generated from the following file robot_dart/sensor/

"},{"location":"api/force__torque_8cpp/","title":"File force_torque.cpp","text":"

FileList > robot_dart > sensor > force_torque.cpp

Go to the source code of this file

"},{"location":"api/force__torque_8cpp/#namespaces","title":"Namespaces","text":"Type Name namespace robot_dart namespace sensor

The documentation for this class was generated from the following file robot_dart/sensor/force_torque.cpp

"},{"location":"api/force__torque_8cpp_source/","title":"File force_torque.cpp","text":"

File List > robot_dart > sensor > force_torque.cpp

Go to the documentation of this file

#include \"force_torque.hpp\"\n#include <robot_dart/utils_headers_dart_dynamics.hpp>\nnamespace robot_dart {\nnamespace sensor {\nForceTorque::ForceTorque(dart::dynamics::Joint* joint, size_t frequency, const std::string& direction) : Sensor(frequency), _direction(direction)\n{\nattach_to_joint(joint, Eigen::Isometry3d::Identity());\n}\nvoid ForceTorque::init()\n{\n_wrench.setZero();\nattach_to_joint(_joint_attached, Eigen::Isometry3d::Identity());\n_active = true;\n}\nvoid ForceTorque::calculate(double)\n{\nif (!_attached_to_joint)\nreturn; // cannot compute anything if not attached to a joint\nEigen::Vector6d wrench = Eigen::Vector6d::Zero();\nauto child_body = _joint_attached->getChildBodyNode();\nROBOT_DART_ASSERT(child_body != nullptr, \"Child BodyNode is nullptr\", );\nwrench = -dart::math::dAdT(_joint_attached->getTransformFromChildBodyNode(), child_body->getBodyForce());\n// We always compute things in SENSOR frame (aka joint frame)\nif (_direction == \"parent_to_child\") {\n_wrench = wrench;\n}\nelse // \"child_to_parent\" (default)\n{\n_wrench = -wrench;\n}\n}\nstd::string ForceTorque::type() const { return \"ft\"; }\nEigen::Vector3d ForceTorque::force() const\n{\nreturn _wrench.tail(3);\n}\nEigen::Vector3d ForceTorque::torque() const\n{\nreturn _wrench.head(3);\n}\nconst Eigen::Vector6d& ForceTorque::wrench() const\n{\nreturn _wrench;\n}\n} // namespace sensor\n} // namespace robot_dart\n
"},{"location":"api/force__torque_8hpp/","title":"File force_torque.hpp","text":"

FileList > robot_dart > sensor > force_torque.hpp

Go to the source code of this file

"},{"location":"api/force__torque_8hpp/#namespaces","title":"Namespaces","text":"Type Name namespace robot_dart namespace sensor"},{"location":"api/force__torque_8hpp/#classes","title":"Classes","text":"Type Name class ForceTorque

The documentation for this class was generated from the following file robot_dart/sensor/force_torque.hpp

"},{"location":"api/force__torque_8hpp_source/","title":"File force_torque.hpp","text":"

File List > robot_dart > sensor > force_torque.hpp

Go to the documentation of this file

#ifndef ROBOT_DART_SENSOR_FORCE_TORQUE_HPP\n#define ROBOT_DART_SENSOR_FORCE_TORQUE_HPP\n#include <robot_dart/sensor/sensor.hpp>\nnamespace robot_dart {\nnamespace sensor {\nclass ForceTorque : public Sensor {\npublic:\nForceTorque(dart::dynamics::Joint* joint, size_t frequency = 1000, const std::string& direction = \"child_to_parent\");\nForceTorque(const std::shared_ptr<Robot>& robot, const std::string& joint_name, size_t frequency = 1000, const std::string& direction = \"child_to_parent\") : ForceTorque(robot->joint(joint_name), frequency, direction) {}\nvoid init() override;\nvoid calculate(double) override;\nstd::string type() const override;\nEigen::Vector3d force() const;\nEigen::Vector3d torque() const;\nconst Eigen::Vector6d& wrench() const;\nvoid attach_to_body(dart::dynamics::BodyNode*, const Eigen::Isometry3d&) override\n{\nROBOT_DART_WARNING(true, \"You cannot attach a force/torque sensor to a body!\");\n}\nprotected:\nstd::string _direction;\nEigen::Vector6d _wrench;\n};\n} // namespace sensor\n} // namespace robot_dart\n#endif\n
"},{"location":"api/imu_8cpp/","title":"File imu.cpp","text":"

FileList > robot_dart > sensor > imu.cpp

Go to the source code of this file

"},{"location":"api/imu_8cpp/#namespaces","title":"Namespaces","text":"Type Name namespace robot_dart namespace sensor

The documentation for this class was generated from the following file robot_dart/sensor/imu.cpp

"},{"location":"api/imu_8cpp_source/","title":"File imu.cpp","text":"

File List > robot_dart > sensor > imu.cpp

Go to the documentation of this file

#include \"imu.hpp\"\n#include <robot_dart/robot_dart_simu.hpp>\n#include <robot_dart/utils_headers_dart_dynamics.hpp>\nnamespace robot_dart {\nnamespace sensor {\nIMU::IMU(const IMUConfig& config) : Sensor(config.frequency), _config(config) {}\nvoid IMU::init()\n{\n_angular_vel.setZero();\n_linear_accel.setZero();\nattach_to_body(_config.body, Eigen::Isometry3d::Identity());\nif (_simu)\n_active = true;\n}\nvoid IMU::calculate(double)\n{\nif (!_attached_to_body)\nreturn; // cannot compute anything if not attached to a link\nROBOT_DART_EXCEPTION_ASSERT(_simu, \"Simulation pointer is null!\");\nEigen::Vector3d tmp = dart::math::logMap(_body_attached->getTransform(dart::dynamics::Frame::World(), _body_attached).linear().matrix());\n_angular_pos = Eigen::AngleAxisd(tmp.norm(), tmp.normalized());\n_angular_vel = _body_attached->getSpatialVelocity().head(3); // angular velocity with respect to the world, in local coordinates\n_linear_accel = _body_attached->getSpatialAcceleration().tail(3); // linear acceleration with respect to the world, in local coordinates\n// add biases\n_angular_vel += _config.gyro_bias;\n_linear_accel += _config.accel_bias;\n// add gravity to acceleration\n_linear_accel -= _world_pose.linear().transpose() * _simu->gravity();\n}\nstd::string IMU::type() const { return \"imu\"; }\nconst Eigen::AngleAxisd& IMU::angular_position() const\n{\nreturn _angular_pos;\n}\nEigen::Vector3d IMU::angular_position_vec() const\n{\nreturn _angular_pos.angle() * _angular_pos.axis();\n}\nconst Eigen::Vector3d& IMU::angular_velocity() const\n{\nreturn _angular_vel;\n}\nconst Eigen::Vector3d& IMU::linear_acceleration() const\n{\nreturn _linear_accel;\n}\n} // namespace sensor\n} // namespace robot_dart\n
"},{"location":"api/imu_8hpp/","title":"File imu.hpp","text":"

FileList > robot_dart > sensor > imu.hpp

Go to the source code of this file

"},{"location":"api/imu_8hpp/#namespaces","title":"Namespaces","text":"Type Name namespace robot_dart namespace sensor"},{"location":"api/imu_8hpp/#classes","title":"Classes","text":"Type Name class IMU struct IMUConfig

The documentation for this class was generated from the following file robot_dart/sensor/imu.hpp

"},{"location":"api/imu_8hpp_source/","title":"File imu.hpp","text":"

File List > robot_dart > sensor > imu.hpp

Go to the documentation of this file

#ifndef ROBOT_DART_SENSOR_IMU_HPP\n#define ROBOT_DART_SENSOR_IMU_HPP\n#include <robot_dart/sensor/sensor.hpp>\nnamespace robot_dart {\nnamespace sensor {\n// TO-DO: Implement some noise models (e.g., https://github.com/ethz-asl/kalibr/wiki/IMU-Noise-Model)\nstruct IMUConfig {\nIMUConfig(dart::dynamics::BodyNode* b, size_t f) : gyro_bias(Eigen::Vector3d::Zero()), accel_bias(Eigen::Vector3d::Zero()), body(b), frequency(f){};\nIMUConfig(const Eigen::Vector3d& gyro_bias, const Eigen::Vector3d& accel_bias, dart::dynamics::BodyNode* b, size_t f) : gyro_bias(gyro_bias), accel_bias(accel_bias), body(b), frequency(f){};\nIMUConfig() : gyro_bias(Eigen::Vector3d::Zero()), accel_bias(Eigen::Vector3d::Zero()), body(nullptr), frequency(200) {}\n// We assume fixed bias; TO-DO: Make this time-dependent\nEigen::Vector3d gyro_bias = Eigen::Vector3d::Zero();\nEigen::Vector3d accel_bias = Eigen::Vector3d::Zero();\n// // We assume white Gaussian noise // TO-DO: Implement this\n// Eigen::Vector3d _gyro_std = Eigen::Vector3d::Zero();\n// Eigen::Vector3d _accel_std = Eigen::Vector3d::Zero();\n// BodyNode/Link attached to\ndart::dynamics::BodyNode* body = nullptr;\n// Eigen::Isometry3d _tf = Eigen::Isometry3d::Identity();\n// Frequency\nsize_t frequency = 200;\n};\nclass IMU : public Sensor {\npublic:\nIMU(const IMUConfig& config);\nvoid init() override;\nvoid calculate(double) override;\nstd::string type() const override;\nconst Eigen::AngleAxisd& angular_position() const;\nEigen::Vector3d angular_position_vec() const;\nconst Eigen::Vector3d& angular_velocity() const;\nconst Eigen::Vector3d& linear_acceleration() const;\nvoid attach_to_joint(dart::dynamics::Joint*, const Eigen::Isometry3d&) override\n{\nROBOT_DART_WARNING(true, \"You cannot attach an IMU sensor to a joint!\");\n}\nprotected:\n// double _prev_time = 0.;\nIMUConfig _config;\nEigen::AngleAxisd _angular_pos; // TO-DO: Check how to do this as close as possible to real sensors\nEigen::Vector3d _angular_vel;\nEigen::Vector3d _linear_accel;\n};\n} // namespace sensor\n} // namespace robot_dart\n#endif\n
"},{"location":"api/sensor_8cpp/","title":"File sensor.cpp","text":"

FileList > robot_dart > sensor > sensor.cpp

Go to the source code of this file

"},{"location":"api/sensor_8cpp/#namespaces","title":"Namespaces","text":"Type Name namespace robot_dart namespace sensor

The documentation for this class was generated from the following file robot_dart/sensor/sensor.cpp

"},{"location":"api/sensor_8cpp_source/","title":"File sensor.cpp","text":"

File List > robot_dart > sensor > sensor.cpp

Go to the documentation of this file

#include \"sensor.hpp\"\n#include \"robot_dart/robot_dart_simu.hpp\"\n#include \"robot_dart/utils.hpp\"\n#include \"robot_dart/utils_headers_dart_dynamics.hpp\"\nnamespace robot_dart {\nnamespace sensor {\nSensor::Sensor(size_t freq) : _active(false), _frequency(freq), _world_pose(Eigen::Isometry3d::Identity()), _attaching_to_body(false), _attached_to_body(false), _attaching_to_joint(false), _attached_to_joint(false) {}\nvoid Sensor::activate(bool enable)\n{\n_active = false;\nif (enable) {\ninit();\n}\n}\nbool Sensor::active() const\n{\nreturn _active;\n}\nvoid Sensor::set_simu(RobotDARTSimu* simu)\n{\nROBOT_DART_EXCEPTION_ASSERT(simu, \"Simulation pointer is null!\");\n_simu = simu;\nbool check = static_cast<int>(_frequency) > simu->physics_freq();\nROBOT_DART_WARNING(check, \"Sensor frequency is bigger than simulation physics. Setting it to simulation rate!\");\nif (check)\n_frequency = simu->physics_freq();\n}\nconst RobotDARTSimu* Sensor::simu() const\n{\nreturn _simu;\n}\nsize_t Sensor::frequency() const { return _frequency; }\nvoid Sensor::set_frequency(size_t freq) { _frequency = freq; }\nvoid Sensor::set_pose(const Eigen::Isometry3d& tf) { _world_pose = tf; }\nconst Eigen::Isometry3d& Sensor::pose() const { return _world_pose; }\nvoid Sensor::detach()\n{\n_attached_to_body = false;\n_attached_to_joint = false;\n_body_attached = nullptr;\n_joint_attached = nullptr;\n_active = false;\n}\nvoid Sensor::refresh(double t)\n{\nif (!_active)\nreturn;\nif (_attaching_to_body && !_attached_to_body) {\nattach_to_body(_body_attached, _attached_tf);\n}\nelse if (_attaching_to_joint && !_attached_to_joint) {\nattach_to_joint(_joint_attached, _attached_tf);\n}\nif (_attached_to_body && _body_attached) {\n_world_pose = _body_attached->getWorldTransform() * _attached_tf;\n}\nelse if (_attached_to_joint && _joint_attached) {\ndart::dynamics::BodyNode* body = nullptr;\nEigen::Isometry3d tf = Eigen::Isometry3d::Identity();\nif (_joint_attached->getParentBodyNode()) {\nbody = _joint_attached->getParentBodyNode();\ntf = _joint_attached->getTransformFromParentBodyNode();\n}\nelse if (_joint_attached->getChildBodyNode()) {\nbody = _joint_attached->getChildBodyNode();\ntf = _joint_attached->getTransformFromChildBodyNode();\n}\nif (body)\n_world_pose = body->getWorldTransform() * tf * _attached_tf;\n}\ncalculate(t);\n}\nvoid Sensor::attach_to_body(dart::dynamics::BodyNode* body, const Eigen::Isometry3d& tf)\n{\n_body_attached = body;\n_attached_tf = tf;\nif (_body_attached) {\n_attaching_to_body = false;\n_attached_to_body = true;\n_attaching_to_joint = false;\n_attached_to_joint = false;\n_joint_attached = nullptr;\n}\nelse { // we cannot keep attaching to a null BodyNode\n_attaching_to_body = false;\n_attached_to_body = false;\n}\n}\nvoid Sensor::attach_to_joint(dart::dynamics::Joint* joint, const Eigen::Isometry3d& tf)\n{\n_joint_attached = joint;\n_attached_tf = tf;\nif (_joint_attached) {\n_attaching_to_joint = false;\n_attached_to_joint = true;\n_attaching_to_body = false;\n_attached_to_body = false;\n}\nelse { // we cannot keep attaching to a null Joint\n_attaching_to_joint = false;\n_attached_to_joint = false;\n}\n}\nconst std::string& Sensor::attached_to() const\n{\nROBOT_DART_EXCEPTION_ASSERT(_attached_to_body || _attached_to_joint, \"Joint is not attached to anything\");\nif (_attached_to_body)\nreturn _body_attached->getName();\n// attached to joint\nreturn _joint_attached->getName();\n}\n} // namespace sensor\n} // namespace robot_dart\n
"},{"location":"api/sensor_8hpp/","title":"File sensor.hpp","text":"

FileList > robot_dart > sensor > sensor.hpp

Go to the source code of this file

"},{"location":"api/sensor_8hpp/#namespaces","title":"Namespaces","text":"Type Name namespace dart namespace dynamics namespace robot_dart namespace sensor"},{"location":"api/sensor_8hpp/#classes","title":"Classes","text":"Type Name class Sensor

The documentation for this class was generated from the following file robot_dart/sensor/sensor.hpp

"},{"location":"api/sensor_8hpp_source/","title":"File sensor.hpp","text":"

File List > robot_dart > sensor > sensor.hpp

Go to the documentation of this file

#ifndef ROBOT_DART_SENSOR_SENSOR_HPP\n#define ROBOT_DART_SENSOR_SENSOR_HPP\n#include <robot_dart/robot.hpp>\n#include <robot_dart/utils.hpp>\n#include <memory>\n#include <vector>\nnamespace dart {\nnamespace dynamics {\nclass BodyNode;\nclass Joint;\n} // namespace dynamics\n} // namespace dart\nnamespace robot_dart {\nclass RobotDARTSimu;\nnamespace sensor {\nclass Sensor {\npublic:\nSensor(size_t freq = 40);\nvirtual ~Sensor() {}\nvoid activate(bool enable = true);\nbool active() const;\nvoid set_simu(RobotDARTSimu* simu);\nconst RobotDARTSimu* simu() const;\nsize_t frequency() const;\nvoid set_frequency(size_t freq);\nvoid set_pose(const Eigen::Isometry3d& tf);\nconst Eigen::Isometry3d& pose() const;\nvoid refresh(double t);\nvirtual void init() = 0;\n// TO-DO: Maybe make this const?\nvirtual void calculate(double) = 0;\nvirtual std::string type() const = 0;\nvirtual void attach_to_body(dart::dynamics::BodyNode* body, const Eigen::Isometry3d& tf = Eigen::Isometry3d::Identity());\nvoid attach_to_body(const std::shared_ptr<Robot>& robot, const std::string& body_name, const Eigen::Isometry3d& tf = Eigen::Isometry3d::Identity()) { attach_to_body(robot->body_node(body_name), tf); }\nvirtual void attach_to_joint(dart::dynamics::Joint* joint, const Eigen::Isometry3d& tf = Eigen::Isometry3d::Identity());\nvoid attach_to_joint(const std::shared_ptr<Robot>& robot, const std::string& joint_name, const Eigen::Isometry3d& tf = Eigen::Isometry3d::Identity()) { attach_to_joint(robot->joint(joint_name), tf); }\nvoid detach();\nconst std::string& attached_to() const;\nprotected:\nRobotDARTSimu* _simu = nullptr;\nbool _active;\nsize_t _frequency;\nEigen::Isometry3d _world_pose;\nbool _attaching_to_body = false, _attached_to_body = false;\nbool _attaching_to_joint = false, _attached_to_joint = false;\nEigen::Isometry3d _attached_tf;\ndart::dynamics::BodyNode* _body_attached;\ndart::dynamics::Joint* _joint_attached;\n};\n} // namespace sensor\n} // namespace robot_dart\n#endif\n
"},{"location":"api/torque_8cpp/","title":"File torque.cpp","text":"

FileList > robot_dart > sensor > torque.cpp

Go to the source code of this file

"},{"location":"api/torque_8cpp/#namespaces","title":"Namespaces","text":"Type Name namespace robot_dart namespace sensor

The documentation for this class was generated from the following file robot_dart/sensor/torque.cpp

"},{"location":"api/torque_8cpp_source/","title":"File torque.cpp","text":"

File List > robot_dart > sensor > torque.cpp

Go to the documentation of this file

#include \"torque.hpp\"\n#include <robot_dart/robot_dart_simu.hpp>\n#include <robot_dart/utils_headers_dart_dynamics.hpp>\nnamespace robot_dart {\nnamespace sensor {\nTorque::Torque(dart::dynamics::Joint* joint, size_t frequency) : Sensor(frequency), _torques(joint->getNumDofs())\n{\nattach_to_joint(joint, Eigen::Isometry3d::Identity());\n}\nvoid Torque::init()\n{\n_torques.setZero();\nattach_to_joint(_joint_attached, Eigen::Isometry3d::Identity());\n_active = true;\n}\nvoid Torque::calculate(double)\n{\nif (!_attached_to_joint)\nreturn; // cannot compute anything if not attached to a joint\nEigen::Vector6d wrench = Eigen::Vector6d::Zero();\nauto child_body = _joint_attached->getChildBodyNode();\nROBOT_DART_ASSERT(child_body != nullptr, \"Child BodyNode is nullptr\", );\nwrench = child_body->getBodyForce();\n// get forces for only the only degrees of freedom in this joint\n_torques = _joint_attached->getRelativeJacobian().transpose() * wrench;\n}\nstd::string Torque::type() const { return \"t\"; }\nconst Eigen::VectorXd& Torque::torques() const\n{\nreturn _torques;\n}\n} // namespace sensor\n} // namespace robot_dart\n
"},{"location":"api/torque_8hpp/","title":"File torque.hpp","text":"

FileList > robot_dart > sensor > torque.hpp

Go to the source code of this file

"},{"location":"api/torque_8hpp/#namespaces","title":"Namespaces","text":"Type Name namespace robot_dart namespace sensor"},{"location":"api/torque_8hpp/#classes","title":"Classes","text":"Type Name class Torque

The documentation for this class was generated from the following file robot_dart/sensor/torque.hpp

"},{"location":"api/torque_8hpp_source/","title":"File torque.hpp","text":"

File List > robot_dart > sensor > torque.hpp

Go to the documentation of this file

#ifndef ROBOT_DART_SENSOR_TORQUE_HPP\n#define ROBOT_DART_SENSOR_TORQUE_HPP\n#include <robot_dart/sensor/sensor.hpp>\nnamespace robot_dart {\nnamespace sensor {\nclass Torque : public Sensor {\npublic:\nTorque(dart::dynamics::Joint* joint, size_t frequency = 1000);\nTorque(const std::shared_ptr<Robot>& robot, const std::string& joint_name, size_t frequency = 1000) : Torque(robot->joint(joint_name), frequency) {}\nvoid init() override;\nvoid calculate(double) override;\nstd::string type() const override;\nconst Eigen::VectorXd& torques() const;\nvoid attach_to_body(dart::dynamics::BodyNode*, const Eigen::Isometry3d&) override\n{\nROBOT_DART_WARNING(true, \"You cannot attach a torque sensor to a body!\");\n}\nprotected:\nEigen::VectorXd _torques;\n};\n} // namespace sensor\n} // namespace robot_dart\n#endif\n
"},{"location":"api/robot__dart__simu_8cpp/","title":"File robot_dart_simu.cpp","text":"

FileList > robot_dart > robot_dart_simu.cpp

Go to the source code of this file

"},{"location":"api/robot__dart__simu_8cpp/#namespaces","title":"Namespaces","text":"Type Name namespace robot_dart namespace collision_filter"},{"location":"api/robot__dart__simu_8cpp/#classes","title":"Classes","text":"Type Name class BitmaskContactFilter struct Masks

The documentation for this class was generated from the following file robot_dart/robot_dart_simu.cpp

"},{"location":"api/robot__dart__simu_8cpp_source/","title":"File robot_dart_simu.cpp","text":"

File List > robot_dart > robot_dart_simu.cpp

Go to the documentation of this file

#include \"robot_dart_simu.hpp\"\n#include \"gui_data.hpp\"\n#include \"utils.hpp\"\n#include \"utils_headers_dart_collision.hpp\"\n#include \"utils_headers_dart_dynamics.hpp\"\n#include <sstream>\nnamespace robot_dart {\nnamespace collision_filter {\n// This is inspired from Swift: https://developer.apple.com/documentation/spritekit/skphysicsbody#//apple_ref/occ/instp/SKPhysicsBody/collisionBitMask\n// https://stackoverflow.com/questions/39063949/cant-understand-how-collision-bit-mask-works\nclass BitmaskContactFilter : public dart::collision::BodyNodeCollisionFilter {\npublic:\nusing DartCollisionConstPtr = const dart::collision::CollisionObject*;\nusing DartShapeConstPtr = const dart::dynamics::ShapeNode*;\nstruct Masks {\nuint32_t collision_mask = 0xffffffff;\nuint32_t category_mask = 0xffffffff;\n};\nvirtual ~BitmaskContactFilter() = default;\n// This function follows DART's coding style as it needs to override a function\nbool ignoresCollision(DartCollisionConstPtr object1, DartCollisionConstPtr object2) const override\n{\nauto shape_node1 = object1->getShapeFrame()->asShapeNode();\nauto shape_node2 = object2->getShapeFrame()->asShapeNode();\nif (dart::collision::BodyNodeCollisionFilter::ignoresCollision(object1, object2))\nreturn true;\nauto shape1_iter = _bitmask_map.find(shape_node1);\nauto shape2_iter = _bitmask_map.find(shape_node2);\nif (shape1_iter != _bitmask_map.end() && shape2_iter != _bitmask_map.end()) {\nauto col_mask1 = shape1_iter->second.collision_mask;\nauto cat_mask1 = shape1_iter->second.category_mask;\nauto col_mask2 = shape2_iter->second.collision_mask;\nauto cat_mask2 = shape2_iter->second.category_mask;\nif ((col_mask1 & cat_mask2) == 0 && (col_mask2 & cat_mask1) == 0)\nreturn true;\n}\nreturn false;\n}\nvoid add_to_map(DartShapeConstPtr shape, uint32_t col_mask, uint32_t cat_mask)\n{\n_bitmask_map[shape] = {col_mask, cat_mask};\n}\nvoid add_to_map(dart::dynamics::SkeletonPtr skel, uint32_t col_mask, uint32_t cat_mask)\n{\nfor (std::size_t i = 0; i < skel->getNumShapeNodes(); ++i) {\nauto shape = skel->getShapeNode(i);\nthis->add_to_map(shape, col_mask, cat_mask);\n}\n}\nvoid remove_from_map(DartShapeConstPtr shape)\n{\nauto shape_iter = _bitmask_map.find(shape);\nif (shape_iter != _bitmask_map.end())\n_bitmask_map.erase(shape_iter);\n}\nvoid remove_from_map(dart::dynamics::SkeletonPtr skel)\n{\nfor (std::size_t i = 0; i < skel->getNumShapeNodes(); ++i) {\nauto shape = skel->getShapeNode(i);\nthis->remove_from_map(shape);\n}\n}\nvoid clear_all() { _bitmask_map.clear(); }\nMasks mask(DartShapeConstPtr shape) const\n{\nauto shape_iter = _bitmask_map.find(shape);\nif (shape_iter != _bitmask_map.end())\nreturn shape_iter->second;\nreturn {0xffffffff, 0xffffffff};\n}\nprivate:\n// We need ShapeNodes and not BodyNodes, since in DART collision checking is performed in ShapeNode-level\n// in RobotDARTSimu, we only allow setting one mask per BodyNode; maybe we can improve the performance of this slightly\nstd::unordered_map<DartShapeConstPtr, Masks> _bitmask_map;\n};\n} // namespace collision_filter\nRobotDARTSimu::RobotDARTSimu(double timestep) : _world(std::make_shared<dart::simulation::World>()),\n_old_index(0),\n_break(false),\n_scheduler(timestep),\n_physics_freq(std::round(1. / timestep)),\n_control_freq(_physics_freq)\n{\n_world->getConstraintSolver()->setCollisionDetector(dart::collision::DARTCollisionDetector::create());\n_world->getConstraintSolver()->getCollisionOption().collisionFilter = std::make_shared<collision_filter::BitmaskContactFilter>();\n_world->setTimeStep(timestep);\n_world->setTime(0.0);\n_graphics = std::make_shared<gui::Base>();\n_gui_data.reset(new simu::GUIData());\n}\nRobotDARTSimu::~RobotDARTSimu()\n{\n_robots.clear();\n_sensors.clear();\n}\nvoid RobotDARTSimu::run(double max_duration, bool reset_commands, bool force_position_bounds)\n{\n_break = false;\ndouble old_time = _world->getTime();\ndouble factor = _world->getTimeStep() / 2.;\nwhile ((_world->getTime() - old_time - max_duration) < -factor) {\nif (step(reset_commands, force_position_bounds))\nbreak;\n}\n}\nbool RobotDARTSimu::step_world(bool reset_commands, bool force_position_bounds)\n{\nif (_scheduler(_physics_freq)) {\n_world->step(reset_commands);\nif (force_position_bounds)\nfor (auto& r : _robots)\nr->force_position_bounds();\n}\n// Update graphics\nif (_scheduler(_graphics_freq)) {\n// Update default texts\nif (_text_panel) { // Need to re-transform as the size of the window might have changed\nEigen::Affine2d tf = Eigen::Affine2d::Identity();\ntf.translate(Eigen::Vector2d(-static_cast<double>(_graphics->width()) / 2., _graphics->height() / 2.));\n_text_panel->transformation = tf;\n}\nif (_status_bar) {\n_status_bar->text = status_bar_text(); // this is dynamic text (timings)\nEigen::Affine2d tf = Eigen::Affine2d::Identity();\ntf.translate(Eigen::Vector2d(-static_cast<double>(_graphics->width()) / 2., -static_cast<double>(_graphics->height() / 2.)));\n_status_bar->transformation = tf;\n}\n// Update robot-specific GUI data\nfor (auto& robot : _robots) {\n_gui_data->update_robot(robot);\n}\n_graphics->refresh();\n}\n// update sensors\nfor (auto& sensor : _sensors) {\nif (sensor->active() && _scheduler(sensor->frequency())) {\nsensor->refresh(_world->getTime());\n}\n}\n_old_index++;\n_scheduler.step();\nreturn _break || _graphics->done();\n}\nbool RobotDARTSimu::step(bool reset_commands, bool force_position_bounds)\n{\nif (_scheduler(_control_freq)) {\nfor (auto& robot : _robots) {\nrobot->update(_world->getTime());\n}\n}\nreturn step_world(reset_commands, force_position_bounds);\n}\nstd::shared_ptr<gui::Base> RobotDARTSimu::graphics() const\n{\nreturn _graphics;\n}\nvoid RobotDARTSimu::set_graphics(const std::shared_ptr<gui::Base>& graphics)\n{\n_graphics = graphics;\n_graphics->set_simu(this);\n_graphics->set_fps(_graphics_freq);\n}\ndart::simulation::WorldPtr RobotDARTSimu::world()\n{\nreturn _world;\n}\nvoid RobotDARTSimu::add_sensor(const std::shared_ptr<sensor::Sensor>& sensor)\n{\n_sensors.push_back(sensor);\nsensor->set_simu(this);\nsensor->init();\n}\nstd::vector<std::shared_ptr<sensor::Sensor>> RobotDARTSimu::sensors() const\n{\nreturn _sensors;\n}\nstd::shared_ptr<sensor::Sensor> RobotDARTSimu::sensor(size_t index) const\n{\nROBOT_DART_ASSERT(index < _sensors.size(), \"Sensor index out of bounds\", nullptr);\nreturn _sensors[index];\n}\nvoid RobotDARTSimu::remove_sensor(const std::shared_ptr<sensor::Sensor>& sensor)\n{\nauto it = std::find(_sensors.begin(), _sensors.end(), sensor);\nif (it != _sensors.end()) {\n_sensors.erase(it);\n}\n}\nvoid RobotDARTSimu::remove_sensor(size_t index)\n{\nROBOT_DART_ASSERT(index < _sensors.size(), \"Sensor index out of bounds\", );\n_sensors.erase(_sensors.begin() + index);\n}\nvoid RobotDARTSimu::remove_sensors(const std::string& type)\n{\nfor (int i = 0; i < static_cast<int>(_sensors.size()); i++) {\nauto& sensor = _sensors[i];\nif (sensor->type() == type) {\n_sensors.erase(_sensors.begin() + i);\ni--;\n}\n}\n}\nvoid RobotDARTSimu::clear_sensors()\n{\n_sensors.clear();\n}\ndouble RobotDARTSimu::timestep() const\n{\nreturn _world->getTimeStep();\n}\nvoid RobotDARTSimu::set_timestep(double timestep, bool update_control_freq)\n{\n_world->setTimeStep(timestep);\n_physics_freq = std::round(1. / timestep);\nif (update_control_freq)\n_control_freq = _physics_freq;\n_scheduler.reset(timestep, _scheduler.sync(), _scheduler.current_time(), _scheduler.real_time());\n}\nEigen::Vector3d RobotDARTSimu::gravity() const\n{\nreturn _world->getGravity();\n}\nvoid RobotDARTSimu::set_gravity(const Eigen::Vector3d& gravity)\n{\n_world->setGravity(gravity);\n}\nvoid RobotDARTSimu::stop_sim(bool disable)\n{\n_break = disable;\n}\nbool RobotDARTSimu::halted_sim() const\n{\nreturn _break;\n}\nsize_t RobotDARTSimu::num_robots() const\n{\nreturn _robots.size();\n}\nconst std::vector<std::shared_ptr<Robot>>& RobotDARTSimu::robots() const\n{\nreturn _robots;\n}\nstd::shared_ptr<Robot> RobotDARTSimu::robot(size_t index) const\n{\nROBOT_DART_ASSERT(index < _robots.size(), \"Robot index out of bounds\", nullptr);\nreturn _robots[index];\n}\nint RobotDARTSimu::robot_index(const std::shared_ptr<Robot>& robot) const\n{\nauto it = std::find(_robots.begin(), _robots.end(), robot);\nROBOT_DART_ASSERT(it != _robots.end(), \"Robot index out of bounds\", -1);\nreturn std::distance(_robots.begin(), it);\n}\nvoid RobotDARTSimu::add_robot(const std::shared_ptr<Robot>& robot)\n{\nif (robot->skeleton()) {\n_robots.push_back(robot);\n_world->addSkeleton(robot->skeleton());\nrobot->_post_addition(this);\n_gui_data->update_robot(robot);\n}\n}\nvoid RobotDARTSimu::add_visual_robot(const std::shared_ptr<Robot>& robot)\n{\nif (robot->skeleton()) {\n// make robot a pure visual one -- assuming that the color is already set\n// visual robots do not do physics updates\nrobot->skeleton()->setMobile(false);\nfor (auto& bd : robot->skeleton()->getBodyNodes()) {\n// visual robots do not have collisions\nauto& collision_shapes = bd->getShapeNodesWith<dart::dynamics::CollisionAspect>();\nfor (auto& shape : collision_shapes) {\nshape->removeAspect<dart::dynamics::CollisionAspect>();\n}\n}\n// visual robots, by default, use the color from the VisualAspect\nrobot->set_color_mode(\"aspect\");\n// visual robots do not cast shadows\nrobot->set_cast_shadows(false);\n// set the ghost/visual flag\nrobot->set_ghost(true);\nrobot->_post_addition(this);\n_robots.push_back(robot);\n_world->addSkeleton(robot->skeleton());\n_gui_data->update_robot(robot);\n}\n}\nvoid RobotDARTSimu::remove_robot(const std::shared_ptr<Robot>& robot)\n{\nauto it = std::find(_robots.begin(), _robots.end(), robot);\nif (it != _robots.end()) {\nrobot->_post_removal(this);\n_gui_data->remove_robot(robot);\n_world->removeSkeleton(robot->skeleton());\n_robots.erase(it);\n}\n}\nvoid RobotDARTSimu::remove_robot(size_t index)\n{\nROBOT_DART_ASSERT(index < _robots.size(), \"Robot index out of bounds\", );\n_robots[index]->_post_removal(this);\n_gui_data->remove_robot(_robots[index]);\n_world->removeSkeleton(_robots[index]->skeleton());\n_robots.erase(_robots.begin() + index);\n}\nvoid RobotDARTSimu::clear_robots()\n{\nfor (auto& robot : _robots) {\nrobot->_post_removal(this);\n_gui_data->remove_robot(robot);\n_world->removeSkeleton(robot->skeleton());\n}\n_robots.clear();\n}\nsimu::GUIData* RobotDARTSimu::gui_data() { return &(*_gui_data); }\nvoid RobotDARTSimu::enable_text_panel(bool enable, double font_size) { _enable(_text_panel, enable, font_size); }\nvoid RobotDARTSimu::enable_status_bar(bool enable, double font_size)\n{\n_enable(_status_bar, enable, font_size);\nif (enable) {\n_status_bar->alignment = (1 | 1 << 3); // alignment of status bar should be LineLeft\n_status_bar->draw_background = true; // we want to draw a background\n_status_bar->background_color = Eigen::Vector4d(0, 0, 0, 0.75); // black-transparent bar\n}\n}\nvoid RobotDARTSimu::_enable(std::shared_ptr<simu::TextData>& text, bool enable, double font_size)\n{\nif (!text && enable) {\ntext = _gui_data->add_text(\"\");\n}\nelse if (!enable) {\nif (text)\n_gui_data->remove_text(text);\ntext = nullptr;\n}\nif (text && font_size > 0)\ntext->font_size = font_size;\n}\nvoid RobotDARTSimu::set_text_panel(const std::string& str)\n{\nROBOT_DART_ASSERT(_text_panel, \"Panel text object not created. Use enable_text_panel() to create it.\", );\n_text_panel->text = str;\n}\nstd::string RobotDARTSimu::text_panel_text() const\n{\nROBOT_DART_ASSERT(_text_panel, \"Panel text object not created. Returning empty string.\", \"\");\nreturn _text_panel->text;\n}\nstd::string RobotDARTSimu::status_bar_text() const\n{\nstd::ostringstream out;\nout.precision(3);\ndouble rt = _scheduler.real_time();\nout << std::fixed << \"[simulation time: \" << _world->getTime()\n<< \"s ] [\"\n<< \"wall time: \" << rt << \"s] [\";\nout.precision(1);\nout << _scheduler.real_time_factor() << \"x]\";\nout << \" [it: \" << _scheduler.it_duration() * 1e3 << \" ms]\";\nout << (_scheduler.sync() ? \" [sync]\" : \" [no-sync]\");\nreturn out.str();\n}\nstd::shared_ptr<simu::TextData> RobotDARTSimu::add_text(const std::string& text, const Eigen::Affine2d& tf, Eigen::Vector4d color, std::uint8_t alignment, bool draw_bg, Eigen::Vector4d bg_color, double font_size)\n{\nreturn _gui_data->add_text(text, tf, color, alignment, draw_bg, bg_color, font_size);\n}\nstd::shared_ptr<Robot> RobotDARTSimu::add_floor(double floor_width, double floor_height, const Eigen::Isometry3d& tf, const std::string& floor_name)\n{\nROBOT_DART_ASSERT((_world->getSkeleton(floor_name) == nullptr), \"We cannot have 2 floors with the name '\" + floor_name + \"'\", nullptr);\nROBOT_DART_ASSERT((floor_width > 0. && floor_height > 0.), \"Floor dimensions should be bigger than zero!\", nullptr);\ndart::dynamics::SkeletonPtr floor_skel = dart::dynamics::Skeleton::create(floor_name);\n// Give the floor a body\ndart::dynamics::BodyNodePtr body = floor_skel->createJointAndBodyNodePair<dart::dynamics::WeldJoint>(nullptr).second;\n// Give the body a shape\nauto box = std::make_shared<dart::dynamics::BoxShape>(Eigen::Vector3d(floor_width, floor_width, floor_height));\nauto box_node = body->createShapeNodeWith<dart::dynamics::VisualAspect, dart::dynamics::CollisionAspect, dart::dynamics::DynamicsAspect>(box);\nbox_node->getVisualAspect()->setColor(dart::Color::Gray());\n// Put the body into position\nEigen::Isometry3d new_tf = tf;\nnew_tf.translate(Eigen::Vector3d(0., 0., -floor_height / 2.0));\nbody->getParentJoint()->setTransformFromParentBodyNode(new_tf);\nauto floor_robot = std::make_shared<Robot>(floor_skel, floor_name);\nadd_robot(floor_robot);\nreturn floor_robot;\n}\nstd::shared_ptr<Robot> RobotDARTSimu::add_checkerboard_floor(double floor_width, double floor_height, double size, const Eigen::Isometry3d& tf, const std::string& floor_name, const Eigen::Vector4d& first_color, const Eigen::Vector4d& second_color)\n{\nROBOT_DART_ASSERT((_world->getSkeleton(floor_name) == nullptr), \"We cannot have 2 floors with the name '\" + floor_name + \"'\", nullptr);\nROBOT_DART_ASSERT((floor_width > 0. && floor_height > 0. && size > 0.), \"Floor dimensions should be bigger than zero!\", nullptr);\n// Add main floor skeleton\ndart::dynamics::SkeletonPtr main_floor_skel = dart::dynamics::Skeleton::create(floor_name + \"_main\");\n// Give the floor a body\ndart::dynamics::BodyNodePtr main_body = main_floor_skel->createJointAndBodyNodePair<dart::dynamics::WeldJoint>(nullptr).second;\n// Give the body a shape\nauto box = std::make_shared<dart::dynamics::BoxShape>(Eigen::Vector3d(floor_width, floor_width, floor_height));\n// No visual shape for this one; only collision and dynamics\nmain_body->createShapeNodeWith<dart::dynamics::CollisionAspect, dart::dynamics::DynamicsAspect>(box);\n// Put the body into position\nEigen::Isometry3d new_tf = tf;\nnew_tf.translate(Eigen::Vector3d(0., 0., -floor_height / 2.0));\nmain_body->getParentJoint()->setTransformFromParentBodyNode(new_tf);\n// Add visual bodies just for visualization\nint step = std::ceil(floor_width / size);\nint c = 0;\nfor (int i = 0; i < step; i++) {\nc = i;\nfor (int j = 0; j < step; j++) {\nEigen::Vector3d init_pose;\ninit_pose << -floor_width / 2. + size / 2 + i * size, -floor_width / 2. + size / 2 + j * size, 0.;\nint id = i * step + j;\ndart::dynamics::WeldJoint::Properties properties;\nproperties.mName = \"joint_\" + std::to_string(id);\ndart::dynamics::BodyNode::Properties bd_properties;\nbd_properties.mName = \"body_\" + std::to_string(id);\ndart::dynamics::BodyNodePtr body = main_body->createChildJointAndBodyNodePair<dart::dynamics::WeldJoint>(properties, bd_properties).second;\nauto box = std::make_shared<dart::dynamics::BoxShape>(Eigen::Vector3d(size, size, floor_height));\n// no collision/dynamics for these ones; only visual shape\nauto box_node = body->createShapeNodeWith<dart::dynamics::VisualAspect>(box);\nif (c % 2 == 0)\nbox_node->getVisualAspect()->setColor(second_color);\nelse\nbox_node->getVisualAspect()->setColor(first_color);\n// Put the body into position\nEigen::Isometry3d tf(Eigen::Isometry3d::Identity());\ntf.translation() = init_pose;\nbody->getParentJoint()->setTransformFromParentBodyNode(tf);\nc++;\n}\n}\nauto floor_robot = std::make_shared<Robot>(main_floor_skel, floor_name);\nadd_robot(floor_robot);\nreturn floor_robot;\n}\nvoid RobotDARTSimu::set_collision_detector(const std::string& collision_detector)\n{\nstd::string coll = collision_detector;\nfor (auto& c : coll)\nc = tolower(c);\nif (coll == \"dart\")\n_world->getConstraintSolver()->setCollisionDetector(dart::collision::DARTCollisionDetector::create());\nelse if (coll == \"fcl\")\n_world->getConstraintSolver()->setCollisionDetector(dart::collision::FCLCollisionDetector::create());\nelse if (coll == \"bullet\") {\n#if (HAVE_BULLET == 1)\n_world->getConstraintSolver()->setCollisionDetector(dart::collision::BulletCollisionDetector::create());\n#else\nROBOT_DART_WARNING(true, \"DART is not installed with Bullet! Cannot set BulletCollisionDetector!\");\n#endif\n}\nelse if (coll == \"ode\") {\n#if (HAVE_ODE == 1)\n_world->getConstraintSolver()->setCollisionDetector(dart::collision::OdeCollisionDetector::create());\n#else\nROBOT_DART_WARNING(true, \"DART is not installed with ODE! Cannot set OdeCollisionDetector!\");\n#endif\n}\n}\nconst std::string& RobotDARTSimu::collision_detector() const { return _world->getConstraintSolver()->getCollisionDetector()->getType(); }\nvoid RobotDARTSimu::set_collision_masks(size_t robot_index, uint32_t category_mask, uint32_t collision_mask)\n{\nROBOT_DART_ASSERT(robot_index < _robots.size(), \"Robot index out of bounds\", );\nauto coll_filter = std::static_pointer_cast<collision_filter::BitmaskContactFilter>(_world->getConstraintSolver()->getCollisionOption().collisionFilter);\ncoll_filter->add_to_map(_robots[robot_index]->skeleton(), collision_mask, category_mask);\n}\nvoid RobotDARTSimu::set_collision_masks(size_t robot_index, const std::string& body_name, uint32_t category_mask, uint32_t collision_mask)\n{\nROBOT_DART_ASSERT(robot_index < _robots.size(), \"Robot index out of bounds\", );\nauto bd = _robots[robot_index]->skeleton()->getBodyNode(body_name);\nROBOT_DART_ASSERT(bd != nullptr, \"BodyNode does not exist in skeleton!\", );\nauto coll_filter = std::static_pointer_cast<collision_filter::BitmaskContactFilter>(_world->getConstraintSolver()->getCollisionOption().collisionFilter);\nfor (auto& shape : bd->getShapeNodes())\ncoll_filter->add_to_map(shape, collision_mask, category_mask);\n}\nvoid RobotDARTSimu::set_collision_masks(size_t robot_index, size_t body_index, uint32_t category_mask, uint32_t collision_mask)\n{\nROBOT_DART_ASSERT(robot_index < _robots.size(), \"Robot index out of bounds\", );\nauto skel = _robots[robot_index]->skeleton();\nROBOT_DART_ASSERT(body_index < skel->getNumBodyNodes(), \"BodyNode index out of bounds\", );\nauto bd = skel->getBodyNode(body_index);\nauto coll_filter = std::static_pointer_cast<collision_filter::BitmaskContactFilter>(_world->getConstraintSolver()->getCollisionOption().collisionFilter);\nfor (auto& shape : bd->getShapeNodes())\ncoll_filter->add_to_map(shape, collision_mask, category_mask);\n}\nuint32_t RobotDARTSimu::collision_mask(size_t robot_index, const std::string& body_name)\n{\nROBOT_DART_ASSERT(robot_index < _robots.size(), \"Robot index out of bounds\", 0xffffffff);\nauto bd = _robots[robot_index]->skeleton()->getBodyNode(body_name);\nROBOT_DART_ASSERT(bd != nullptr, \"BodyNode does not exist in skeleton!\", 0xffffffff);\nauto coll_filter = std::static_pointer_cast<collision_filter::BitmaskContactFilter>(_world->getConstraintSolver()->getCollisionOption().collisionFilter);\nuint32_t mask = 0xffffffff;\nfor (auto& shape : bd->getShapeNodes())\nmask &= coll_filter->mask(shape).collision_mask;\nreturn mask;\n}\nuint32_t RobotDARTSimu::collision_mask(size_t robot_index, size_t body_index)\n{\nROBOT_DART_ASSERT(robot_index < _robots.size(), \"Robot index out of bounds\", 0xffffffff);\nauto skel = _robots[robot_index]->skeleton();\nROBOT_DART_ASSERT(body_index < skel->getNumBodyNodes(), \"BodyNode index out of bounds\", 0xffffffff);\nauto bd = skel->getBodyNode(body_index);\nauto coll_filter = std::static_pointer_cast<collision_filter::BitmaskContactFilter>(_world->getConstraintSolver()->getCollisionOption().collisionFilter);\nuint32_t mask = 0xffffffff;\nfor (auto& shape : bd->getShapeNodes())\nmask &= coll_filter->mask(shape).collision_mask;\nreturn mask;\n}\nuint32_t RobotDARTSimu::collision_category(size_t robot_index, const std::string& body_name)\n{\nROBOT_DART_ASSERT(robot_index < _robots.size(), \"Robot index out of bounds\", 0xffffffff);\nauto bd = _robots[robot_index]->skeleton()->getBodyNode(body_name);\nROBOT_DART_ASSERT(bd != nullptr, \"BodyNode does not exist in skeleton!\", 0xffffffff);\nauto coll_filter = std::static_pointer_cast<collision_filter::BitmaskContactFilter>(_world->getConstraintSolver()->getCollisionOption().collisionFilter);\nuint32_t mask = 0xffffffff;\nfor (auto& shape : bd->getShapeNodes())\nmask &= coll_filter->mask(shape).category_mask;\nreturn mask;\n}\nuint32_t RobotDARTSimu::collision_category(size_t robot_index, size_t body_index)\n{\nROBOT_DART_ASSERT(robot_index < _robots.size(), \"Robot index out of bounds\", 0xffffffff);\nauto skel = _robots[robot_index]->skeleton();\nROBOT_DART_ASSERT(body_index < skel->getNumBodyNodes(), \"BodyNode index out of bounds\", 0xffffffff);\nauto bd = skel->getBodyNode(body_index);\nauto coll_filter = std::static_pointer_cast<collision_filter::BitmaskContactFilter>(_world->getConstraintSolver()->getCollisionOption().collisionFilter);\nuint32_t mask = 0xffffffff;\nfor (auto& shape : bd->getShapeNodes())\nmask &= coll_filter->mask(shape).category_mask;\nreturn mask;\n}\nstd::pair<uint32_t, uint32_t> RobotDARTSimu::collision_masks(size_t robot_index, const std::string& body_name)\n{\nstd::pair<uint32_t, uint32_t> mask = {0xffffffff, 0xffffffff};\nROBOT_DART_ASSERT(robot_index < _robots.size(), \"Robot index out of bounds\", mask);\nauto bd = _robots[robot_index]->skeleton()->getBodyNode(body_name);\nROBOT_DART_ASSERT(bd != nullptr, \"BodyNode does not exist in skeleton!\", mask);\nauto coll_filter = std::static_pointer_cast<collision_filter::BitmaskContactFilter>(_world->getConstraintSolver()->getCollisionOption().collisionFilter);\nfor (auto& shape : bd->getShapeNodes()) {\nmask.first &= coll_filter->mask(shape).collision_mask;\nmask.second &= coll_filter->mask(shape).category_mask;\n}\nreturn mask;\n}\nstd::pair<uint32_t, uint32_t> RobotDARTSimu::collision_masks(size_t robot_index, size_t body_index)\n{\nstd::pair<uint32_t, uint32_t> mask = {0xffffffff, 0xffffffff};\nROBOT_DART_ASSERT(robot_index < _robots.size(), \"Robot index out of bounds\", mask);\nauto skel = _robots[robot_index]->skeleton();\nROBOT_DART_ASSERT(body_index < skel->getNumBodyNodes(), \"BodyNode index out of bounds\", mask);\nauto bd = skel->getBodyNode(body_index);\nauto coll_filter = std::static_pointer_cast<collision_filter::BitmaskContactFilter>(_world->getConstraintSolver()->getCollisionOption().collisionFilter);\nfor (auto& shape : bd->getShapeNodes()) {\nmask.first &= coll_filter->mask(shape).collision_mask;\nmask.second &= coll_filter->mask(shape).category_mask;\n}\nreturn mask;\n}\nvoid RobotDARTSimu::remove_collision_masks(size_t robot_index)\n{\nROBOT_DART_ASSERT(robot_index < _robots.size(), \"Robot index out of bounds\", );\nauto coll_filter = std::static_pointer_cast<collision_filter::BitmaskContactFilter>(_world->getConstraintSolver()->getCollisionOption().collisionFilter);\ncoll_filter->remove_from_map(_robots[robot_index]->skeleton());\n}\nvoid RobotDARTSimu::remove_collision_masks(size_t robot_index, const std::string& body_name)\n{\nROBOT_DART_ASSERT(robot_index < _robots.size(), \"Robot index out of bounds\", );\nauto bd = _robots[robot_index]->skeleton()->getBodyNode(body_name);\nROBOT_DART_ASSERT(bd != nullptr, \"BodyNode does not exist in skeleton!\", );\nauto coll_filter = std::static_pointer_cast<collision_filter::BitmaskContactFilter>(_world->getConstraintSolver()->getCollisionOption().collisionFilter);\nfor (auto& shape : bd->getShapeNodes())\ncoll_filter->remove_from_map(shape);\n}\nvoid RobotDARTSimu::remove_collision_masks(size_t robot_index, size_t body_index)\n{\nROBOT_DART_ASSERT(robot_index < _robots.size(), \"Robot index out of bounds\", );\nauto skel = _robots[robot_index]->skeleton();\nROBOT_DART_ASSERT(body_index < skel->getNumBodyNodes(), \"BodyNode index out of bounds\", );\nauto bd = skel->getBodyNode(body_index);\nauto coll_filter = std::static_pointer_cast<collision_filter::BitmaskContactFilter>(_world->getConstraintSolver()->getCollisionOption().collisionFilter);\nfor (auto& shape : bd->getShapeNodes())\ncoll_filter->remove_from_map(shape);\n}\nvoid RobotDARTSimu::remove_all_collision_masks()\n{\nauto coll_filter = std::static_pointer_cast<collision_filter::BitmaskContactFilter>(_world->getConstraintSolver()->getCollisionOption().collisionFilter);\ncoll_filter->clear_all();\n}\n} // namespace robot_dart\n
"},{"location":"api/robot__dart__simu_8hpp/","title":"File robot_dart_simu.hpp","text":"

FileList > robot_dart > robot_dart_simu.hpp

Go to the source code of this file

"},{"location":"api/robot__dart__simu_8hpp/#namespaces","title":"Namespaces","text":"Type Name namespace robot_dart namespace simu"},{"location":"api/robot__dart__simu_8hpp/#classes","title":"Classes","text":"Type Name class RobotDARTSimu struct TextData

The documentation for this class was generated from the following file robot_dart/robot_dart_simu.hpp

"},{"location":"api/robot__dart__simu_8hpp_source/","title":"File robot_dart_simu.hpp","text":"

File List > robot_dart > robot_dart_simu.hpp

Go to the documentation of this file

#ifndef ROBOT_DART_SIMU_HPP\n#define ROBOT_DART_SIMU_HPP\n#include <robot_dart/gui/base.hpp>\n#include <robot_dart/robot.hpp>\n#include <robot_dart/scheduler.hpp>\n#include <robot_dart/sensor/sensor.hpp>\nnamespace robot_dart {\nnamespace simu {\nstruct GUIData;\n// We use the Abode Source Sans Pro font: https://github.com/adobe-fonts/source-sans-pro\n// This font is licensed under SIL Open Font License 1.1: https://github.com/adobe-fonts/source-sans-pro/blob/release/LICENSE.md\nstruct TextData {\nstd::string text;\nEigen::Affine2d transformation;\nEigen::Vector4d color;\nstd::uint8_t alignment;\nbool draw_background;\nEigen::Vector4d background_color;\ndouble font_size = 28.;\n};\n} // namespace simu\nclass RobotDARTSimu {\npublic:\nusing robot_t = std::shared_ptr<Robot>;\nRobotDARTSimu(double timestep = 0.015);\n~RobotDARTSimu();\nvoid run(double max_duration = 5.0, bool reset_commands = false, bool force_position_bounds = true);\nbool step_world(bool reset_commands = false, bool force_position_bounds = true);\nbool step(bool reset_commands = false, bool force_position_bounds = true);\nScheduler& scheduler() { return _scheduler; }\nconst Scheduler& scheduler() const { return _scheduler; }\nbool schedule(int freq) { return _scheduler(freq); }\nint physics_freq() const { return _physics_freq; }\nint control_freq() const { return _control_freq; }\nvoid set_control_freq(int frequency)\n{\nROBOT_DART_EXCEPTION_INTERNAL_ASSERT(\nfrequency <= _physics_freq && \"Control frequency needs to be less than physics frequency\");\n_control_freq = frequency;\n}\nint graphics_freq() const { return _graphics_freq; }\nvoid set_graphics_freq(int frequency)\n{\nROBOT_DART_EXCEPTION_INTERNAL_ASSERT(\nfrequency <= _physics_freq && \"Graphics frequency needs to be less than physics frequency\");\n_graphics_freq = frequency;\n_graphics->set_fps(_graphics_freq);\n}\nstd::shared_ptr<gui::Base> graphics() const;\nvoid set_graphics(const std::shared_ptr<gui::Base>& graphics);\ndart::simulation::WorldPtr world();\ntemplate <typename T, typename... Args>\nstd::shared_ptr<T> add_sensor(Args&&... args)\n{\nadd_sensor(std::make_shared<T>(std::forward<Args>(args)...));\nreturn std::static_pointer_cast<T>(_sensors.back());\n}\nvoid add_sensor(const std::shared_ptr<sensor::Sensor>& sensor);\nstd::vector<std::shared_ptr<sensor::Sensor>> sensors() const;\nstd::shared_ptr<sensor::Sensor> sensor(size_t index) const;\nvoid remove_sensor(const std::shared_ptr<sensor::Sensor>& sensor);\nvoid remove_sensor(size_t index);\nvoid remove_sensors(const std::string& type);\nvoid clear_sensors();\ndouble timestep() const;\nvoid set_timestep(double timestep, bool update_control_freq = true);\nEigen::Vector3d gravity() const;\nvoid set_gravity(const Eigen::Vector3d& gravity);\nvoid stop_sim(bool disable = true);\nbool halted_sim() const;\nsize_t num_robots() const;\nconst std::vector<robot_t>& robots() const;\nrobot_t robot(size_t index) const;\nint robot_index(const robot_t& robot) const;\nvoid add_robot(const robot_t& robot);\nvoid add_visual_robot(const robot_t& robot);\nvoid remove_robot(const robot_t& robot);\nvoid remove_robot(size_t index);\nvoid clear_robots();\nsimu::GUIData* gui_data();\nvoid enable_text_panel(bool enable = true, double font_size = -1);\nstd::string text_panel_text() const;\nvoid set_text_panel(const std::string& str);\nvoid enable_status_bar(bool enable = true, double font_size = -1);\nstd::string status_bar_text() const;\nstd::shared_ptr<simu::TextData> add_text(const std::string& text, const Eigen::Affine2d& tf = Eigen::Affine2d::Identity(), Eigen::Vector4d color = Eigen::Vector4d(1, 1, 1, 1), std::uint8_t alignment = (1 | 3 << 3), bool draw_bg = false, Eigen::Vector4d bg_color = Eigen::Vector4d(0, 0, 0, 0.75), double font_size = 28);\nstd::shared_ptr<Robot> add_floor(double floor_width = 10.0, double floor_height = 0.1, const Eigen::Isometry3d& tf = Eigen::Isometry3d::Identity(), const std::string& floor_name = \"floor\");\nstd::shared_ptr<Robot> add_checkerboard_floor(double floor_width = 10.0, double floor_height = 0.1, double size = 1., const Eigen::Isometry3d& tf = Eigen::Isometry3d::Identity(), const std::string& floor_name = \"checkerboard_floor\", const Eigen::Vector4d& first_color = dart::Color::White(1.), const Eigen::Vector4d& second_color = dart::Color::Gray(1.));\nvoid set_collision_detector(const std::string& collision_detector); // collision_detector can be \"DART\", \"FCL\", \"Ode\" or \"Bullet\" (case does not matter)\nconst std::string& collision_detector() const;\n// Bitmask collision filtering\nvoid set_collision_masks(size_t robot_index, uint32_t category_mask, uint32_t collision_mask);\nvoid set_collision_masks(size_t robot_index, const std::string& body_name, uint32_t category_mask, uint32_t collision_mask);\nvoid set_collision_masks(size_t robot_index, size_t body_index, uint32_t category_mask, uint32_t collision_mask);\nuint32_t collision_mask(size_t robot_index, const std::string& body_name);\nuint32_t collision_mask(size_t robot_index, size_t body_index);\nuint32_t collision_category(size_t robot_index, const std::string& body_name);\nuint32_t collision_category(size_t robot_index, size_t body_index);\nstd::pair<uint32_t, uint32_t> collision_masks(size_t robot_index, const std::string& body_name);\nstd::pair<uint32_t, uint32_t> collision_masks(size_t robot_index, size_t body_index);\nvoid remove_collision_masks(size_t robot_index);\nvoid remove_collision_masks(size_t robot_index, const std::string& body_name);\nvoid remove_collision_masks(size_t robot_index, size_t body_index);\nvoid remove_all_collision_masks();\nprotected:\nvoid _enable(std::shared_ptr<simu::TextData>& text, bool enable, double font_size);\ndart::simulation::WorldPtr _world;\nsize_t _old_index;\nbool _break;\nstd::vector<std::shared_ptr<sensor::Sensor>> _sensors;\nstd::vector<robot_t> _robots;\nstd::shared_ptr<gui::Base> _graphics;\nstd::unique_ptr<simu::GUIData> _gui_data;\nstd::shared_ptr<simu::TextData> _text_panel = nullptr;\nstd::shared_ptr<simu::TextData> _status_bar = nullptr;\nScheduler _scheduler;\nint _physics_freq = -1, _control_freq = -1, _graphics_freq = 40;\n};\n} // namespace robot_dart\n#endif\n
"},{"location":"api/robot__pool_8cpp/","title":"File robot_pool.cpp","text":"

FileList > robot_dart > robot_pool.cpp

Go to the source code of this file

"},{"location":"api/robot__pool_8cpp/#namespaces","title":"Namespaces","text":"Type Name namespace robot_dart

The documentation for this class was generated from the following file robot_dart/robot_pool.cpp

"},{"location":"api/robot__pool_8cpp_source/","title":"File robot_pool.cpp","text":"

File List > robot_dart > robot_pool.cpp

Go to the documentation of this file

#include <robot_dart/robot_pool.hpp>\nnamespace robot_dart {\nRobotPool::RobotPool(const std::function<std::shared_ptr<Robot>()>& robot_creator, size_t pool_size, bool verbose) : _robot_creator(robot_creator), _pool_size(pool_size), _verbose(verbose)\n{\nif (_verbose) {\nstd::cout << \"Creating a pool of \" << pool_size << \" robots: \";\nstd::cout.flush();\n}\nfor (size_t i = 0; i < _pool_size; ++i) {\nif (_verbose) {\nstd::cout << \"[\" << i << \"]\";\nstd::cout.flush();\n}\nauto robot = robot_creator();\n_model_filename = robot->model_filename();\n_reset_robot(robot);\n_skeletons.push_back(robot->skeleton());\n}\nfor (size_t i = 0; i < _pool_size; i++)\n_free.push_back(true);\nif (_verbose)\nstd::cout << std::endl;\n}\nstd::shared_ptr<Robot> RobotPool::get_robot(const std::string& name)\n{\nwhile (true) {\nstd::lock_guard<std::mutex> lock(_skeleton_mutex);\nfor (size_t i = 0; i < _pool_size; i++)\nif (_free[i]) {\n_free[i] = false;\nreturn std::make_shared<Robot>(_skeletons[i], name);\n}\n}\n}\nvoid RobotPool::free_robot(const std::shared_ptr<Robot>& robot)\n{\nstd::lock_guard<std::mutex> lock(_skeleton_mutex);\nfor (size_t i = 0; i < _pool_size; i++) {\nif (_skeletons[i] == robot->skeleton()) {\n_reset_robot(robot);\n_free[i] = true;\nbreak;\n}\n}\n}\nvoid RobotPool::_reset_robot(const std::shared_ptr<Robot>& robot)\n{\nrobot->reset();\n}\n} // namespace robot_dart\n
"},{"location":"api/robot__pool_8hpp/","title":"File robot_pool.hpp","text":"

FileList > robot_dart > robot_pool.hpp

Go to the source code of this file

"},{"location":"api/robot__pool_8hpp/#namespaces","title":"Namespaces","text":"Type Name namespace robot_dart"},{"location":"api/robot__pool_8hpp/#classes","title":"Classes","text":"Type Name class RobotPool

The documentation for this class was generated from the following file robot_dart/robot_pool.hpp

"},{"location":"api/robot__pool_8hpp_source/","title":"File robot_pool.hpp","text":"

File List > robot_dart > robot_pool.hpp

Go to the documentation of this file

#ifndef ROBOT_DART_ROBOT_POOL\n#define ROBOT_DART_ROBOT_POOL\n#include <functional>\n#include <memory>\n#include <mutex>\n#include <vector>\n#include <robot_dart/robot.hpp>\nnamespace robot_dart {\nclass RobotPool {\npublic:\nusing robot_creator_t = std::function<std::shared_ptr<Robot>()>;\nRobotPool(const robot_creator_t& robot_creator, size_t pool_size = 32, bool verbose = true);\nvirtual ~RobotPool() {}\nRobotPool(const RobotPool&) = delete;\nvoid operator=(const RobotPool&) = delete;\nvirtual std::shared_ptr<Robot> get_robot(const std::string& name = \"robot\");\nvirtual void free_robot(const std::shared_ptr<Robot>& robot);\nconst std::string& model_filename() const { return _model_filename; }\nprotected:\nrobot_creator_t _robot_creator;\nsize_t _pool_size;\nbool _verbose;\nstd::vector<dart::dynamics::SkeletonPtr> _skeletons;\nstd::vector<bool> _free;\nstd::mutex _skeleton_mutex;\nstd::string _model_filename;\nvirtual void _reset_robot(const std::shared_ptr<Robot>& robot);\n};\n} // namespace robot_dart\n#endif\n
"},{"location":"api/scheduler_8cpp/","title":"File scheduler.cpp","text":"

FileList > robot_dart > scheduler.cpp

Go to the source code of this file

"},{"location":"api/scheduler_8cpp/#namespaces","title":"Namespaces","text":"Type Name namespace robot_dart

The documentation for this class was generated from the following file robot_dart/scheduler.cpp

"},{"location":"api/scheduler_8cpp_source/","title":"File scheduler.cpp","text":"

File List > robot_dart > scheduler.cpp

Go to the documentation of this file

#include <robot_dart/scheduler.hpp>\nnamespace robot_dart {\nbool Scheduler::schedule(int frequency)\n{\nif (_max_frequency == -1) {\n_start_time = clock_t::now();\n_last_iteration_time = _start_time;\n}\n_max_frequency = std::max(_max_frequency, frequency);\ndouble period = std::round((1. / frequency) / _dt);\nROBOT_DART_EXCEPTION_INTERNAL_ASSERT(\nperiod >= 1. && \"Time-step is too big for required frequency.\");\nif (_current_step % int(period) == 0)\nreturn true;\nreturn false;\n}\nvoid Scheduler::reset(double dt, bool sync, double current_time, double real_time)\n{\nROBOT_DART_EXCEPTION_INTERNAL_ASSERT(dt > 0. && \"Time-step needs to be bigger than zero.\");\n_current_time = 0.;\n_real_time = 0.;\n_simu_start_time = current_time;\n_real_start_time = real_time;\n_current_step = 0;\n_max_frequency = -1;\n_average_it_duration = 0.;\n_dt = dt;\n_sync = sync;\n}\ndouble Scheduler::step()\n{\n_current_time += _dt;\n_current_step += 1;\nauto end = clock_t::now();\n_it_duration = std::chrono::duration<double, std::micro>(end - _last_iteration_time).count();\n_last_iteration_time = end;\n_average_it_duration = _average_it_duration + (_it_duration - _average_it_duration) / _current_step;\nstd::chrono::duration<double, std::micro> real = end - _start_time;\nif (_sync) {\nauto expected = std::chrono::microseconds(int(_current_time * 1e6));\nstd::chrono::duration<double, std::micro> adjust = expected - real;\nif (adjust.count() > 0)\nstd::this_thread::sleep_for(adjust);\n}\n_real_time = real.count() * 1e-6;\nreturn _real_start_time + _real_time;\n}\n} // namespace robot_dart\n
"},{"location":"api/scheduler_8hpp/","title":"File scheduler.hpp","text":"

FileList > robot_dart > scheduler.hpp

Go to the source code of this file

"},{"location":"api/scheduler_8hpp/#namespaces","title":"Namespaces","text":"Type Name namespace robot_dart"},{"location":"api/scheduler_8hpp/#classes","title":"Classes","text":"Type Name class Scheduler

The documentation for this class was generated from the following file robot_dart/scheduler.hpp

"},{"location":"api/scheduler_8hpp_source/","title":"File scheduler.hpp","text":"

File List > robot_dart > scheduler.hpp

Go to the documentation of this file

#ifndef ROBOT_DART_SCHEDULER_HPP\n#define ROBOT_DART_SCHEDULER_HPP\n#include <robot_dart/utils.hpp>\n#include <chrono>\n#include <thread>\nnamespace robot_dart {\nclass Scheduler {\nprotected:\nusing clock_t = std::chrono::high_resolution_clock;\npublic:\nScheduler(double dt, bool sync = false) : _dt(dt), _sync(sync)\n{\nROBOT_DART_EXCEPTION_INTERNAL_ASSERT(_dt > 0. && \"Time-step needs to be bigger than zero.\");\n}\nbool operator()(int frequency) { return schedule(frequency); };\nbool schedule(int frequency);\ndouble step();\nvoid reset(double dt, bool sync = false, double current_time = 0., double real_time = 0.);\nvoid set_sync(bool enable) { _sync = enable; }\nbool sync() const { return _sync; }\ndouble current_time() const { return _simu_start_time + _current_time; }\ndouble next_time() const { return _simu_start_time + _current_time + _dt; }\ndouble real_time() const { return _real_start_time + _real_time; }\ndouble dt() const { return _dt; }\n// 0.8x => we are simulating at 80% of real time\ndouble real_time_factor() const { return _dt / it_duration(); }\n// time for a single iteration (wall-clock)\ndouble it_duration() const { return _average_it_duration * 1e-6; }\n// time of the last iteration (wall-clock)\ndouble last_it_duration() const { return _it_duration * 1e-6; }\nprotected:\ndouble _current_time = 0., _simu_start_time = 0., _real_time = 0., _real_start_time = 0., _it_duration = 0.;\ndouble _average_it_duration = 0.;\ndouble _dt;\nint _current_step = 0;\nbool _sync;\nint _max_frequency = -1;\nclock_t::time_point _start_time;\nclock_t::time_point _last_iteration_time;\n};\n} // namespace robot_dart\n#endif\n
"},{"location":"api/utils_8hpp/","title":"File utils.hpp","text":"

FileList > robot_dart > utils.hpp

Go to the source code of this file

"},{"location":"api/utils_8hpp/#namespaces","title":"Namespaces","text":"Type Name namespace robot_dart"},{"location":"api/utils_8hpp/#classes","title":"Classes","text":"Type Name class Assertion"},{"location":"api/utils_8hpp/#macros","title":"Macros","text":"Type Name define M_PIf static_cast<float>(M_PI) define ROBOT_DART_ASSERT (condition, message, returnValue) define ROBOT_DART_EXCEPTION_ASSERT (condition, message) define ROBOT_DART_EXCEPTION_INTERNAL_ASSERT (condition) define ROBOT_DART_INTERNAL_ASSERT (condition) define ROBOT_DART_SHOW_WARNINGS true define ROBOT_DART_UNUSED_VARIABLE (var) (void)(var) define ROBOT_DART_WARNING (condition, message)"},{"location":"api/utils_8hpp/#macro-definition-documentation","title":"Macro Definition Documentation","text":""},{"location":"api/utils_8hpp/#define-m_pif","title":"define M_PIf","text":"
#define M_PIf static_cast<float>(M_PI)\n
"},{"location":"api/utils_8hpp/#define-robot_dart_assert","title":"define ROBOT_DART_ASSERT","text":"
#define ROBOT_DART_ASSERT (\ncondition,\nmessage,\nreturnValue\n) do {                                                                                                             \\\n        if (!(condition)) {                                                                                          \\\n            std::cerr << __LINE__ << \" \" << __FILE__ << \" -> robot_dart assertion failed: \" << message << std::endl; \\\n            return returnValue;                                                                                      \\\n        }                                                                                                            \\\n    } while (false)\n
"},{"location":"api/utils_8hpp/#define-robot_dart_exception_assert","title":"define ROBOT_DART_EXCEPTION_ASSERT","text":"
#define ROBOT_DART_EXCEPTION_ASSERT (\ncondition,\nmessage\n) do {                                                \\\n        if (!(condition)) {                             \\\n            throw robot_dart::Assertion (message);       \\\n        }                                               \\\n    } while (false)\n
"},{"location":"api/utils_8hpp/#define-robot_dart_exception_internal_assert","title":"define ROBOT_DART_EXCEPTION_INTERNAL_ASSERT","text":"
#define ROBOT_DART_EXCEPTION_INTERNAL_ASSERT (\ncondition\n) do {                                                \\\n        if (!(condition)) {                             \\\n            throw robot_dart::Assertion (#condition);    \\\n        }                                               \\\n    } while (false)\n
"},{"location":"api/utils_8hpp/#define-robot_dart_internal_assert","title":"define ROBOT_DART_INTERNAL_ASSERT","text":"
#define ROBOT_DART_INTERNAL_ASSERT (\ncondition\n) do {                                                                                                                      \\\n        if (!(condition)) {                                                                                                   \\\n            std::cerr << \"Assertion '\" << #condition << \"' failed in '\" << __FILE__ << \"' on line \" << __LINE__ << std::endl; \\\n            std::abort();                                                                                                     \\\n        }                                                                                                                     \\\n    } while (false)\n
"},{"location":"api/utils_8hpp/#define-robot_dart_show_warnings","title":"define ROBOT_DART_SHOW_WARNINGS","text":"
#define ROBOT_DART_SHOW_WARNINGS true\n
"},{"location":"api/utils_8hpp/#define-robot_dart_unused_variable","title":"define ROBOT_DART_UNUSED_VARIABLE","text":"
#define ROBOT_DART_UNUSED_VARIABLE (\nvar\n) (void)(var)\n
"},{"location":"api/utils_8hpp/#define-robot_dart_warning","title":"define ROBOT_DART_WARNING","text":"
#define ROBOT_DART_WARNING (\ncondition,\nmessage\n) if (ROBOT_DART_SHOW_WARNINGS && (condition)) {                               \\\n        std::cerr << \"[robot_dart WARNING]: \\\"\" << message << \"\\\"\" << std::endl; \\\n    }\n

The documentation for this class was generated from the following file robot_dart/utils.hpp

"},{"location":"api/utils_8hpp_source/","title":"File utils.hpp","text":"

File List > robot_dart > utils.hpp

Go to the documentation of this file

#ifndef ROBOT_DART_UTILS_HPP\n#define ROBOT_DART_UTILS_HPP\n#include <exception>\n#include <iostream>\n#include <robot_dart/utils_headers_external.hpp>\n#ifndef ROBOT_DART_SHOW_WARNINGS\n#define ROBOT_DART_SHOW_WARNINGS true\n#endif\n#ifndef M_PIf\n#define M_PIf static_cast<float>(M_PI)\n#endif\nnamespace robot_dart {\ninline Eigen::VectorXd make_vector(std::initializer_list<double> args)\n{\nreturn Eigen::VectorXd::Map(args.begin(), args.size());\n}\ninline Eigen::Isometry3d make_tf(const Eigen::Matrix3d& R, const Eigen::Vector3d& t)\n{\nEigen::Isometry3d tf = Eigen::Isometry3d::Identity();\ntf.linear().matrix() = R;\ntf.translation() = t;\nreturn tf;\n}\ninline Eigen::Isometry3d make_tf(const Eigen::Matrix3d& R)\n{\nEigen::Isometry3d tf = Eigen::Isometry3d::Identity();\ntf.linear().matrix() = R;\nreturn tf;\n}\ninline Eigen::Isometry3d make_tf(const Eigen::Vector3d& t)\n{\nEigen::Isometry3d tf = Eigen::Isometry3d::Identity();\ntf.translation() = t;\nreturn tf;\n}\ninline Eigen::Isometry3d make_tf(std::initializer_list<double> args)\n{\nEigen::Isometry3d tf = Eigen::Isometry3d::Identity();\ntf.translation() = make_vector(args);\nreturn tf;\n}\nclass Assertion : public std::exception {\npublic:\nAssertion(const std::string& msg = \"\") : _msg(_make_message(msg)) {}\nconst char* what() const throw()\n{\nreturn _msg.c_str();\n}\nprivate:\nstd::string _msg;\nstd::string _make_message(const std::string& msg) const\n{\nstd::string message = \"robot_dart assertion failed\";\nif (msg != \"\")\nmessage += \": '\" + msg + \"'\";\nreturn message;\n}\n};\n} // namespace robot_dart\n#define ROBOT_DART_UNUSED_VARIABLE(var) (void)(var)\n#define ROBOT_DART_WARNING(condition, message)                                   \\\n    if (ROBOT_DART_SHOW_WARNINGS && (condition)) {                               \\\n        std::cerr << \"[robot_dart WARNING]: \\\"\" << message << \"\\\"\" << std::endl; \\\n    }\n#define ROBOT_DART_ASSERT(condition, message, returnValue)                                                           \\\n    do {                                                                                                             \\\n        if (!(condition)) {                                                                                          \\\n            std::cerr << __LINE__ << \" \" << __FILE__ << \" -> robot_dart assertion failed: \" << message << std::endl; \\\n            return returnValue;                                                                                      \\\n        }                                                                                                            \\\n    } while (false)\n#define ROBOT_DART_EXCEPTION_ASSERT(condition, message) \\\n    do {                                                \\\n        if (!(condition)) {                             \\\n            throw robot_dart::Assertion(message);       \\\n        }                                               \\\n    } while (false)\n#define ROBOT_DART_INTERNAL_ASSERT(condition)                                                                                 \\\n    do {                                                                                                                      \\\n        if (!(condition)) {                                                                                                   \\\n            std::cerr << \"Assertion '\" << #condition << \"' failed in '\" << __FILE__ << \"' on line \" << __LINE__ << std::endl; \\\n            std::abort();                                                                                                     \\\n        }                                                                                                                     \\\n    } while (false)\n#define ROBOT_DART_EXCEPTION_INTERNAL_ASSERT(condition) \\\n    do {                                                \\\n        if (!(condition)) {                             \\\n            throw robot_dart::Assertion(#condition);    \\\n        }                                               \\\n    } while (false)\n#endif\n
"},{"location":"api/utils__headers__dart__collision_8hpp/","title":"File utils_headers_dart_collision.hpp","text":"

FileList > robot_dart > utils_headers_dart_collision.hpp

Go to the source code of this file

The documentation for this class was generated from the following file robot_dart/utils_headers_dart_collision.hpp

"},{"location":"api/utils__headers__dart__collision_8hpp_source/","title":"File utils_headers_dart_collision.hpp","text":"

File List > robot_dart > utils_headers_dart_collision.hpp

Go to the documentation of this file

#ifndef ROBOT_DART_UTILS_HEADERS_DART_COLLISION_HPP\n#define ROBOT_DART_UTILS_HEADERS_DART_COLLISION_HPP\n#pragma GCC system_header\n#include <dart/config.hpp>\n#include <dart/collision/CollisionFilter.hpp>\n#include <dart/collision/CollisionObject.hpp>\n#include <dart/collision/dart/DARTCollisionDetector.hpp>\n#include <dart/collision/fcl/FCLCollisionDetector.hpp>\n#include <dart/constraint/ConstraintSolver.hpp>\n#if (HAVE_BULLET == 1)\n#include <dart/collision/bullet/BulletCollisionDetector.hpp>\n#endif\n#if (HAVE_ODE == 1)\n#include <dart/collision/ode/OdeCollisionDetector.hpp>\n#endif\n#endif\n
"},{"location":"api/utils__headers__dart__dynamics_8hpp/","title":"File utils_headers_dart_dynamics.hpp","text":"

FileList > robot_dart > utils_headers_dart_dynamics.hpp

Go to the source code of this file

The documentation for this class was generated from the following file robot_dart/utils_headers_dart_dynamics.hpp

"},{"location":"api/utils__headers__dart__dynamics_8hpp_source/","title":"File utils_headers_dart_dynamics.hpp","text":"

File List > robot_dart > utils_headers_dart_dynamics.hpp

Go to the documentation of this file

#ifndef ROBOT_DART_UTILS_HEADERS_DART_DYNAMICS_HPP\n#define ROBOT_DART_UTILS_HEADERS_DART_DYNAMICS_HPP\n#pragma GCC system_header\n#include <dart/dynamics/BallJoint.hpp>\n#include <dart/dynamics/BodyNode.hpp>\n#include <dart/dynamics/BoxShape.hpp>\n#include <dart/dynamics/DegreeOfFreedom.hpp>\n#include <dart/dynamics/EllipsoidShape.hpp>\n#include <dart/dynamics/EulerJoint.hpp>\n#include <dart/dynamics/FreeJoint.hpp>\n#include <dart/dynamics/MeshShape.hpp>\n#include <dart/dynamics/RevoluteJoint.hpp>\n#include <dart/dynamics/ShapeNode.hpp>\n#include <dart/dynamics/SoftBodyNode.hpp>\n#include <dart/dynamics/SoftMeshShape.hpp>\n#include <dart/dynamics/WeldJoint.hpp>\n#endif\n
"},{"location":"api/utils__headers__dart__io_8hpp/","title":"File utils_headers_dart_io.hpp","text":"

FileList > robot_dart > utils_headers_dart_io.hpp

Go to the source code of this file

"},{"location":"api/utils__headers__dart__io_8hpp/#namespaces","title":"Namespaces","text":"Type Name namespace dart

The documentation for this class was generated from the following file robot_dart/utils_headers_dart_io.hpp

"},{"location":"api/utils__headers__dart__io_8hpp_source/","title":"File utils_headers_dart_io.hpp","text":"

File List > robot_dart > utils_headers_dart_io.hpp

Go to the documentation of this file

#ifndef ROBOT_DART_UTILS_HEADERS_DART_IO_HPP\n#define ROBOT_DART_UTILS_HEADERS_DART_IO_HPP\n#pragma GCC system_header\n#include <dart/config.hpp>\n#if DART_VERSION_AT_LEAST(7, 0, 0)\n#include <dart/io/SkelParser.hpp>\n#include <dart/io/sdf/SdfParser.hpp>\n#include <dart/io/urdf/urdf.hpp>\n#else\n#include <dart/utils/SkelParser.hpp>\n#include <dart/utils/sdf/SdfParser.hpp>\n#include <dart/utils/urdf/urdf.hpp>\n// namespace alias for compatibility\nnamespace dart {\nnamespace io = utils;\n}\n#endif\n#endif\n
"},{"location":"api/utils__headers__external_8hpp/","title":"File utils_headers_external.hpp","text":"

FileList > robot_dart > utils_headers_external.hpp

Go to the source code of this file

The documentation for this class was generated from the following file robot_dart/utils_headers_external.hpp

"},{"location":"api/utils__headers__external_8hpp_source/","title":"File utils_headers_external.hpp","text":"

File List > robot_dart > utils_headers_external.hpp

Go to the documentation of this file

#ifndef ROBOT_DART_UTILS_HEADERS_EXTERNAL_HPP\n#define ROBOT_DART_UTILS_HEADERS_EXTERNAL_HPP\n#pragma GCC system_header\n#include <Eigen/Core>\n#include <Eigen/Geometry>\n#include <dart/config.hpp>\n#include <dart/dynamics/MeshShape.hpp>\n#include <dart/dynamics/Skeleton.hpp>\n#include <dart/simulation/World.hpp>\n#endif\n
"},{"location":"api/utils__headers__external__gui_8hpp/","title":"File utils_headers_external_gui.hpp","text":"

FileList > robot_dart > utils_headers_external_gui.hpp

Go to the source code of this file

The documentation for this class was generated from the following file robot_dart/utils_headers_external_gui.hpp

"},{"location":"api/utils__headers__external__gui_8hpp_source/","title":"File utils_headers_external_gui.hpp","text":"

File List > robot_dart > utils_headers_external_gui.hpp

Go to the documentation of this file

#ifndef ROBOT_DART_UTILS_HEADERS_EXTERNAL_GUI_HPP\n#define ROBOT_DART_UTILS_HEADERS_EXTERNAL_GUI_HPP\n#pragma GCC system_header\n#include <robot_dart/utils_headers_external.hpp>\n#include <Magnum/DartIntegration/World.h>\n#endif\n
"},{"location":"api/namespaces/","title":"Namespace List","text":"

Here is a list of all namespaces with brief descriptions:

"},{"location":"api/classes/","title":"Class Index","text":""},{"location":"api/classes/#a","title":"a","text":""},{"location":"api/classes/#b","title":"b","text":""},{"location":"api/classes/#c","title":"c","text":""},{"location":"api/classes/#d","title":"d","text":""},{"location":"api/classes/#f","title":"f","text":""},{"location":"api/classes/#g","title":"g","text":""},{"location":"api/classes/#h","title":"h","text":""},{"location":"api/classes/#i","title":"i","text":""},{"location":"api/classes/#l","title":"l","text":""},{"location":"api/classes/#m","title":"m","text":""},{"location":"api/classes/#o","title":"o","text":""},{"location":"api/classes/#p","title":"p","text":""},{"location":"api/classes/#r","title":"r","text":""},{"location":"api/classes/#s","title":"s","text":""},{"location":"api/classes/#t","title":"t","text":""},{"location":"api/classes/#u","title":"u","text":""},{"location":"api/classes/#v","title":"v","text":""},{"location":"api/classes/#w","title":"w","text":""},{"location":"api/hierarchy/","title":"Class Hierarchy","text":"

This inheritance list is sorted roughly, but not completely, alphabetically:

"},{"location":"api/modules/","title":"Modules","text":"

No modules found.

"},{"location":"api/pages/","title":"Related Pages","text":"

Here is a list of all related documentation pages:

"},{"location":"api/class_members/","title":"Class Members","text":""},{"location":"api/class_members/#a","title":"a","text":""},{"location":"api/class_members/#b","title":"b","text":""},{"location":"api/class_members/#c","title":"c","text":""},{"location":"api/class_members/#d","title":"d","text":""},{"location":"api/class_members/#e","title":"e","text":""},{"location":"api/class_members/#f","title":"f","text":""},{"location":"api/class_members/#g","title":"g","text":""},{"location":"api/class_members/#h","title":"h","text":""},{"location":"api/class_members/#i","title":"i","text":""},{"location":"api/class_members/#j","title":"j","text":""},{"location":"api/class_members/#k","title":"k","text":""},{"location":"api/class_members/#l","title":"l","text":""},{"location":"api/class_members/#m","title":"m","text":""},{"location":"api/class_members/#n","title":"n","text":""},{"location":"api/class_members/#o","title":"o","text":""},{"location":"api/class_members/#p","title":"p","text":""},{"location":"api/class_members/#r","title":"r","text":""},{"location":"api/class_members/#s","title":"s","text":""},{"location":"api/class_members/#t","title":"t","text":""},{"location":"api/class_members/#u","title":"u","text":""},{"location":"api/class_members/#v","title":"v","text":""},{"location":"api/class_members/#w","title":"w","text":""},{"location":"api/class_members/#_1","title":"~","text":""},{"location":"api/class_members/#_","title":"_","text":""},{"location":"api/class_member_functions/","title":"Class Member Functions","text":""},{"location":"api/class_member_functions/#a","title":"a","text":""},{"location":"api/class_member_functions/#b","title":"b","text":""},{"location":"api/class_member_functions/#c","title":"c","text":""},{"location":"api/class_member_functions/#d","title":"d","text":""},{"location":"api/class_member_functions/#e","title":"e","text":""},{"location":"api/class_member_functions/#f","title":"f","text":""},{"location":"api/class_member_functions/#g","title":"g","text":""},{"location":"api/class_member_functions/#h","title":"h","text":""},{"location":"api/class_member_functions/#i","title":"i","text":""},{"location":"api/class_member_functions/#j","title":"j","text":""},{"location":"api/class_member_functions/#k","title":"k","text":""},{"location":"api/class_member_functions/#l","title":"l","text":""},{"location":"api/class_member_functions/#m","title":"m","text":""},{"location":"api/class_member_functions/#n","title":"n","text":""},{"location":"api/class_member_functions/#o","title":"o","text":""},{"location":"api/class_member_functions/#p","title":"p","text":""},{"location":"api/class_member_functions/#r","title":"r","text":""},{"location":"api/class_member_functions/#s","title":"s","text":""},{"location":"api/class_member_functions/#t","title":"t","text":""},{"location":"api/class_member_functions/#u","title":"u","text":""},{"location":"api/class_member_functions/#v","title":"v","text":""},{"location":"api/class_member_functions/#w","title":"w","text":""},{"location":"api/class_member_functions/#_1","title":"~","text":""},{"location":"api/class_member_functions/#_","title":"_","text":""},{"location":"api/class_member_variables/","title":"Class Member Variables","text":""},{"location":"api/class_member_variables/#a","title":"a","text":""},{"location":"api/class_member_variables/#b","title":"b","text":""},{"location":"api/class_member_variables/#c","title":"c","text":""},{"location":"api/class_member_variables/#d","title":"d","text":""},{"location":"api/class_member_variables/#f","title":"f","text":""},{"location":"api/class_member_variables/#g","title":"g","text":""},{"location":"api/class_member_variables/#h","title":"h","text":""},{"location":"api/class_member_variables/#i","title":"i","text":""},{"location":"api/class_member_variables/#m","title":"m","text":""},{"location":"api/class_member_variables/#r","title":"r","text":""},{"location":"api/class_member_variables/#s","title":"s","text":""},{"location":"api/class_member_variables/#t","title":"t","text":""},{"location":"api/class_member_variables/#w","title":"w","text":""},{"location":"api/class_member_variables/#_","title":"_","text":""},{"location":"api/class_member_typedefs/","title":"Class Member Typedefs","text":""},{"location":"api/class_member_typedefs/#c","title":"c","text":""},{"location":"api/class_member_typedefs/#d","title":"d","text":""},{"location":"api/class_member_typedefs/#f","title":"f","text":""},{"location":"api/class_member_typedefs/#n","title":"n","text":""},{"location":"api/class_member_typedefs/#p","title":"p","text":""},{"location":"api/class_member_typedefs/#r","title":"r","text":""},{"location":"api/class_member_typedefs/#t","title":"t","text":""},{"location":"api/class_member_enums/","title":"Class Member Enums","text":""},{"location":"api/class_member_enums/#f","title":"f","text":""},{"location":"api/namespace_members/","title":"Namespace Members","text":""},{"location":"api/namespace_members/#a","title":"a","text":""},{"location":"api/namespace_members/#b","title":"b","text":""},{"location":"api/namespace_members/#c","title":"c","text":""},{"location":"api/namespace_members/#d","title":"d","text":""},{"location":"api/namespace_members/#m","title":"m","text":""},{"location":"api/namespace_members/#o","title":"o","text":""},{"location":"api/namespace_members/#p","title":"p","text":""},{"location":"api/namespace_members/#r","title":"r","text":""},{"location":"api/namespace_members/#s","title":"s","text":""},{"location":"api/namespace_members/#_1","title":"@","text":""},{"location":"api/namespace_member_functions/","title":"Namespace Member Functions","text":""},{"location":"api/namespace_member_functions/#a","title":"a","text":""},{"location":"api/namespace_member_functions/#c","title":"c","text":""},{"location":"api/namespace_member_functions/#d","title":"d","text":""},{"location":"api/namespace_member_functions/#m","title":"m","text":""},{"location":"api/namespace_member_functions/#p","title":"p","text":""},{"location":"api/namespace_member_functions/#r","title":"r","text":""},{"location":"api/namespace_member_functions/#s","title":"s","text":""},{"location":"api/namespace_member_variables/","title":"Namespace Member Variables","text":""},{"location":"api/namespace_member_variables/#b","title":"b","text":""},{"location":"api/namespace_member_typedefs/","title":"Namespace Member Typedefs","text":""},{"location":"api/namespace_member_typedefs/#c","title":"c","text":""},{"location":"api/namespace_member_typedefs/#o","title":"o","text":""},{"location":"api/namespace_member_typedefs/#s","title":"s","text":""},{"location":"api/namespace_member_enums/","title":"Namespace Member Enums","text":""},{"location":"api/namespace_member_enums/#_1","title":"@","text":""},{"location":"api/functions/","title":"Functions","text":""},{"location":"api/functions/#r","title":"r","text":""},{"location":"api/functions/#s","title":"s","text":""},{"location":"api/macros/","title":"Macros","text":""},{"location":"api/macros/#g","title":"g","text":""},{"location":"api/macros/#m","title":"m","text":""},{"location":"api/macros/#r","title":"r","text":""},{"location":"api/macros/#s","title":"s","text":""},{"location":"api/variables/","title":"Variables","text":""},{"location":"api/variables/#s","title":"s","text":""},{"location":"api/links/","title":"Links","text":""}]} \ No newline at end of file +{"config":{"lang":["en"],"separator":"[\\s\\-]+","pipeline":["stopWordFilter"]},"docs":[{"location":"","title":"Home","text":""},{"location":"#robotdart","title":"RobotDART","text":"

RobotDART is a C++ robot simulator (with optional Python bindings) built on top of the DART physics engine. The RobotDART simulator is intended to be used by Robotics and Machine Learning researchers who want to write controllers or test learning algorithms without the delays and overhead that usually comes with other simulators (e.g., Gazebo, Coppelia-sim).

For this reason, the simulator runs headless by default, and there is the possibility of rendering the scene (e.g., through a camera sensor) without opening a graphics window. All RobotDART's code is thread-safe (including graphics and camera sensors), and thus enables its users to use their code in parallel jobs in multicore computers.

In a few words, RobotDART combines:

"},{"location":"#main-features","title":"Main Features","text":""},{"location":"#what-robotdart-is-not","title":"What RobotDART is not","text":""},{"location":"faq/","title":"FAQ","text":""},{"location":"faq/#frequently-asked-questions","title":"Frequently Asked Questions","text":"

This pages provides a user guide of the library through Frequently Asked Questions (FAQ).

"},{"location":"faq/#what-is-a-minimal-working-example-of-robotdart","title":"What is a minimal working example of RobotDART?","text":"

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.

C++Python
#include <robot_dart/robot_dart_simu.hpp>\n#ifdef GRAPHIC\n#include <robot_dart/gui/magnum/graphics.hpp>\n#endif\n
import RobotDART as rd\n
C++Python
auto robot = std::make_shared<robot_dart::Robot>(\"pexod.urdf\");\n
robot = rd.Robot(\"pexod.urdf\");\n
C++Python
robot->set_base_pose(robot_dart::make_tf({0., 0., 0.2}));\n
robot.set_base_pose([0., 0., 0., 0., 0., 0.2])\n
C++Python
robot_dart::RobotDARTSimu simu(0.001); // dt=0.001, 1KHz simulation\nsimu.add_floor();\nsimu.add_robot(robot);\n
simu = rd.RobotDARTSimu(0.001); # dt=0.001, 1KHz simulation\nsimu.add_floor();\nsimu.add_robot(robot);\n
C++Python
auto graphics = std::make_shared<robot_dart::gui::magnum::Graphics>();\nsimu.set_graphics(graphics);\ngraphics->look_at({0.5, 3., 0.75}, {0.5, 0., 0.2});\n
graphics = rd.gui.Graphics()\nsimu.set_graphics(graphics)\ngraphics.look_at([0.5, 3., 0.75], [0.5, 0., 0.2])\n
C++Python
simu.run(10.);\n
simu.run(10.)\n

"},{"location":"faq/#what-robots-are-supported-in-robotdart","title":"What robots are supported in RobotDART?","text":"

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).

"},{"location":"faq/#how-can-i-load-my-own-urdfsdfskelmjcf-file","title":"How can I load my own URDF/SDF/SKEL/MJCF file?","text":"

See the robots page for details.

"},{"location":"faq/#how-do-i-enable-graphics-in-my-code","title":"How do I enable graphics in my code?","text":"

To enable graphics in your code, you need to do the following:

C++Python
auto graphics = std::make_shared<robot_dart::gui::magnum::Graphics>();\nsimu.set_graphics(graphics);\ngraphics->look_at({0.5, 3., 0.75}, {0.5, 0., 0.2});\n
graphics = rd.gui.Graphics()\nsimu.set_graphics(graphics)\ngraphics.look_at([0.5, 3., 0.75], [0.5, 0., 0.2])\n
"},{"location":"faq/#i-want-to-have-multiple-camera-sensors-is-it-possible","title":"I want to have multiple camera sensors. Is it possible?","text":"

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:

C++Python
// Add camera\nauto camera = std::make_shared<robot_dart::sensor::Camera>(graphics->magnum_app(), 256, 256);\n
# Add camera\ncamera = rd.sensor.Camera(graphics.magnum_app(), 32, 32)\n
"},{"location":"faq/#how-do-i-record-a-video","title":"How do I record a video?","text":"

In order to record a video of what the main or any other camera \"sees\", you need to call the function record_video(path) of the graphics class:

C++Python
graphics->record_video(\"talos_dancing.mp4\");\n
graphics.record_video(\"talos_dancing.mp4\")\n

Or the camera class:

C++Python
// cameras can also record video\ncamera->record_video(\"video-camera.mp4\");\n
# cameras can also record video\ncamera.record_video(\"video-camera.mp4\")\n
"},{"location":"faq/#how-can-i-position-a-camera-to-the-environment","title":"How can I position a camera to the environment?","text":"

In order to position a camera inside the world, we need to use the lookAt method of the camera/graphics object:

C++Python
// set the position of the camera, and the position where the main camera is looking at\nEigen::Vector3d cam_pos = {-0.5, -3., 0.75};\nEigen::Vector3d cam_looks_at = {0.5, 0., 0.2};\ncamera->look_at(cam_pos, cam_looks_at);\n
# set the position of the camera, and the position where the main camera is looking at\ncam_pos = [-0.5, -3., 0.75]\ncam_looks_at = [0.5, 0., 0.2]\ncamera.look_at(cam_pos, cam_looks_at)\n
"},{"location":"faq/#how-can-i-attach-a-camera-to-a-moving-link","title":"How can I attach a camera to a moving link?","text":"

Cameras can be easily attached to a moving link:

C++Python
Eigen::Isometry3d tf;\ntf = Eigen::AngleAxisd(3.14, Eigen::Vector3d{1., 0., 0.});\ntf *= Eigen::AngleAxisd(1.57, Eigen::Vector3d{0., 0., 1.});\ntf.translation() = Eigen::Vector3d(0., 0., 0.1);\ncamera->attach_to_body(robot->body_node(\"iiwa_link_ee\"), tf); // cameras are looking towards -z by default\n
tf = dartpy.math.Isometry3()\nrot =  dartpy.math.AngleAxis(3.14, [1., 0., 0.])\nrot = rot.multiply( dartpy.math.AngleAxis(1.57, [0., 0., 1.])).to_rotation_matrix()\ntf.set_translation([0., 0., 0.1])\ncamera.attach_to_body(robot.body_node(\"iiwa_link_ee\"), tf) # cameras are looking towards -z by default\n
"},{"location":"faq/#how-can-i-manipulate-the-camera-object","title":"How can I manipulate the camera object?","text":"

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:

C++Python
camera->camera().set_far_plane(5.f);\ncamera->camera().set_near_plane(0.01f);\ncamera->camera().set_fov(60.0f);\n
camera.camera().set_far_plane(5.)\ncamera.camera().set_near_plane(0.01)\ncamera.camera().set_fov(60.0)\n

or all at once:

C++Python
camera->camera().set_camera_params(5., // far plane\n0.01f, // near plane\n60.0f, // field of view\n600, // width\n400 // height\n);\n
camera.camera().set_camera_params(5., #far plane\n0.01, #near plane\n60.0, # field of view\n600, # width\n400) #height\n

You can find a complete example at cameras.cpp.

"},{"location":"faq/#how-can-i-interact-with-the-camera","title":"How can I interact with the camera?","text":"

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.

"},{"location":"faq/#what-do-the-numbers-in-the-status-bar-mean","title":"What do the numbers in the status bar mean?","text":"

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.

"},{"location":"faq/#how-can-i-alter-the-graphics-scene-eg-change-lighting-conditions","title":"How can I alter the graphics scene (e.g., change lighting conditions)?","text":"

When creating a graphics object, you can pass a GraphicsConfiguration object that changes the default values:

C++Python
robot_dart::gui::magnum::GraphicsConfiguration configuration;\n// We can change the width/height of the window (or camera image dimensions)\nconfiguration.width = 1280;\nconfiguration.height = 960;\nconfiguration.title = \"Graphics Tutorial\"; // We can set a title for our window\n// We can change the configuration for shadows\nconfiguration.shadowed = true;\nconfiguration.transparent_shadows = true;\nconfiguration.shadow_map_size = 1024;\n// We can also alter some specifications for the lighting\nconfiguration.max_lights = 3; // maximum number of lights for our scene [default=3]\nconfiguration.specular_strength = 0.25; // strength of the specular component\n// Some extra configuration for the main camera\nconfiguration.draw_main_camera = true;\nconfiguration.draw_debug = true;\nconfiguration.draw_text = true;\n// We can also change the background color [default=black]\nconfiguration.bg_color = Eigen::Vector4d{1.0, 1.0, 1.0, 1.0};\n// Create the graphics object with the configuration as parameter\nauto graphics = std::make_shared<robot_dart::gui::magnum::Graphics>(configuration);\n
configuration = rd.gui.GraphicsConfiguration()\n# We can change the width/height of the window (or camera, dimensions)\nconfiguration.width = 1280\nconfiguration.height = 960\nconfiguration.title = \"Graphics Tutorial\"  # We can set a title for our window\n# We can change the configuration for shadows\nconfiguration.shadowed = True\nconfiguration.transparent_shadows = True\nconfiguration.shadow_map_size = 1024\n# We can also alter some specifications for the lighting\nconfiguration.max_lights = 3  # maximum number of lights for our scene\nconfiguration.specular_strength = 0.25  # strength og the specular component\n#  Some extra configuration for the main camera\nconfiguration.draw_main_camera = True\nconfiguration.draw_debug = True\nconfiguration.draw_text = True\n# We can also change the background color [default = black]\nconfiguration.bg_color = [1., 1., 1., 1.]\n# create the graphics object with the configuration as a parameter\ngraphics = rd.gui.Graphics(configuration)\n

You can disable or enable shadows on the fly as well:

C++Python
// Disable shadows\ngraphics->enable_shadows(false, false);\nsimu.run(1.);\n// Enable shadows only for non-transparent objects\ngraphics->enable_shadows(true, false);\nsimu.run(1.);\n// Enable shadows for transparent objects as well\ngraphics->enable_shadows(true, true);\nsimu.run(1.);\n
# Disable shadows\ngraphics.enable_shadows(False, False)\nsimu.run(1.)\n# Enable shadows only for non-transparent objects\ngraphics.enable_shadows(True, False)\nsimu.run(1.)\n# Enable shadows for transparent objects as well\ngraphics.enable_shadows(True, True)\nsimu.run(1.)\n

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:

C++Python
// Clear Lights\ngraphics->clear_lights();\n
# Clear Lights\ngraphics.clear_lights()\n

Then you must create a custom light material:

C++Python
// Create Light material\nMagnum::Float shininess = 1000.f;\nMagnum::Color4 white = {1.f, 1.f, 1.f, 1.f};\n// ambient, diffuse, specular\nauto custom_material = robot_dart::gui::magnum::gs::Material(white, white, white, shininess);\n
# Clear Light material\nshininess = 1000.\nwhite = magnum.Color4(1., 1., 1., 1.)\n# ambient, diffuse, specular\ncustom_material = rd.gui.Material(white, white, white, shininess)\n

Now you can add on ore more of the following lights:

Point Light:

C++Python
// Create point light\nMagnum::Vector3 position = {0.f, 0.f, 2.f};\nMagnum::Float intensity = 1.f;\nMagnum::Vector3 attenuation_terms = {1.f, 0.f, 0.f};\nauto point_light = robot_dart::gui::magnum::gs::create_point_light(position, custom_material, intensity, attenuation_terms);\ngraphics->add_light(point_light);\n
# Create point light\nposition = magnum.Vector3(0., 0., 2.)\nintensity = 1.\nattenuation_terms = magnum.Vector3(1., 0., 0.)\npoint_light = rd.gui.create_point_light(position, custom_material, intensity, attenuation_terms)\ngraphics.add_light(point_light)\n

Spot Light:

C++Python
// Create spot light\nMagnum::Vector3 position = {0.f, 0.f, 1.f};\nMagnum::Vector3 direction = {-1.f, -1.f, -1.f};\nMagnum::Float intensity = 1.f;\nMagnum::Vector3 attenuation_terms = {1.f, 0.f, 0.f};\nMagnum::Float spot_exponent = M_PI;\nMagnum::Float spot_cut_off = M_PI / 8;\nauto spot_light = robot_dart::gui::magnum::gs::create_spot_light(position, custom_material, direction, spot_exponent, spot_cut_off, intensity, attenuation_terms);\ngraphics->add_light(spot_light);\n
# Create spot light\nposition = magnum.Vector3(0., 0., 1.)\ndirection = magnum.Vector3(-1, -1, -1)\nintensity = 1.\nattenuation_terms = magnum.Vector3(1., 0., 0.)\nspot_exponent = np.pi\nspot_cut_off = np.pi / 8\nspot_light = rd.gui.create_spot_light(position, custom_material, direction, spot_exponent, spot_cut_off, intensity, attenuation_terms)\ngraphics.add_light(spot_light)\n

Directional Light:

C++Python
// Create directional light\nMagnum::Vector3 direction = {-1.f, -1.f, -1.f};\nauto directional_light = robot_dart::gui::magnum::gs::create_directional_light(direction, custom_material);\ngraphics->add_light(directional_light);\n
# Create directional light\ndirection = magnum.Vector3(-1, -1, -1)\ndirectional_light = rd.gui.create_directional_light(direction, custom_material)\ngraphics.add_light(directional_light)\n
"},{"location":"faq/#i-want-to-visualize-a-target-configuration-of-my-robot-is-this-possible","title":"I want to visualize a target configuration of my robot, is this possible?","text":"

Yes this is possible. RobotDART gives the ability to create a clone of your robot that has no physics, no contacts, just visuals:

C++Python
// Add a ghost robot; only visuals, no dynamics, no collision\nauto ghost = robot->clone_ghost();\nsimu.add_robot(ghost);\n
# Add a ghost robot; only visuals, no dynamics, no collision\nghost = robot.clone_ghost()\nsimu.add_robot(ghost)\n
"},{"location":"faq/#how-can-i-control-my-robot","title":"How can I control my robot ?","text":"

PD control

C++Python
// add a PD-controller to the arm\n// set desired positions\nEigen::VectorXd ctrl = robot_dart::make_vector({0., M_PI / 4., 0., -M_PI / 4., 0., M_PI / 2., 0., 0.});\n// add the controller to the robot\nauto controller = std::make_shared<robot_dart::control::PDControl>(ctrl);\nrobot->add_controller(controller);\ncontroller->set_pd(300., 50.);\n
# add a PD-controller to the arm\n# set desired positions\nctrl = [0., np.pi / 4., 0., -np.pi / 4., 0., np.pi / 2., 0., 0.]\n# add the controller to the robot\ncontroller = rd.PDControl(ctrl)\nrobot.add_controller(controller)\ncontroller.set_pd(300., 50.)\n

Simple control

C++Python
auto controller1 = std::make_shared<robot_dart::control::SimpleControl>(ctrl);\nrobot->add_controller(controller1);\n
controller1 = rd.SimpleControl(ctrl)\nrobot.add_controller(controller1)\n

Robot control

C++Python
class MyController : public robot_dart::control::RobotControl {\npublic:\nMyController() : robot_dart::control::RobotControl() {}\nMyController(const Eigen::VectorXd& ctrl, bool full_control) : robot_dart::control::RobotControl(ctrl, full_control) {}\nMyController(const Eigen::VectorXd& ctrl, const std::vector<std::string>& dof_names) : robot_dart::control::RobotControl(ctrl, dof_names) {}\nvoid configure() override\n{\n_active = true;\n}\nEigen::VectorXd calculate(double) override\n{\nauto robot = _robot.lock();\nEigen::VectorXd cmd = 100. * (_ctrl - robot->positions(_controllable_dofs));\nreturn cmd;\n}\nstd::shared_ptr<robot_dart::control::RobotControl> clone() const override\n{\nreturn std::make_shared<MyController>(*this);\n}\n};\n
class MyController(rd.RobotControl):\ndef __init__(self, ctrl, full_control):\nrd.RobotControl.__init__(self, ctrl, full_control)\ndef __init__(self, ctrl, controllable_dofs):\nrd.RobotControl.__init__(self, ctrl, controllable_dofs)\ndef configure(self):\nself._active = True\ndef calculate(self, t):\ntarget = np.array([self._ctrl])\ncmd = 100*(target-self.robot().positions(self._controllable_dofs))\nreturn cmd[0]\n# TO-DO: This is NOT working at the moment!\ndef clone(self):\nreturn MyController(self._ctrl, self._controllable_dofs)\n
"},{"location":"faq/#is-there-a-way-to-control-the-simulation-timestep","title":"Is there a way to control the simulation timestep?","text":"

When creating a RobotDARTSimu object you choose the simulation timestep:

C++Python
// choose time step of 0.001 seconds\nrobot_dart::RobotDARTSimu simu(0.001);\n
# choose time step of 0.001 seconds\nsimu = rd.RobotDARTSimu(0.001)\n

which can later be modified by:

C++Python
// set timestep to 0.005 and update control frequency(bool)\nsimu.set_timestep(0.005, true);\n
# set timestep to 0.005 and update control frequency(bool)\nsimu.set_timestep(0.005, True)\n
"},{"location":"faq/#i-want-to-simulate-a-mars-environment-is-it-possible-to-change-the-gravitational-force-of-the-simulation-environment","title":"I want to simulate a mars environment, is it possible to change the gravitational force of the simulation environment?","text":"

Yes you can modify the gravitational forces 3-dimensional vector of the simulation:

C++Python
// Set gravitational force of mars\nEigen::Vector3d mars_gravity = {0., 0., -3.721};\nsimu.set_gravity(mars_gravity);\n
# set gravitational force of mars\nmars_gravity = [0., 0., -3.721]\nsimu.set_gravity(mars_gravity)\n
"},{"location":"faq/#which-collision-detectors-are-available-what-are-their-differences-how-can-i-choose-between-them","title":"Which collision detectors are available? What are their differences? How can I choose between them?","text":"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:

C++Python
simu.set_collision_detector(\"fcl\"); // collision_detector can be \"dart\", \"fcl\", \"ode\" or \"bullet\" (case does not matter)\n
simu.set_collision_detector(\"fcl\") # collision_detector can be \"dart\", \"fcl\", \"ode\" or \"bullet\" (case does not matter)\n
"},{"location":"faq/#my-robot-does-not-self-collide-how-can-i-change-this","title":"My robot does not self-collide. How can I change this?","text":"

One possible cause may be the fact that self collision is disabled, you can check and change this:

C++Python
if (!robot->self_colliding()) {\nstd::cout << \"Self collision is not enabled\" << std::endl;\n// set self collisions to true and adjacent collisions to false\nrobot->set_self_collision(true, false);\n}\n
if(not robot.self_colliding()):\nprint(\"Self collision is not enabled\")\n# set self collisions to true and adjacent collisions to false\nrobot.set_self_collision(True, False)\n
"},{"location":"faq/#how-can-i-compute-kinematicdynamic-properties-of-my-robot-eg-jacobians-mass-matrix","title":"How can I compute kinematic/dynamic properties of my robot (e.g., Jacobians, Mass Matrix)?","text":"

Kinematic Properties:

C++Python
// Get Joint Positions(Angles)\nauto joint_positions = robot->positions();\n// Get Joint Velocities\nauto joint_vels = robot->velocities();\n// Get Joint Accelerations\nauto joint_accs = robot->accelerations();\n// Get link_name(str) Transformation matrix with respect to the world frame.\nauto eef_tf = robot->body_pose(link_name);\n// Get translation vector from transformation matrix\nauto eef_pos = eef_tf.translation();\n// Get rotation matrix from tranformation matrix\nauto eef_rot = eef_tf.rotation();\n// Get link_name 6d pose vector [logmap(eef_tf.linear()), eef_tf.translation()]\nauto eef_pose_vec = robot->body_pose_vec(link_name);\n// Get link_name 6d velocity vector [angular, cartesian]\nauto eef_vel = robot->body_velocity(link_name);\n// Get link_name 6d acceleration vector [angular, cartesian]\nauto eef_acc = robot->body_acceleration(link_name);\n// Jacobian targeting the origin of link_name(str)\nauto jacobian = robot->jacobian(link_name);\n// Jacobian time derivative\nauto jacobian_deriv = robot->jacobian_deriv(link_name);\n// Center of Mass Jacobian\nauto com_jacobian = robot->com_jacobian();\n// Center of Mass Jacobian Time Derivative\nauto com_jacobian_deriv = robot->com_jacobian_deriv();\n
# Get Joint Positions(Angles)\njoint_positions = robot.positions()\n# Get Joint Velocities\njoint_vels = robot.velocities()\n# Get Joint Accelerations\njoint_accs = robot.accelerations()\n# Get link_name(str) Transformation matrix with respect to the world frame.\neef_tf = robot.body_pose(link_name)\n# Get translation vector from transformation matrix\neef_pos = eef_tf.translation()\n# Get rotation matrix from tranformation matrix\neef_rot = eef_tf.rotation()\n# Get link_name 6d pose vector [logmap(eef_tf.linear()), eef_tf.translation()]\neef_pose_vec = robot.body_pose_vec(link_name)\n# Get link_name 6d velocity vector [angular, cartesian]\neef_vel = robot.body_velocity(link_name)\n# Get link_name 6d acceleration vector [angular, cartesian]\neef_acc = robot.body_acceleration(link_name)\n# Jacobian targeting the origin of link_name(str)\njacobian = robot.jacobian(link_name)\n# Jacobian time derivative\njacobian_deriv = robot.jacobian_deriv(link_name)\n# Center of Mass Jacobian\ncom_jacobian = robot.com_jacobian()\n# Center of Mass Jacobian Time Derivative\ncom_jacobian_deriv = robot.com_jacobian_deriv()\n

Dynamic Properties:

C++Python
// Get Joint Forces\nauto joint_forces = robot->forces();\n// Get link's mass\nauto eef_mass = robot->body_mass(link_name);\n// Mass Matrix of robot\nauto mass_matrix = robot->mass_matrix();\n// Inverse of Mass Matrix\nauto inv_mass_matrix = robot->inv_mass_matrix();\n// Augmented Mass matrix\nauto aug_mass_matrix = robot->aug_mass_matrix();\n// Inverse of Augmented Mass matrix\nauto inv_aug_mass_matrix = robot->inv_aug_mass_matrix();\n// Coriolis Force vector\nauto coriolis = robot->coriolis_forces();\n// Gravity Force vector\nauto gravity = robot->gravity_forces();\n// Combined vector of Coriolis Force and Gravity Force\nauto coriolis_gravity = robot->coriolis_gravity_forces();\n// Constraint Force Vector\nauto constraint_forces = robot->constraint_forces();\n
# Get Joint Forces\njoint_forces = robot.forces()\n# Get link's mass\neef_mass = robot.body_mass(link_name)\n# Mass Matrix of robot\nmass_matrix = robot.mass_matrix()\n# Inverse of Mass Matrix\ninv_mass_matrix = robot.inv_mass_matrix()\n# Augmented Mass matrix\naug_mass_matrix = robot.aug_mass_matrix()\n# Inverse of Augmented Mass matrix\ninv_aug_mass_matrix = robot.inv_aug_mass_matrix()\n# Coriolis Force vector\ncoriolis = robot.coriolis_forces()\n# Gravity Force vector\ngravity = robot.gravity_forces()\n# Combined vector of Coriolis Force and Gravity Force\ncoriolis_gravity = robot.coriolis_gravity_forces()\n# NOT IMPLEMENTED\n# # Constraint Force Vector\n# constraint_forces = robot.constraint_forces()\n
"},{"location":"faq/#is-there-a-way-to-change-the-joint-properties-eg-actuation-friction","title":"Is there a way to change the joint properties (e.g., actuation, friction)?","text":"

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:

C++Python
// Set all DoFs to same actuator\nrobot->set_actuator_types(\"servo\"); // actuator types can be \"servo\", \"torque\", \"velocity\", \"passive\", \"locked\", \"mimic\"\n// You can also set actuator types separately\nrobot->set_actuator_type(\"torque\", \"iiwa_joint_5\");\n
# Set all DoFs to same actuator\n# actuator types can be \"servo\", \"torque\", \"velocity\", \"passive\", \"locked\", \"mimic\"\nrobot.set_actuator_types(\"servo\")\n# You can also set actuator types separately\nrobot.set_actuator_type(\"torque\", \"iiwa_joint_5\")\n

To enable position and velocity limits for the actuators:

C++Python
// \u0395nforce joint position and velocity limits\nrobot->set_position_enforced(true);\n
# \u0395nforce joint position and velocity limits\nrobot.set_position_enforced(True)\n

Every DOF's limits (position, velocity, acceleration, force) can be modified:

C++Python
// Modify Position Limits\nEigen::VectorXd pos_upper_lims(7);\npos_upper_lims << 2.096, 2.096, 2.096, 2.096, 2.096, 2.096, 2.096;\nrobot->set_position_upper_limits(pos_upper_lims, dof_names);\nrobot->set_position_lower_limits(-pos_upper_lims, dof_names);\n// Modify Velocity Limits\nEigen::VectorXd vel_upper_lims(7);\nvel_upper_lims << 1.5, 1.5, 1.5, 1.5, 1.5, 1.5, 1.5;\nrobot->set_velocity_upper_limits(vel_upper_lims, dof_names);\nrobot->set_velocity_lower_limits(-vel_upper_lims, dof_names);\n// Modify Force Limits\nEigen::VectorXd force_upper_lims(7);\nforce_upper_lims << 150, 150, 150, 150, 150, 150, 150;\nrobot->set_force_upper_limits(force_upper_lims, dof_names);\nrobot->set_force_lower_limits(-force_upper_lims, dof_names);\n// Modify Acceleration Limits\nEigen::VectorXd acc_upper_lims(7);\nacc_upper_lims << 1500, 1500, 1500, 1500, 1500, 1500, 1500;\nrobot->set_acceleration_upper_limits(acc_upper_lims, dof_names);\nrobot->set_acceleration_lower_limits(-acc_upper_lims, dof_names);\n
# Modify Position Limits\npos_upper_lims = np.array([2.096, 2.096, 2.096, 2.096, 2.096, 2.096, 2.096])\nrobot.set_position_upper_limits(pos_upper_lims, dof_names)\nrobot.set_position_lower_limits(-1*pos_upper_lims, dof_names)\n# Modify Velocity Limits\nvel_upper_lims = np.array([1.5, 1.5, 1.5, 1.5, 1.5, 1.5, 1.5])\nrobot.set_velocity_upper_limits(vel_upper_lims, dof_names)\nrobot.set_velocity_lower_limits(-1*vel_upper_lims, dof_names)\n# Modify Force Limits\nforce_upper_lims = np.array([150, 150, 150, 150, 150, 150, 150])\nrobot.set_force_upper_limits(force_upper_lims, dof_names)\nrobot.set_force_lower_limits(-1*force_upper_lims, dof_names)\n# Modify Acceleration Limits\nacc_upper_lims = np.array([1500, 1500, 1500, 1500, 1500, 1500, 1500])\nrobot.set_acceleration_upper_limits(acc_upper_lims, dof_names)\nrobot.set_acceleration_lower_limits(-1*acc_upper_lims, dof_names)\n

You can also modify the damping coefficients, coulomb frictions and spring stiffness of every DOF:

C++Python
// Modify Damping Coefficients\nstd::vector<double> damps = {0.4, 0.4, 0.4, 0.4, 0.4, 0.4, 0.4};\nrobot->set_damping_coeffs(damps, dof_names);\n// Modify Coulomb Frictions\nstd::vector<double> cfrictions = {0.001, 0.001, 0.001, 0.001, 0.001, 0.001, 0.001};\nrobot->set_coulomb_coeffs(cfrictions, dof_names);\n// Modify  Spring Stiffness\nstd::vector<double> stiffnesses = {0.001, 0.001, 0.001, 0.001, 0.001, 0.001, 0.001};\nrobot->set_spring_stiffnesses(stiffnesses, dof_names);\n
# Modify Damping Coefficients\ndamps = [0.4, 0.4, 0.4, 0.4, 0.4, 0.4, 0.4]\nrobot.set_damping_coeffs(damps, dof_names)\n# Modify Coulomb Frictions\ncfrictions = [0.001, 0.001, 0.001, 0.001, 0.001, 0.001, 0.001]\nrobot.set_coulomb_coeffs(cfrictions, dof_names)\n# Modify  Spring Stiffness\nstiffnesses = [0.001, 0.001, 0.001, 0.001, 0.001, 0.001, 0.001]\nrobot.set_spring_stiffnesses(stiffnesses, dof_names)\n
"},{"location":"faq/#what-are-the-supported-sensors-how-can-i-use-an-imu","title":"What are the supported sensors? How can I use an IMU?","text":"

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).

"},{"location":"faq/#torque-sensor","title":"Torque sensor","text":"

Torque sensors can be added to every joint of the robot:

C++Python
// Add torque sensors to the robot\nint ct = 0;\nstd::vector<std::shared_ptr<robot_dart::sensor::Torque>> tq_sensors(robot->num_dofs());\nfor (const auto& joint : robot->dof_names())\ntq_sensors[ct++] = simu.add_sensor<robot_dart::sensor::Torque>(robot, joint, 1000);\n
# Add torque sensors to the robot\ntq_sensors = np.empty(robot.num_dofs(), dtype=rd.sensor.Torque)\nct = 0\nfor joint in robot.dof_names():\nsimu.add_sensor(rd.sensor.Torque(robot, joint, 1000))\ntq_sensors[ct] = simu.sensors()[-1]\nct += 1\n

Torque sensors measure the torque \\(\\tau \\in \\rm I\\!R^n\\) of the attached joint (where \\(n\\) is the DOFs of the joint):

C++Python
// vector that contains the torque measurement for every joint (scalar)\nEigen::VectorXd torques_measure(robot->num_dofs());\nfor (const auto& tq_sens : tq_sensors)\ntorques_measure.block<1, 1>(ct++, 0) = tq_sens->torques();\n
# vector that contains the torque measurement for every joint (scalar)\ntorques_measure = np.empty(robot.num_dofs())\nct = 0\nfor tq_sens in tq_sensors:\ntorques_measure[ct] = tq_sens.torques()\nct += 1\n
"},{"location":"faq/#force-torque-sensor","title":"Force-Torque sensor","text":"

Force-Torque sensors can be added to every joint of the robot:

C++Python
// Add force-torque sensors to the robot\nct = 0;\nstd::vector<std::shared_ptr<robot_dart::sensor::ForceTorque>> f_tq_sensors(robot->num_dofs());\nfor (const auto& joint : robot->dof_names())\nf_tq_sensors[ct++] = simu.add_sensor<robot_dart::sensor::ForceTorque>(robot, joint, 1000, \"parent_to_child\");\n
# Add force-torque sensors to the robot\nf_tq_sensors = np.empty(robot.num_dofs(), dtype=rd.sensor.ForceTorque)\nct = 0\nfor joint in robot.dof_names():\nsimu.add_sensor(rd.sensor.ForceTorque(\nrobot, joint, 1000, \"parent_to_child\"))\nf_tq_sensors[ct] = simu.sensors()[-1]\nprint(f_tq_sensors)\nct += 1\n

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:

C++Python
//  matrix that contains the torque measurement for every joint (3d vector)\nEigen::MatrixXd ft_torques_measure(robot->num_dofs(), 3);\n//  matrix that contains the force measurement for every joint (3d vector)\nEigen::MatrixXd ft_forces_measure(robot->num_dofs(), 3);\n//  matrix that contains the wrench measurement for every joint (6d vector)[torque, force]\nEigen::MatrixXd ft_wrench_measure(robot->num_dofs(), 6);\nct = 0;\nfor (const auto& f_tq_sens : f_tq_sensors) {\nft_torques_measure.block<1, 3>(ct, 0) = f_tq_sens->torque();\nft_forces_measure.block<1, 3>(ct, 0) = f_tq_sens->force();\nft_wrench_measure.block<1, 6>(ct, 0) = f_tq_sens->wrench();\nct++;\n}\n
#  matrix that contains the torque measurement for every joint (3d vector)\nft_torques_measure = np.empty([robot.num_dofs(), 3])\n#  matrix that contains the force measurement for every joint (3d vector)\nft_forces_measure = np.empty([robot.num_dofs(), 3])\n#  matrix that contains the wrench measurement for every joint (6d vector)[torque, force]\nft_wrench_measure = np.empty([robot.num_dofs(), 6])\nct = 0\nfor f_tq_sens in f_tq_sensors:\nft_torques_measure[ct, :] = f_tq_sens.torque()\nft_forces_measure[ct, :] = f_tq_sens.force()\nft_wrench_measure[ct, :] = f_tq_sens.wrench()\nct += 1\n
"},{"location":"faq/#imu-sensor","title":"IMU sensor","text":"

IMU sensors can be added to every link of the robot:

C++Python
// Add IMU sensors to the robot\nct = 0;\nstd::vector<std::shared_ptr<robot_dart::sensor::IMU>> imu_sensors(robot->num_bodies());\nfor (const auto& body_node : robot->body_names()) {\n// _imu(std::make_shared<sensor::IMU>(sensor::IMUConfig(body_node(\"head\"), frequency))),\nimu_sensors[ct++] = simu.add_sensor<robot_dart::sensor::IMU>(robot_dart::sensor::IMUConfig(robot->body_node(body_node), 1000));\n}\n
# Add IMU sensors to the robot\nct = 0\nimu_sensors = np.empty(robot.num_bodies(), dtype=rd.sensor.IMU)\nfor body_node in robot.body_names():\nsimu.add_sensor(rd.sensor.IMU(\nrd.sensor.IMUConfig(robot.body_node(body_node), 1000)))\nimu_sensors[ct] = simu.sensors()[-1]\nct += 1\n

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:

C++Python
Eigen::MatrixXd imu_angular_positions_measure(robot->num_bodies(), 3);\nEigen::MatrixXd imu_angular_velocities_measure(robot->num_bodies(), 3);\nEigen::MatrixXd imu_linear_acceleration_measure(robot->num_bodies(), 3);\nct = 0;\nfor (const auto& imu_sens : imu_sensors) {\nimu_angular_positions_measure.block<1, 3>(ct, 0) = imu_sens->angular_position_vec();\nimu_angular_velocities_measure.block<1, 3>(ct, 0) = imu_sens->angular_velocity();\nimu_linear_acceleration_measure.block<1, 3>(ct, 0) = imu_sens->linear_acceleration();\nct++;\n}\n
imu_angular_positions_measure = np.empty([robot.num_bodies(), 3])\nimu_angular_velocities_measure = np.empty([robot.num_bodies(), 3])\nimu_linear_acceleration_measure = np.empty([robot.num_bodies(), 3])\nct = 0\nfor imu_sens in imu_sensors:\nimu_angular_positions_measure[ct,:] = imu_sens.angular_position_vec()\nimu_angular_velocities_measure[ct, :] = imu_sens.angular_velocity()\nimu_linear_acceleration_measure[ct,:] = imu_sens.linear_acceleration()\nct += 1\n
"},{"location":"faq/#rgb-sensor","title":"RGB sensor","text":"

Any camera can be used as an RGB sensor:

C++Python
// a nested std::vector (w*h*3) of the last image taken can be retrieved\nauto rgb_image = camera->image();\n
# a nested array (w*h*3) of the last image taken can be retrieved\nrgb_image = camera.image()\n

We can easily save the image and/or transform it to grayscale:

C++Python
// a nested std::vector (w*h*3) of the last image taken can be retrieved\nauto rgb_image = camera->image();\n
# a nested array (w*h*3) of the last image taken can be retrieved\nrgb_image = camera.image()\n
"},{"location":"faq/#rgb_d-sensor","title":"RGB_D sensor","text":"

Any camera can also be configured to also record depth:

C++Python
camera->camera().record(true, true); // cameras are recording color images by default, enable depth images as well for this example\n
# cameras are recording color images by default, enable depth images as well for this example\ncamera.camera().record(True, True)\n

We can then read the RGB and depth images:

C++Python
// get the depth image from a camera\n// with a version for visualization or bigger differences in the output\nauto rgb_d_image = camera->depth_image();\n// and the raw values that can be used along with the camera parameters to transform the image to point-cloud\nauto rgb_d_image_raw = camera->raw_depth_image();\n
# get the depth image from a camera\n# with a version for visualization or bigger differences in the output\nrgb_d_image = camera.depth_image()\n# and the raw values that can be used along with the camera parameters to transform the image to point-cloud\nrgb_d_image_raw = camera.raw_depth_image()\n

We can save the depth images as well:

C++Python
robot_dart::gui::save_png_image(\"camera-depth.png\", rgb_d_image);\nrobot_dart::gui::save_png_image(\"camera-depth-raw.png\", rgb_d_image_raw);\n
rd.gui.save_png_image(\"camera-depth.png\", rgb_d_image)\nrd.gui.save_png_image(\"camera-depth-raw.png\", rgb_d_image_raw)\n
"},{"location":"faq/#how-can-i-spawn-multiple-robots-in-parallel","title":"How can I spawn multiple robots in parallel?","text":""},{"location":"faq/#robot-pool-only-in-c","title":"Robot Pool (only in C++)","text":"

The best way to do so is to create a Robot pool. With a robot pool you:

Let's see a more practical example:

C++
#include <robot_dart/robot_pool.hpp>\n
C++
namespace pool {\n// This function should load one robot: here we load Talos\ninline std::shared_ptr<robot_dart::Robot> robot_creator()\n{\nreturn std::make_shared<robot_dart::robots::Talos>();\n}\n// To create the object we need to pass the robot_creator function and the number of maximum parallel threads\nrobot_dart::RobotPool robot_pool(robot_creator, NUM_THREADS);\n} // namespace pool\n

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.

C++
// for the example, we run NUM_THREADS threads of eval_robot()\nstd::vector<std::thread> threads(NUM_THREADS * 2); // *2 to see some reuse\nfor (size_t i = 0; i < threads.size(); ++i)\nthreads[i] = std::thread(eval_robot, i); // eval_robot is the function that uses the robot\n
C++
inline void eval_robot(int i)\n{\n// We get one available robot\nauto robot = pool::robot_pool.get_robot();\nstd::cout << \"Robot \" << i << \" got [\" << robot->skeleton() << \"]\" << std::endl;\n/// --- some robot_dart code ---\nsimulate_robot(robot);\n// --- do something with the result\nstd::cout << \"End of simulation \" << i << std::endl;\n// CRITICAL : free your robot !\npool::robot_pool.free_robot(robot);\nstd::cout << \"Robot \" << i << \" freed!\" << std::endl;\n}\n
"},{"location":"faq/#python","title":"Python","text":"

We have not implemented this feature in Python yet. One can emulate the RobotPool behavior or create a custom parallel robot loader.

"},{"location":"faq/#i-need-to-simulate-many-worlds-with-camera-sensors-in-parallel-how-can-i-do-this","title":"I need to simulate many worlds with camera sensors in parallel. How can I do this?","text":"

Below you can find an example showcasing the use of many worlds with camera sensors in parallel.

C++Python
// Load robot from URDF\nauto global_robot = std::make_shared<robot_dart::robots::Iiwa>();\nstd::vector<std::thread> workers;\n// Set maximum number of parallel GL contexts (this is GPU-dependent)\nrobot_dart::gui::magnum::GlobalData::instance()->set_max_contexts(4);\n// We want 15 parallel simulations with different GL context each\nsize_t N_workers = 15;\nstd::mutex mutex;\nsize_t id = 0;\n// Launch the workers\nfor (size_t i = 0; i < N_workers; i++) {\nworkers.push_back(std::thread([&] {\nmutex.lock();\nsize_t index = id++;\nmutex.unlock();\n// Get the GL context -- this is a blocking call\n// will wait until one GL context is available\n// get_gl_context(gl_context); // this call will not sleep between failed queries\nget_gl_context_with_sleep(gl_context, 20); // this call will sleep 20ms between each failed query\n// Do the simulation\nauto robot = global_robot->clone();\nrobot_dart::RobotDARTSimu simu(0.001);\nEigen::VectorXd ctrl = robot_dart::make_vector({0., M_PI / 3., 0., -M_PI / 4., 0., 0., 0.});\nauto controller = std::make_shared<robot_dart::control::PDControl>(ctrl);\nrobot->add_controller(controller);\ncontroller->set_pd(300., 50.);\n// Magnum graphics\nrobot_dart::gui::magnum::GraphicsConfiguration configuration = robot_dart::gui::magnum::WindowlessGraphics::default_configuration();\nconfiguration.width = 1024;\nconfiguration.height = 768;\nauto graphics = std::make_shared<robot_dart::gui::magnum::WindowlessGraphics>(configuration);\nsimu.set_graphics(graphics);\n// Position the camera differently for each thread to visualize the difference\ngraphics->look_at({0.4 * index, 3.5 - index * 0.1, 2.}, {0., 0., 0.25});\n// record images from main camera/graphics\n// graphics->set_recording(true); // WindowlessGLApplication records images by default\nsimu.add_robot(robot);\nsimu.run(6);\n// Save the image for verification\nrobot_dart::gui::save_png_image(\"camera_\" + std::to_string(index) + \".png\",\ngraphics->image());\n// Release the GL context for another thread to use\nrelease_gl_context(gl_context);\n}));\n}\n// Wait for all the workers\nfor (size_t i = 0; i < workers.size(); i++) {\nworkers[i].join();\n}\n
robot = rd.Robot(\"arm.urdf\", \"arm\", False)\nrobot.fix_to_world()\ndef test():\npid = os.getpid()\nii = pid%15\n# create the controller\npdcontrol = rd.PDControl([0.0, 1.0, -1.5, 1.0], False)\n# clone the robot\ngrobot = robot.clone()\n# add the controller to the robot\ngrobot.add_controller(pdcontrol, 1.)\npdcontrol.set_pd(200., 20.)\n# create the simulation object\nsimu = rd.RobotDARTSimu(0.001)\n# set the graphics\ngraphics = rd.gui.WindowlessGraphics()\nsimu.set_graphics(graphics)\ngraphics.look_at([0.4 * ii, 3.5 - ii * 0.1, 2.], [0., 0., 0.25], [0., 0., 1.])\n# add the robot and the floor\nsimu.add_robot(grobot)\nsimu.add_checkerboard_floor()\n# run\nsimu.run(20.)\n# save last frame for visualization purposes\nimg = graphics.image()\nrd.gui.save_png_image('camera-' + str(ii) + '.png', img)\n# helper function to run in parallel\ndef runInParallel(N):\nproc = []\nfor i in range(N):\n# rd.gui.run_with_gl_context accepts 2 parameters:\n#    (func, wait_time_in_ms)\n#    the func needs to be of the following format: void(), aka no return, no arguments\np = Process(target=rd.gui.run_with_gl_context, args=(test, 20))\np.start()\nproc.append(p)\nfor p in proc:\np.join()\nprint('Running parallel evaluations')\nN = 15\nstart = timer()\nrunInParallel(N)\nend = timer()\nprint('Time:', end-start)\n

In C++ you are also able to pre-allocate a custom number of OpenGL contexts so that you can take advantage of stronger GPUs.

"},{"location":"faq/#i-do-not-know-how-to-use-waf-how-can-i-detect-robotdart-from-cmake","title":"I do not know how to use waf. How can I detect RobotDART from CMake?","text":"

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:

cmake_minimum_required(VERSION 3.10 FATAL_ERROR)\nproject(robot_dart_example)\n# we ask for Magnum because we want to build the graphics\nfind_package(RobotDART REQUIRED OPTIONAL_COMPONENTS Magnum)\nadd_executable(robot_dart_example example.cpp)\ntarget_link_libraries(robot_dart_example\nRobotDART::Simu\n)\nif(RobotDART_Magnum_FOUND)\nadd_executable(robot_dart_example_graphics example.cpp)\ntarget_link_libraries(robot_dart_example_graphics\nRobotDART::Simu\nRobotDART::Magnum\n)\nendif()\n
"},{"location":"faq/#where-can-i-find-complete-working-examples-for-either-c-or-python","title":"Where can I find complete working examples for either c++ or python?","text":"

C++ examples

Python examples

"},{"location":"install/","title":"Manual Installation","text":""},{"location":"install/#manual-installation-of-robotdart","title":"Manual Installation of RobotDART","text":"

For the quick installation manual, see the quick installation page.

"},{"location":"install/#dependencies","title":"Dependencies","text":""},{"location":"install/#required","title":"Required","text":""},{"location":"install/#optional","title":"Optional","text":""},{"location":"install/#installation-of-the-dependencies","title":"Installation of the dependencies","text":"

Note: The following instructions are high-level and assume people with some experience in building/installing software.

"},{"location":"install/#installing-system-wide-packages","title":"Installing system-wide packages","text":"

For Ubuntu-based distributions (>=20.04) we should use the following commands:

sudo apt-get update\nsudo apt-get install build-essential cmake pkg-config git libboost-regex-dev libboost-system-dev libboost-test-dev pybind11-dev\nsudo apt-get install libdart-all-dev\n

For OSX with brew:

brew install dartsim\n
"},{"location":"install/#installing-magnum","title":"Installing Magnum","text":"

Magnum depends on Corrade and we are going to use a few plugins and extras from the library. We are also going to use Glfw and Glx for the back-end. Follow the instrutions below:

#installation of Glfw and OpenAL\n# Ubuntu\nsudo apt-get install libglfw3-dev libglfw3 libassimp-dev libopenal-dev libglfw3-dev libsdl2-dev libopenexr-dev libdevil-dev libpng-dev libfaad-dev libfreetype6-dev\n# Mac OSX\nbrew install glfw3 openal-soft assimp\n\n# installation of Corrade\ncd /path/to/tmp/folder\ngit clone https://github.com/mosra/corrade.git\ncd corrade\nmkdir build && cd build\ncmake -DCMAKE_BUILD_TYPE=Release ..\nmake -j\nsudo make install\n\n# installation of Magnum\ncd /path/to/tmp/folder\ngit clone https://github.com/mosra/magnum.git\ncd magnum\nmkdir build && cd build\n# Ubuntu\ncmake -DCMAKE_BUILD_TYPE=Release -DWITH_AUDIO=ON -DWITH_DEBUGTOOLS=ON -DWITH_GL=ON -DWITH_MESHTOOLS=ON -DWITH_PRIMITIVES=ON -DWITH_SCENEGRAPH=ON -DWITH_SHADERS=ON -DWITH_TEXT=ON -DWITH_TEXTURETOOLS=ON -DWITH_TRADE=ON -DWITH_GLFWAPPLICATION=ON -DWITH_WINDOWLESSEGLAPPLICATION=ON -DWITH_OPENGLTESTER=ON -DWITH_ANYAUDIOIMPORTER=ON -DWITH_ANYIMAGECONVERTER=ON -DWITH_ANYIMAGEIMPORTER=ON -DWITH_ANYSCENEIMPORTER=ON -DWITH_MAGNUMFONT=ON -DWITH_OBJIMPORTER=ON -DWITH_TGAIMPORTER=ON -DWITH_WAVAUDIOIMPORTER=ON -DTARGET_EGL=ON .. # this will enable almost all features of Magnum that are not necessarily needed for robot_dart (please refer to the documentation of Magnum for more details on selecting only the ones that you need)\n# Mac OSX\ncmake -DCMAKE_BUILD_TYPE=Release -DWITH_AUDIO=ON -DWITH_DEBUGTOOLS=ON -DWITH_GL=ON -DWITH_MESHTOOLS=ON -DWITH_PRIMITIVES=ON -DWITH_SCENEGRAPH=ON -DWITH_SHADERS=ON -DWITH_TEXT=ON -DWITH_TEXTURETOOLS=ON -DWITH_TRADE=ON -DWITH_GLFWAPPLICATION=ON -DWITH_WINDOWLESSCGLAPPLICATION=ON -DWITH_OPENGLTESTER=ON -DWITH_ANYAUDIOIMPORTER=ON -DWITH_ANYIMAGECONVERTER=ON -DWITH_ANYIMAGEIMPORTER=ON -DWITH_ANYSCENEIMPORTER=ON -DWITH_MAGNUMFONT=ON -DWITH_OBJIMPORTER=ON -DWITH_TGAIMPORTER=ON -DWITH_WAVAUDIOIMPORTER=ON .. # this will enable almost all features of Magnum that are not necessarily needed for robot_dart (please refer to the documentation of Magnum for more details on selecting only the ones that you need)\nmake -j\nsudo make install\n\n# installation of Magnum Plugins\ncd /path/to/tmp/folder\ngit clone https://github.com/mosra/magnum-plugins.git\ncd magnum-plugins\nmkdir build && cd build\ncmake -DCMAKE_BUILD_TYPE=Release -DWITH_ASSIMPIMPORTER=ON -DWITH_DDSIMPORTER=ON -DWITH_JPEGIMPORTER=ON -DWITH_OPENGEXIMPORTER=ON -DWITH_PNGIMPORTER=ON -DWITH_TINYGLTFIMPORTER=ON -DWITH_STBTRUETYPEFONT=ON .. # this will enable quite a few Magnum Plugins that are not necessarily needed for robot_dart (please refer to the documentation of Magnum for more details on selecting only the ones that you need)\nmake -j\nsudo make install\n\n# installation of Magnum DART Integration (DART needs to be installed) and Eigen Integration\ncd /path/to/tmp/folder\ngit clone https://github.com/mosra/magnum-integration.git\ncd magnum-integration\nmkdir build && cd build\ncmake -DCMAKE_BUILD_TYPE=Release -DWITH_DART=ON -DWITH_EIGEN=ON ..\nmake -j\nsudo make install\n
"},{"location":"install/#compilation-and-running-the-examples","title":"Compilation and running the examples","text":"

The compilation of the library is straight-forward:

To build the examples, execute this: ./waf examples

Now you can run the examples. For example, to run the arm example you need to type the following: ./build/arm (or ./build/arm_plain to run it without graphics).

"},{"location":"install/#installing-the-library","title":"Installing the library","text":"

To install the library (assuming that you have already compiled it), you need only to run:

By default the library will be installed in /usr/local/lib (for this maybe sudo ./waf install might be needed) and a static library will be generated. You can change the defaults as follows:

In short, with --prefix you can change the directory where the library will be installed and if --shared is present a shared library will be created instead of a static one.

"},{"location":"install/#compiling-the-python-bindings","title":"Compiling the python bindings","text":"

For the python bindings of robot_dart, we need numpy to be installed, pybind11 and the python bindings of DART (dartpy).

For numpy one can install it with pip or standard packages. dartpy should be installed via the packages above. If not, please see the installation instructions on the main DART website.

Then the compilation of robot_dart is almost identical as before:

To run the python examples (for the python examples you need to have enabled the graphics, that is, install Magnum library), run:

"},{"location":"install/#common-issues-with-python-bindings","title":"Common Issues with Python bindings","text":"

One of the most common issue with the python bindings is the fact that DART bindings might be compiled and installed for python 3 and the robot_dart ones for python 2. To force the usage of python 3 for robot_dart, you use python3 ./waf instead of just ./waf in all the commands above.

"},{"location":"quick_install/","title":"Installation","text":""},{"location":"quick_install/#scripts-for-quick-installation-of-robotdart","title":"Scripts for Quick Installation of RobotDART","text":"

In this page we provide standalone scripts for installing RobotDART for Ubuntu (>=20.04) and OSX. The scripts will install all the required dependencies and RobotDART. Notably, all dependencies that need to be compiled by source and RobotDART will be installed inside the /opt folder. This way, one can be rest assured that their system will be clean.

"},{"location":"quick_install/#ubuntu-2004","title":"Ubuntu >=20.04","text":"

To quickly install RobotDART on Ubuntu >=20.04, we just need to run ./scripts/install_ubuntu.sh from the root of the repo. In more detail:

This will install everything needed! Once the script is successfully executed, one should add the following to their ~/.bashrc or ~/.zshrc file (you may need to swap the python version to yours1):

export PATH=/opt/magnum/bin:$PATH\nexport LD_LIBRARY_PATH=/opt/magnum/lib:/opt/robot_dart/lib:$LD_LIBRARY_PATH\nexport PYTHONPATH=/opt/robot_dart/lib/python3.10/site-packages:$PYTHONPATH\n
"},{"location":"quick_install/#osx","title":"OSX","text":"

Coming soon

  1. You can run python --version to see your version. We only keep the major.minor (ignoring the patch version)\u00a0\u21a9

"},{"location":"robots/","title":"Supported robots","text":""},{"location":"robots/#supported-robots","title":"Supported robots","text":"

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()):

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.

"},{"location":"robots/#talos-pal-robotics","title":"Talos (PAL Robotics)","text":"

Talos is a humanoid robot made by PAL Robotics.

We have two URDF files:

Load Talos

C++
auto robot = std::make_shared<robot_dart::robots::Talos>();\n
Python
robot = rd.Talos()\n

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.

Load Talos Fast

C++
// load talos fast\nauto robot = std::make_shared<robot_dart::robots::TalosFastCollision>();\n
Python
robot = rd.TalosFastCollision()\n

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.

"},{"location":"robots/#panda-franka-emika","title":"Panda (Franka Emika)","text":"

The Franka is a modern manipulator made by Franka Emika Panda. It is commonly found in many robotics labs.

Load Franka

C++
auto robot = std::make_shared<robot_dart::robots::Franka>();\n
Python
robot = rd.Franka()\n
"},{"location":"robots/#lbr-iiwa-kuka","title":"LBR iiwa (KUKA)","text":"

The LBR iiwa is manufactured by KUKA. It is similar to the Panda and is also very common in robotics labs.

Load Iiwa

C++
auto robot = std::make_shared<robot_dart::robots::Iiwa>();\n
Python
robot = rd.Iiwa()\n
"},{"location":"robots/#icub-iit","title":"iCub (IIT)","text":"

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.

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

C++
auto robot = std::make_shared<robot_dart::robots::ICub>();\n// Set actuator types to VELOCITY motors so that they stay in position without any controller\nrobot->set_actuator_types(\"velocity\");\nrobot_dart::RobotDARTSimu simu(0.001);\nsimu.set_collision_detector(\"fcl\");\n
Python
robot = rd.ICub()\n# Set actuator types to VELOCITY motors so that they stay in position without any controller\nrobot.set_actuator_types(\"velocity\")\nsimu = rd.RobotDARTSimu(0.001)\nsimu.set_collision_detector(\"fcl\")\n

Print IMU sensor measurements

C++
std::cout << \"Angular    Position: \" << robot->imu().angular_position_vec().transpose().format(fmt) << std::endl;\nstd::cout << \"Angular    Velocity: \" << robot->imu().angular_velocity().transpose().format(fmt) << std::endl;\nstd::cout << \"Linear Acceleration: \" << robot->imu().linear_acceleration().transpose().format(fmt) << std::endl;\nstd::cout << \"=================================\" << std::endl;\n
Python
print(\"Angular    Position: \",  robot.imu().angular_position_vec().transpose())\nprint(\"Angular    Velocity: \",  robot.imu().angular_velocity().transpose())\nprint(\"Linear Acceleration: \",  robot.imu().linear_acceleration().transpose())\nprint(\"=================================\" )\n

Print Force-Torque sensor measurements

C++
std::cout << \"FT ( force): \" << robot->ft_foot_left().force().transpose().format(fmt) << std::endl;\nstd::cout << \"FT (torque): \" << robot->ft_foot_left().torque().transpose().format(fmt) << std::endl;\nstd::cout << \"=================================\" << std::endl;\n
Python
print(\"FT ( force): \",  robot.ft_foot_left().force().transpose())\nprint(\"FT (torque): \",  robot.ft_foot_left().torque().transpose())\nprint(\"=================================\")\n
"},{"location":"robots/#unitree-a1","title":"Unitree A1","text":"

A1 is a quadruped robot made by the Unitree Robotics.

Load A1

C++
auto robot = std::make_shared<robot_dart::robots::A1>();\n
Python
robot = rd.A1()\n

Print IMU sensor measurements

C++
std::cout << \"Angular    Position: \" << robot->imu().angular_position_vec().transpose().format(fmt) << std::endl;\nstd::cout << \"Angular    Velocity: \" << robot->imu().angular_velocity().transpose().format(fmt) << std::endl;\nstd::cout << \"Linear Acceleration: \" << robot->imu().linear_acceleration().transpose().format(fmt) << std::endl;\nstd::cout << \"=================================\" << std::endl;\n
Python
print( \"Angular    Position: \", robot.imu().angular_position_vec().transpose())\nprint( \"Angular    Velocity: \", robot.imu().angular_velocity().transpose())\nprint( \"Linear Acceleration: \", robot.imu().linear_acceleration().transpose())\nprint( \"=================================\")\n

Add a depth camera on the head

How can I attach a camera to a moving link?

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.

"},{"location":"robots/#dynamixel-based-hexapod-robot-inria-and-others","title":"Dynamixel-based hexapod robot (Inria and others)","text":"

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).

Load Hexapod

C++
auto robot = std::make_shared<robot_dart::robots::Hexapod>();\n
Python
robot = rd.Hexapod()\n

Load Pexod

C++
auto robot = std::make_shared<robot_dart::Robot>(\"pexod.urdf\");\n
Python
robot = rd.Robot(\"pexod.urdf\");\n
"},{"location":"robots/#simple-arm","title":"Simple arm","text":"

Load Simple Arm

C++
auto robot = std::make_shared<robot_dart::robots::Arm>();\n
Python
robot = rd.Arm()\n
"},{"location":"robots/#loading-custom-robots","title":"Loading Custom Robots","text":"

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

C++
    auto your_robot = std::make_shared<robot_dart::Robot>(\"path/to/model.urdf\");\n
Python
    your_robot = robot_dart.Robot(\"path/to/model.urdf\")\n

Load custom Robot with packages (e.g STL, DAE meshes)

C++
    std::vector<std::pair<std::string, std::string>> your_model_packages = ('model', 'path/to/model/dir');\nauto your_robot = std::make_shared<robot_dart::Robot>(\"path/to/model.urdf\", your_model_packages, \"packages\");\n
Python
    your_model_packages = [(\"model\", \"path/to/model/dir\")]\nyour_robot = robot_dart.Robot(\"path/to/model.urdf\", your_model_packages)\n
"},{"location":"api/annotated/","title":"Class List","text":"

Here are the classes, structs, unions and interfaces with brief descriptions:

"},{"location":"api/files/","title":"File List","text":"

Here is a list of all files with brief descriptions:

"},{"location":"api/namespaceMagnum/","title":"Namespace Magnum","text":"

Namespace List > Magnum

"},{"location":"api/namespaceMagnum/#namespaces","title":"Namespaces","text":"Type Name namespace GL namespace Platform namespace SceneGraph namespace Shaders

The documentation for this class was generated from the following file robot_dart/gui/magnum/gs/create_compatibility_shader.hpp

"},{"location":"api/namespaceMagnum_1_1GL/","title":"Namespace Magnum::GL","text":"

Namespace List > Magnum > GL

The documentation for this class was generated from the following file [generated]

"},{"location":"api/namespaceMagnum_1_1Platform/","title":"Namespace Magnum::Platform","text":"

Namespace List > Magnum > Platform

The documentation for this class was generated from the following file [generated]

"},{"location":"api/namespaceMagnum_1_1SceneGraph/","title":"Namespace Magnum::SceneGraph","text":"

Namespace List > Magnum > SceneGraph

The documentation for this class was generated from the following file [generated]

"},{"location":"api/namespaceMagnum_1_1Shaders/","title":"Namespace Magnum::Shaders","text":"

Namespace List > Magnum > Shaders

"},{"location":"api/namespaceMagnum_1_1Shaders/#namespaces","title":"Namespaces","text":"Type Name namespace Implementation

The documentation for this class was generated from the following file robot_dart/gui/magnum/gs/create_compatibility_shader.hpp

"},{"location":"api/namespaceMagnum_1_1Shaders_1_1Implementation/","title":"Namespace Magnum::Shaders::Implementation","text":"

Namespace List > Magnum > Shaders > Implementation

"},{"location":"api/namespaceMagnum_1_1Shaders_1_1Implementation/#public-functions","title":"Public Functions","text":"Type Name GL::Shader createCompatibilityShader (const Utility::Resource & rs, GL::Version version, GL::Shader::Type type)"},{"location":"api/namespaceMagnum_1_1Shaders_1_1Implementation/#public-functions-documentation","title":"Public Functions Documentation","text":""},{"location":"api/namespaceMagnum_1_1Shaders_1_1Implementation/#function-createcompatibilityshader","title":"function createCompatibilityShader","text":"
inline GL::Shader Magnum::Shaders::Implementation::createCompatibilityShader (\nconst Utility::Resource & rs,\nGL::Version version,\nGL::Shader::Type type\n) 

The documentation for this class was generated from the following file robot_dart/gui/magnum/gs/create_compatibility_shader.hpp

"},{"location":"api/namespacedart/","title":"Namespace dart","text":"

Namespace List > dart

"},{"location":"api/namespacedart/#namespaces","title":"Namespaces","text":"Type Name namespace collision namespace dynamics

The documentation for this class was generated from the following file robot_dart/gui/magnum/drawables.hpp

"},{"location":"api/namespacedart_1_1collision/","title":"Namespace dart::collision","text":"

Namespace List > dart > collision

The documentation for this class was generated from the following file [generated]

"},{"location":"api/namespacedart_1_1dynamics/","title":"Namespace dart::dynamics","text":"

Namespace List > dart > dynamics

The documentation for this class was generated from the following file robot_dart/gui/magnum/drawables.hpp

"},{"location":"api/namespacerobot__dart/","title":"Namespace robot_dart","text":"

Namespace List > robot_dart

"},{"location":"api/namespacerobot__dart/#namespaces","title":"Namespaces","text":"Type Name namespace collision_filter namespace control namespace detail namespace gui namespace robots namespace sensor namespace simu"},{"location":"api/namespacerobot__dart/#classes","title":"Classes","text":"Type Name class Assertion class Robot class RobotDARTSimu class RobotPool class Scheduler"},{"location":"api/namespacerobot__dart/#public-attributes","title":"Public Attributes","text":"Type Name auto body_node_get_friction_coeff = = {
    return body-&gt;getFrictionCoeff();\n\n}<br> |\n

| auto | body_node_get_restitution_coeff = = {

    return body-&gt;getRestitutionCoeff();\n\n}<br> |\n

| auto | body_node_set_friction_coeff = = {

    body-&gt;setFrictionCoeff(value);\n\n}<br> |\n

| auto | body_node_set_restitution_coeff = = {

    body-&gt;setRestitutionCoeff(value);\n\n}<br> |\n
"},{"location":"api/namespacerobot__dart/#public-functions","title":"Public Functions","text":"Type Name Eigen::Isometry3d make_tf (const Eigen::Matrix3d & R, const Eigen::Vector3d & t) Eigen::Isometry3d make_tf (const Eigen::Matrix3d & R) Eigen::Isometry3d make_tf (const Eigen::Vector3d & t) Eigen::Isometry3d make_tf (std::initializer_list< double > args) Eigen::VectorXd make_vector (std::initializer_list< double > args)"},{"location":"api/namespacerobot__dart/#public-attributes-documentation","title":"Public Attributes Documentation","text":""},{"location":"api/namespacerobot__dart/#variable-body_node_get_friction_coeff","title":"variable body_node_get_friction_coeff","text":"
auto robot_dart::body_node_get_friction_coeff;\n
"},{"location":"api/namespacerobot__dart/#variable-body_node_get_restitution_coeff","title":"variable body_node_get_restitution_coeff","text":"
auto robot_dart::body_node_get_restitution_coeff;\n
"},{"location":"api/namespacerobot__dart/#variable-body_node_set_friction_coeff","title":"variable body_node_set_friction_coeff","text":"
auto robot_dart::body_node_set_friction_coeff;\n
"},{"location":"api/namespacerobot__dart/#variable-body_node_set_restitution_coeff","title":"variable body_node_set_restitution_coeff","text":"
auto robot_dart::body_node_set_restitution_coeff;\n
"},{"location":"api/namespacerobot__dart/#public-functions-documentation","title":"Public Functions Documentation","text":""},{"location":"api/namespacerobot__dart/#function-make_tf","title":"function make_tf","text":"
inline Eigen::Isometry3d robot_dart::make_tf (\nconst Eigen::Matrix3d & R,\nconst Eigen::Vector3d & t\n) 
"},{"location":"api/namespacerobot__dart/#function-make_tf_1","title":"function make_tf","text":"
inline Eigen::Isometry3d robot_dart::make_tf (\nconst Eigen::Matrix3d & R\n) 
"},{"location":"api/namespacerobot__dart/#function-make_tf_2","title":"function make_tf","text":"
inline Eigen::Isometry3d robot_dart::make_tf (\nconst Eigen::Vector3d & t\n) 
"},{"location":"api/namespacerobot__dart/#function-make_tf_3","title":"function make_tf","text":"
inline Eigen::Isometry3d robot_dart::make_tf (\nstd::initializer_list< double > args\n) 
"},{"location":"api/namespacerobot__dart/#function-make_vector","title":"function make_vector","text":"
inline Eigen::VectorXd robot_dart::make_vector (\nstd::initializer_list< double > args\n) 

The documentation for this class was generated from the following file robot_dart/control/pd_control.cpp

"},{"location":"api/classrobot__dart_1_1Assertion/","title":"Class robot_dart::Assertion","text":"

ClassList > robot_dart > Assertion

Inherits the following classes: std::exception

"},{"location":"api/classrobot__dart_1_1Assertion/#public-functions","title":"Public Functions","text":"Type Name Assertion (const std::string & msg=\"\") const char * what () const"},{"location":"api/classrobot__dart_1_1Assertion/#public-functions-documentation","title":"Public Functions Documentation","text":""},{"location":"api/classrobot__dart_1_1Assertion/#function-assertion","title":"function Assertion","text":"
inline robot_dart::Assertion::Assertion (\nconst std::string & msg=\"\"\n) 
"},{"location":"api/classrobot__dart_1_1Assertion/#function-what","title":"function what","text":"
inline const char * robot_dart::Assertion::what () const\n

The documentation for this class was generated from the following file robot_dart/utils.hpp

"},{"location":"api/classrobot__dart_1_1Robot/","title":"Class robot_dart::Robot","text":"

ClassList > robot_dart > Robot

Inherits the following classes: std::enable_shared_from_this< Robot >

Inherited by the following classes: robot_dart::robots::A1, robot_dart::robots::Arm, robot_dart::robots::Franka, robot_dart::robots::Hexapod, robot_dart::robots::ICub, robot_dart::robots::Iiwa, robot_dart::robots::Pendulum, robot_dart::robots::Talos, robot_dart::robots::Tiago, robot_dart::robots::Ur3e, robot_dart::robots::Vx300

"},{"location":"api/classrobot__dart_1_1Robot/#public-functions","title":"Public Functions","text":"Type Name Robot (const std::string & model_file, const std::vector< std::pair< std::string, std::string > > & packages, const std::string & robot_name=\"robot\", bool is_urdf_string=false, bool cast_shadows=true) Robot (const std::string & model_file, const std::string & robot_name=\"robot\", bool is_urdf_string=false, bool cast_shadows=true) Robot (dart::dynamics::SkeletonPtr skeleton, const std::string & robot_name=\"robot\", bool cast_shadows=true) Eigen::VectorXd acceleration_lower_limits (const std::vector< std::string > & dof_names={}) const Eigen::VectorXd acceleration_upper_limits (const std::vector< std::string > & dof_names={}) const Eigen::VectorXd accelerations (const std::vector< std::string > & dof_names={}) const std::vector< std::shared_ptr< control::RobotControl > > active_controllers () const std::string actuator_type (const std::string & joint_name) const std::vector< std::string > actuator_types (const std::vector< std::string > & joint_names={}) const void add_body_mass (const std::string & body_name, double mass) void add_body_mass (size_t body_index, double mass) void add_controller (const std::shared_ptr< control::RobotControl > & controller, double weight=1.0) void add_external_force (const std::string & body_name, const Eigen::Vector3d & force, const Eigen::Vector3d & offset=Eigen::Vector3d::Zero(), bool force_local=false, bool offset_local=true) void add_external_force (size_t body_index, const Eigen::Vector3d & force, const Eigen::Vector3d & offset=Eigen::Vector3d::Zero(), bool force_local=false, bool offset_local=true) void add_external_torque (const std::string & body_name, const Eigen::Vector3d & torque, bool local=false) void add_external_torque (size_t body_index, const Eigen::Vector3d & torque, bool local=false) bool adjacent_colliding () const Eigen::MatrixXd aug_mass_matrix (const std::vector< std::string > & dof_names={}) const Eigen::Isometry3d base_pose () const Eigen::Vector6d base_pose_vec () const Eigen::Vector6d body_acceleration (const std::string & body_name) const Eigen::Vector6d body_acceleration (size_t body_index) const size_t body_index (const std::string & body_name) const double body_mass (const std::string & body_name) const double body_mass (size_t body_index) const std::string body_name (size_t body_index) const std::vector< std::string > body_names () const dart::dynamics::BodyNode * body_node (const std::string & body_name) dart::dynamics::BodyNode * body_node (size_t body_index) Eigen::Isometry3d body_pose (const std::string & body_name) const Eigen::Isometry3d body_pose (size_t body_index) const Eigen::Vector6d body_pose_vec (const std::string & body_name) const Eigen::Vector6d body_pose_vec (size_t body_index) const Eigen::Vector6d body_velocity (const std::string & body_name) const Eigen::Vector6d body_velocity (size_t body_index) const bool cast_shadows () const void clear_controllers () void clear_external_forces () void clear_internal_forces () std::shared_ptr< Robot > clone () const std::shared_ptr< Robot > clone_ghost (const std::string & ghost_name=\"ghost\", const Eigen::Vector4d & ghost_color={0.3, 0.3, 0.3, 0.7}) const Eigen::Vector3d com () const Eigen::Vector6d com_acceleration () const Eigen::MatrixXd com_jacobian (const std::vector< std::string > & dof_names={}) const Eigen::MatrixXd com_jacobian_deriv (const std::vector< std::string > & dof_names={}) const Eigen::Vector6d com_velocity () const Eigen::VectorXd commands (const std::vector< std::string > & dof_names={}) const Eigen::VectorXd constraint_forces (const std::vector< std::string > & dof_names={}) const std::shared_ptr< control::RobotControl > controller (size_t index) const std::vector< std::shared_ptr< control::RobotControl > > controllers () const Eigen::VectorXd coriolis_forces (const std::vector< std::string > & dof_names={}) const Eigen::VectorXd coriolis_gravity_forces (const std::vector< std::string > & dof_names={}) const std::vector< double > coulomb_coeffs (const std::vector< std::string > & dof_names={}) const std::vector< double > damping_coeffs (const std::vector< std::string > & dof_names={}) const dart::dynamics::DegreeOfFreedom * dof (const std::string & dof_name) dart::dynamics::DegreeOfFreedom * dof (size_t dof_index) size_t dof_index (const std::string & dof_name) const const std::unordered_map< std::string, size_t > & dof_map () const std::string dof_name (size_t dof_index) const std::vector< std::string > dof_names (bool filter_mimics=false, bool filter_locked=false, bool filter_passive=false) const const std::vector< std::pair< dart::dynamics::BodyNode *, double > > & drawing_axes () const Eigen::Vector6d external_forces (const std::string & body_name) const Eigen::Vector6d external_forces (size_t body_index) const void fix_to_world () bool fixed () const Eigen::VectorXd force_lower_limits (const std::vector< std::string > & dof_names={}) const void force_position_bounds () std::pair< Eigen::Vector6d, Eigen::Vector6d > force_torque (size_t joint_index) const Eigen::VectorXd force_upper_limits (const std::vector< std::string > & dof_names={}) const Eigen::VectorXd forces (const std::vector< std::string > & dof_names={}) const bool free () const void free_from_world (const Eigen::Vector6d & pose=Eigen::Vector6d::Zero()) double friction_coeff (const std::string & body_name) double friction_coeff (size_t body_index) Eigen::Vector3d friction_dir (const std::string & body_name) Eigen::Vector3d friction_dir (size_t body_index) bool ghost () const Eigen::VectorXd gravity_forces (const std::vector< std::string > & dof_names={}) const Eigen::MatrixXd inv_aug_mass_matrix (const std::vector< std::string > & dof_names={}) const Eigen::MatrixXd inv_mass_matrix (const std::vector< std::string > & dof_names={}) const Eigen::MatrixXd jacobian (const std::string & body_name, const std::vector< std::string > & dof_names={}) const Eigen::MatrixXd jacobian_deriv (const std::string & body_name, const std::vector< std::string > & dof_names={}) const dart::dynamics::Joint * joint (const std::string & joint_name) dart::dynamics::Joint * joint (size_t joint_index) size_t joint_index (const std::string & joint_name) const const std::unordered_map< std::string, size_t > & joint_map () const std::string joint_name (size_t joint_index) const std::vector< std::string > joint_names () const std::vector< std::string > locked_dof_names () const Eigen::MatrixXd mass_matrix (const std::vector< std::string > & dof_names={}) const std::vector< std::string > mimic_dof_names () const const std::string & model_filename () const const std::vector< std::pair< std::string, std::string > > & model_packages () const const std::string & name () const size_t num_bodies () const size_t num_controllers () const size_t num_dofs () const size_t num_joints () const std::vector< std::string > passive_dof_names () const std::vector< bool > position_enforced (const std::vector< std::string > & dof_names={}) const Eigen::VectorXd position_lower_limits (const std::vector< std::string > & dof_names={}) const Eigen::VectorXd position_upper_limits (const std::vector< std::string > & dof_names={}) const Eigen::VectorXd positions (const std::vector< std::string > & dof_names={}) const void reinit_controllers () void remove_all_drawing_axis () void remove_controller (const std::shared_ptr< control::RobotControl > & controller) void remove_controller (size_t index) virtual void reset () void reset_commands () double restitution_coeff (const std::string & body_name) double restitution_coeff (size_t body_index) double secondary_friction_coeff (const std::string & body_name) double secondary_friction_coeff (size_t body_index) bool self_colliding () const void set_acceleration_lower_limits (const Eigen::VectorXd & accelerations, const std::vector< std::string > & dof_names={}) void set_acceleration_upper_limits (const Eigen::VectorXd & accelerations, const std::vector< std::string > & dof_names={}) void set_accelerations (const Eigen::VectorXd & accelerations, const std::vector< std::string > & dof_names={}) void set_actuator_type (const std::string & type, const std::string & joint_name, bool override_mimic=false, bool override_base=false) void set_actuator_types (const std::string & type, const std::vector< std::string > & joint_names={}, bool override_mimic=false, bool override_base=false) void set_base_pose (const Eigen::Isometry3d & tf) void set_base_pose (const Eigen::Vector6d & pose) set base pose: pose is a 6D vector (first 3D orientation in angle-axis and last 3D translation) void set_body_mass (const std::string & body_name, double mass) void set_body_mass (size_t body_index, double mass) void set_body_name (size_t body_index, const std::string & body_name) void set_cast_shadows (bool cast_shadows=true) void set_color_mode (const std::string & color_mode) void set_color_mode (const std::string & color_mode, const std::string & body_name) void set_commands (const Eigen::VectorXd & commands, const std::vector< std::string > & dof_names={}) void set_coulomb_coeffs (const std::vector< double > & cfrictions, const std::vector< std::string > & dof_names={}) void set_coulomb_coeffs (double cfriction, const std::vector< std::string > & dof_names={}) void set_damping_coeffs (const std::vector< double > & damps, const std::vector< std::string > & dof_names={}) void set_damping_coeffs (double damp, const std::vector< std::string > & dof_names={}) void set_draw_axis (const std::string & body_name, double size=0.25) void set_external_force (const std::string & body_name, const Eigen::Vector3d & force, const Eigen::Vector3d & offset=Eigen::Vector3d::Zero(), bool force_local=false, bool offset_local=true) void set_external_force (size_t body_index, const Eigen::Vector3d & force, const Eigen::Vector3d & offset=Eigen::Vector3d::Zero(), bool force_local=false, bool offset_local=true) void set_external_torque (const std::string & body_name, const Eigen::Vector3d & torque, bool local=false) void set_external_torque (size_t body_index, const Eigen::Vector3d & torque, bool local=false) void set_force_lower_limits (const Eigen::VectorXd & forces, const std::vector< std::string > & dof_names={}) void set_force_upper_limits (const Eigen::VectorXd & forces, const std::vector< std::string > & dof_names={}) void set_forces (const Eigen::VectorXd & forces, const std::vector< std::string > & dof_names={}) void set_friction_coeff (const std::string & body_name, double value) void set_friction_coeff (size_t body_index, double value) void set_friction_coeffs (double value) void set_friction_dir (const std::string & body_name, const Eigen::Vector3d & direction) void set_friction_dir (size_t body_index, const Eigen::Vector3d & direction) void set_ghost (bool ghost=true) void set_joint_name (size_t joint_index, const std::string & joint_name) void set_mimic (const std::string & joint_name, const std::string & mimic_joint_name, double multiplier=1., double offset=0.) void set_position_enforced (const std::vector< bool > & enforced, const std::vector< std::string > & dof_names={}) void set_position_enforced (bool enforced, const std::vector< std::string > & dof_names={}) void set_position_lower_limits (const Eigen::VectorXd & positions, const std::vector< std::string > & dof_names={}) void set_position_upper_limits (const Eigen::VectorXd & positions, const std::vector< std::string > & dof_names={}) void set_positions (const Eigen::VectorXd & positions, const std::vector< std::string > & dof_names={}) void set_restitution_coeff (const std::string & body_name, double value) void set_restitution_coeff (size_t body_index, double value) void set_restitution_coeffs (double value) void set_secondary_friction_coeff (const std::string & body_name, double value) void set_secondary_friction_coeff (size_t body_index, double value) void set_secondary_friction_coeffs (double value) void set_self_collision (bool enable_self_collisions=true, bool enable_adjacent_collisions=false) void set_spring_stiffnesses (const std::vector< double > & stiffnesses, const std::vector< std::string > & dof_names={}) void set_spring_stiffnesses (double stiffness, const std::vector< std::string > & dof_names={}) void set_velocities (const Eigen::VectorXd & velocities, const std::vector< std::string > & dof_names={}) void set_velocity_lower_limits (const Eigen::VectorXd & velocities, const std::vector< std::string > & dof_names={}) void set_velocity_upper_limits (const Eigen::VectorXd & velocities, const std::vector< std::string > & dof_names={}) dart::dynamics::SkeletonPtr skeleton () std::vector< double > spring_stiffnesses (const std::vector< std::string > & dof_names={}) const void update (double t) void update_joint_dof_maps () Eigen::VectorXd vec_dof (const Eigen::VectorXd & vec, const std::vector< std::string > & dof_names) const Eigen::VectorXd velocities (const std::vector< std::string > & dof_names={}) const Eigen::VectorXd velocity_lower_limits (const std::vector< std::string > & dof_names={}) const Eigen::VectorXd velocity_upper_limits (const std::vector< std::string > & dof_names={}) const virtual ~Robot ()"},{"location":"api/classrobot__dart_1_1Robot/#public-static-functions","title":"Public Static Functions","text":"Type Name std::shared_ptr< Robot > create_box (const Eigen::Vector3d & dims, const Eigen::Isometry3d & tf, const std::string & type=\"free\", double mass=1.0, const Eigen::Vector4d & color=dart::Color::Red(1.0), const std::string & box_name=\"box\") std::shared_ptr< Robot > create_box (const Eigen::Vector3d & dims, const Eigen::Vector6d & pose=Eigen::Vector6d::Zero(), const std::string & type=\"free\", double mass=1.0, const Eigen::Vector4d & color=dart::Color::Red(1.0), const std::string & box_name=\"box\") std::shared_ptr< Robot > create_ellipsoid (const Eigen::Vector3d & dims, const Eigen::Isometry3d & tf, const std::string & type=\"free\", double mass=1.0, const Eigen::Vector4d & color=dart::Color::Red(1.0), const std::string & ellipsoid_name=\"ellipsoid\") std::shared_ptr< Robot > create_ellipsoid (const Eigen::Vector3d & dims, const Eigen::Vector6d & pose=Eigen::Vector6d::Zero(), const std::string & type=\"free\", double mass=1.0, const Eigen::Vector4d & color=dart::Color::Red(1.0), const std::string & ellipsoid_name=\"ellipsoid\")"},{"location":"api/classrobot__dart_1_1Robot/#protected-attributes","title":"Protected Attributes","text":"Type Name std::vector< std::pair< dart::dynamics::BodyNode *, double > > _axis_shapes bool _cast_shadows std::vector< std::shared_ptr< control::RobotControl > > _controllers std::unordered_map< std::string, size_t > _dof_map bool _is_ghost std::unordered_map< std::string, size_t > _joint_map std::string _model_filename std::vector< std::pair< std::string, std::string > > _packages std::string _robot_name dart::dynamics::SkeletonPtr _skeleton"},{"location":"api/classrobot__dart_1_1Robot/#protected-functions","title":"Protected Functions","text":"Type Name dart::dynamics::Joint::ActuatorType _actuator_type (size_t joint_index) const std::vector< dart::dynamics::Joint::ActuatorType > _actuator_types () const std::string _get_path (const std::string & filename) const Eigen::MatrixXd _jacobian (const Eigen::MatrixXd & full_jacobian, const std::vector< std::string > & dof_names) const dart::dynamics::SkeletonPtr _load_model (const std::string & filename, const std::vector< std::pair< std::string, std::string > > & packages=std::vector< std::pair< std::string, std::string > >(), bool is_urdf_string=false) Eigen::MatrixXd _mass_matrix (const Eigen::MatrixXd & full_mass_matrix, const std::vector< std::string > & dof_names) const virtual void _post_addition (RobotDARTSimu *) Function called by RobotDARTSimu object when adding the robot to the world. virtual void _post_removal (RobotDARTSimu *) Function called by RobotDARTSimu object when removing the robot to the world. void _set_actuator_type (size_t joint_index, dart::dynamics::Joint::ActuatorType type, bool override_mimic=false, bool override_base=false) void _set_actuator_types (const std::vector< dart::dynamics::Joint::ActuatorType > & types, bool override_mimic=false, bool override_base=false) void _set_actuator_types (dart::dynamics::Joint::ActuatorType type, bool override_mimic=false, bool override_base=false) void _set_color_mode (dart::dynamics::MeshShape::ColorMode color_mode, dart::dynamics::SkeletonPtr skel) void _set_color_mode (dart::dynamics::MeshShape::ColorMode color_mode, dart::dynamics::ShapeNode * sn)"},{"location":"api/classrobot__dart_1_1Robot/#public-functions-documentation","title":"Public Functions Documentation","text":""},{"location":"api/classrobot__dart_1_1Robot/#function-robot-13","title":"function Robot [\u2153]","text":"
robot_dart::Robot::Robot (\nconst std::string & model_file,\nconst std::vector< std::pair< std::string, std::string > > & packages,\nconst std::string & robot_name=\"robot\",\nbool is_urdf_string=false,\nbool cast_shadows=true\n) 
"},{"location":"api/classrobot__dart_1_1Robot/#function-robot-23","title":"function Robot [\u2154]","text":"
robot_dart::Robot::Robot (\nconst std::string & model_file,\nconst std::string & robot_name=\"robot\",\nbool is_urdf_string=false,\nbool cast_shadows=true\n) 
"},{"location":"api/classrobot__dart_1_1Robot/#function-robot-33","title":"function Robot [3/3]","text":"
robot_dart::Robot::Robot (\ndart::dynamics::SkeletonPtr skeleton,\nconst std::string & robot_name=\"robot\",\nbool cast_shadows=true\n) 
"},{"location":"api/classrobot__dart_1_1Robot/#function-acceleration_lower_limits","title":"function acceleration_lower_limits","text":"
Eigen::VectorXd robot_dart::Robot::acceleration_lower_limits (\nconst std::vector< std::string > & dof_names={}\n) const\n
"},{"location":"api/classrobot__dart_1_1Robot/#function-acceleration_upper_limits","title":"function acceleration_upper_limits","text":"
Eigen::VectorXd robot_dart::Robot::acceleration_upper_limits (\nconst std::vector< std::string > & dof_names={}\n) const\n
"},{"location":"api/classrobot__dart_1_1Robot/#function-accelerations","title":"function accelerations","text":"
Eigen::VectorXd robot_dart::Robot::accelerations (\nconst std::vector< std::string > & dof_names={}\n) const\n
"},{"location":"api/classrobot__dart_1_1Robot/#function-active_controllers","title":"function active_controllers","text":"
std::vector< std::shared_ptr< control::RobotControl > > robot_dart::Robot::active_controllers () const\n
"},{"location":"api/classrobot__dart_1_1Robot/#function-actuator_type","title":"function actuator_type","text":"
std::string robot_dart::Robot::actuator_type (\nconst std::string & joint_name\n) const\n
"},{"location":"api/classrobot__dart_1_1Robot/#function-actuator_types","title":"function actuator_types","text":"
std::vector< std::string > robot_dart::Robot::actuator_types (\nconst std::vector< std::string > & joint_names={}\n) const\n
"},{"location":"api/classrobot__dart_1_1Robot/#function-add_body_mass-12","title":"function add_body_mass [\u00bd]","text":"
void robot_dart::Robot::add_body_mass (\nconst std::string & body_name,\ndouble mass\n) 
"},{"location":"api/classrobot__dart_1_1Robot/#function-add_body_mass-22","title":"function add_body_mass [2/2]","text":"
void robot_dart::Robot::add_body_mass (\nsize_t body_index,\ndouble mass\n) 
"},{"location":"api/classrobot__dart_1_1Robot/#function-add_controller","title":"function add_controller","text":"
void robot_dart::Robot::add_controller (\nconst std::shared_ptr< control::RobotControl > & controller,\ndouble weight=1.0\n) 
"},{"location":"api/classrobot__dart_1_1Robot/#function-add_external_force-12","title":"function add_external_force [\u00bd]","text":"
void robot_dart::Robot::add_external_force (\nconst std::string & body_name,\nconst Eigen::Vector3d & force,\nconst Eigen::Vector3d & offset=Eigen::Vector3d::Zero(),\nbool force_local=false,\nbool offset_local=true\n) 
"},{"location":"api/classrobot__dart_1_1Robot/#function-add_external_force-22","title":"function add_external_force [2/2]","text":"
void robot_dart::Robot::add_external_force (\nsize_t body_index,\nconst Eigen::Vector3d & force,\nconst Eigen::Vector3d & offset=Eigen::Vector3d::Zero(),\nbool force_local=false,\nbool offset_local=true\n) 
"},{"location":"api/classrobot__dart_1_1Robot/#function-add_external_torque-12","title":"function add_external_torque [\u00bd]","text":"
void robot_dart::Robot::add_external_torque (\nconst std::string & body_name,\nconst Eigen::Vector3d & torque,\nbool local=false\n) 
"},{"location":"api/classrobot__dart_1_1Robot/#function-add_external_torque-22","title":"function add_external_torque [2/2]","text":"
void robot_dart::Robot::add_external_torque (\nsize_t body_index,\nconst Eigen::Vector3d & torque,\nbool local=false\n) 
"},{"location":"api/classrobot__dart_1_1Robot/#function-adjacent_colliding","title":"function adjacent_colliding","text":"
bool robot_dart::Robot::adjacent_colliding () const\n
"},{"location":"api/classrobot__dart_1_1Robot/#function-aug_mass_matrix","title":"function aug_mass_matrix","text":"
Eigen::MatrixXd robot_dart::Robot::aug_mass_matrix (\nconst std::vector< std::string > & dof_names={}\n) const\n
"},{"location":"api/classrobot__dart_1_1Robot/#function-base_pose","title":"function base_pose","text":"
Eigen::Isometry3d robot_dart::Robot::base_pose () const\n
"},{"location":"api/classrobot__dart_1_1Robot/#function-base_pose_vec","title":"function base_pose_vec","text":"
Eigen::Vector6d robot_dart::Robot::base_pose_vec () const\n
"},{"location":"api/classrobot__dart_1_1Robot/#function-body_acceleration-12","title":"function body_acceleration [\u00bd]","text":"
Eigen::Vector6d robot_dart::Robot::body_acceleration (\nconst std::string & body_name\n) const\n
"},{"location":"api/classrobot__dart_1_1Robot/#function-body_acceleration-22","title":"function body_acceleration [2/2]","text":"
Eigen::Vector6d robot_dart::Robot::body_acceleration (\nsize_t body_index\n) const\n
"},{"location":"api/classrobot__dart_1_1Robot/#function-body_index","title":"function body_index","text":"
size_t robot_dart::Robot::body_index (\nconst std::string & body_name\n) const\n
"},{"location":"api/classrobot__dart_1_1Robot/#function-body_mass-12","title":"function body_mass [\u00bd]","text":"
double robot_dart::Robot::body_mass (\nconst std::string & body_name\n) const\n
"},{"location":"api/classrobot__dart_1_1Robot/#function-body_mass-22","title":"function body_mass [2/2]","text":"
double robot_dart::Robot::body_mass (\nsize_t body_index\n) const\n
"},{"location":"api/classrobot__dart_1_1Robot/#function-body_name","title":"function body_name","text":"
std::string robot_dart::Robot::body_name (\nsize_t body_index\n) const\n
"},{"location":"api/classrobot__dart_1_1Robot/#function-body_names","title":"function body_names","text":"
std::vector< std::string > robot_dart::Robot::body_names () const\n
"},{"location":"api/classrobot__dart_1_1Robot/#function-body_node-12","title":"function body_node [\u00bd]","text":"
dart::dynamics::BodyNode * robot_dart::Robot::body_node (\nconst std::string & body_name\n) 
"},{"location":"api/classrobot__dart_1_1Robot/#function-body_node-22","title":"function body_node [2/2]","text":"
dart::dynamics::BodyNode * robot_dart::Robot::body_node (\nsize_t body_index\n) 
"},{"location":"api/classrobot__dart_1_1Robot/#function-body_pose-12","title":"function body_pose [\u00bd]","text":"
Eigen::Isometry3d robot_dart::Robot::body_pose (\nconst std::string & body_name\n) const\n
"},{"location":"api/classrobot__dart_1_1Robot/#function-body_pose-22","title":"function body_pose [2/2]","text":"
Eigen::Isometry3d robot_dart::Robot::body_pose (\nsize_t body_index\n) const\n
"},{"location":"api/classrobot__dart_1_1Robot/#function-body_pose_vec-12","title":"function body_pose_vec [\u00bd]","text":"
Eigen::Vector6d robot_dart::Robot::body_pose_vec (\nconst std::string & body_name\n) const\n
"},{"location":"api/classrobot__dart_1_1Robot/#function-body_pose_vec-22","title":"function body_pose_vec [2/2]","text":"
Eigen::Vector6d robot_dart::Robot::body_pose_vec (\nsize_t body_index\n) const\n
"},{"location":"api/classrobot__dart_1_1Robot/#function-body_velocity-12","title":"function body_velocity [\u00bd]","text":"
Eigen::Vector6d robot_dart::Robot::body_velocity (\nconst std::string & body_name\n) const\n
"},{"location":"api/classrobot__dart_1_1Robot/#function-body_velocity-22","title":"function body_velocity [2/2]","text":"
Eigen::Vector6d robot_dart::Robot::body_velocity (\nsize_t body_index\n) const\n
"},{"location":"api/classrobot__dart_1_1Robot/#function-cast_shadows","title":"function cast_shadows","text":"
bool robot_dart::Robot::cast_shadows () const\n
"},{"location":"api/classrobot__dart_1_1Robot/#function-clear_controllers","title":"function clear_controllers","text":"
void robot_dart::Robot::clear_controllers () 
"},{"location":"api/classrobot__dart_1_1Robot/#function-clear_external_forces","title":"function clear_external_forces","text":"
void robot_dart::Robot::clear_external_forces () 
"},{"location":"api/classrobot__dart_1_1Robot/#function-clear_internal_forces","title":"function clear_internal_forces","text":"
void robot_dart::Robot::clear_internal_forces () 
"},{"location":"api/classrobot__dart_1_1Robot/#function-clone","title":"function clone","text":"
std::shared_ptr< Robot > robot_dart::Robot::clone () const\n
"},{"location":"api/classrobot__dart_1_1Robot/#function-clone_ghost","title":"function clone_ghost","text":"
std::shared_ptr< Robot > robot_dart::Robot::clone_ghost (\nconst std::string & ghost_name=\"ghost\",\nconst Eigen::Vector4d & ghost_color={0.3, 0.3, 0.3, 0.7}\n) const\n
"},{"location":"api/classrobot__dart_1_1Robot/#function-com","title":"function com","text":"
Eigen::Vector3d robot_dart::Robot::com () const\n
"},{"location":"api/classrobot__dart_1_1Robot/#function-com_acceleration","title":"function com_acceleration","text":"
Eigen::Vector6d robot_dart::Robot::com_acceleration () const\n
"},{"location":"api/classrobot__dart_1_1Robot/#function-com_jacobian","title":"function com_jacobian","text":"
Eigen::MatrixXd robot_dart::Robot::com_jacobian (\nconst std::vector< std::string > & dof_names={}\n) const\n
"},{"location":"api/classrobot__dart_1_1Robot/#function-com_jacobian_deriv","title":"function com_jacobian_deriv","text":"
Eigen::MatrixXd robot_dart::Robot::com_jacobian_deriv (\nconst std::vector< std::string > & dof_names={}\n) const\n
"},{"location":"api/classrobot__dart_1_1Robot/#function-com_velocity","title":"function com_velocity","text":"
Eigen::Vector6d robot_dart::Robot::com_velocity () const\n
"},{"location":"api/classrobot__dart_1_1Robot/#function-commands","title":"function commands","text":"
Eigen::VectorXd robot_dart::Robot::commands (\nconst std::vector< std::string > & dof_names={}\n) const\n
"},{"location":"api/classrobot__dart_1_1Robot/#function-constraint_forces","title":"function constraint_forces","text":"
Eigen::VectorXd robot_dart::Robot::constraint_forces (\nconst std::vector< std::string > & dof_names={}\n) const\n
"},{"location":"api/classrobot__dart_1_1Robot/#function-controller","title":"function controller","text":"
std::shared_ptr< control::RobotControl > robot_dart::Robot::controller (\nsize_t index\n) const\n
"},{"location":"api/classrobot__dart_1_1Robot/#function-controllers","title":"function controllers","text":"
std::vector< std::shared_ptr< control::RobotControl > > robot_dart::Robot::controllers () const\n
"},{"location":"api/classrobot__dart_1_1Robot/#function-coriolis_forces","title":"function coriolis_forces","text":"
Eigen::VectorXd robot_dart::Robot::coriolis_forces (\nconst std::vector< std::string > & dof_names={}\n) const\n
"},{"location":"api/classrobot__dart_1_1Robot/#function-coriolis_gravity_forces","title":"function coriolis_gravity_forces","text":"
Eigen::VectorXd robot_dart::Robot::coriolis_gravity_forces (\nconst std::vector< std::string > & dof_names={}\n) const\n
"},{"location":"api/classrobot__dart_1_1Robot/#function-coulomb_coeffs","title":"function coulomb_coeffs","text":"
std::vector< double > robot_dart::Robot::coulomb_coeffs (\nconst std::vector< std::string > & dof_names={}\n) const\n
"},{"location":"api/classrobot__dart_1_1Robot/#function-damping_coeffs","title":"function damping_coeffs","text":"
std::vector< double > robot_dart::Robot::damping_coeffs (\nconst std::vector< std::string > & dof_names={}\n) const\n
"},{"location":"api/classrobot__dart_1_1Robot/#function-dof-12","title":"function dof [\u00bd]","text":"
dart::dynamics::DegreeOfFreedom * robot_dart::Robot::dof (\nconst std::string & dof_name\n) 
"},{"location":"api/classrobot__dart_1_1Robot/#function-dof-22","title":"function dof [2/2]","text":"
dart::dynamics::DegreeOfFreedom * robot_dart::Robot::dof (\nsize_t dof_index\n) 
"},{"location":"api/classrobot__dart_1_1Robot/#function-dof_index","title":"function dof_index","text":"
size_t robot_dart::Robot::dof_index (\nconst std::string & dof_name\n) const\n
"},{"location":"api/classrobot__dart_1_1Robot/#function-dof_map","title":"function dof_map","text":"
const std::unordered_map< std::string, size_t > & robot_dart::Robot::dof_map () const\n
"},{"location":"api/classrobot__dart_1_1Robot/#function-dof_name","title":"function dof_name","text":"
std::string robot_dart::Robot::dof_name (\nsize_t dof_index\n) const\n
"},{"location":"api/classrobot__dart_1_1Robot/#function-dof_names","title":"function dof_names","text":"
std::vector< std::string > robot_dart::Robot::dof_names (\nbool filter_mimics=false,\nbool filter_locked=false,\nbool filter_passive=false\n) const\n
"},{"location":"api/classrobot__dart_1_1Robot/#function-drawing_axes","title":"function drawing_axes","text":"
const std::vector< std::pair< dart::dynamics::BodyNode *, double > > & robot_dart::Robot::drawing_axes () const\n
"},{"location":"api/classrobot__dart_1_1Robot/#function-external_forces-12","title":"function external_forces [\u00bd]","text":"
Eigen::Vector6d robot_dart::Robot::external_forces (\nconst std::string & body_name\n) const\n
"},{"location":"api/classrobot__dart_1_1Robot/#function-external_forces-22","title":"function external_forces [2/2]","text":"
Eigen::Vector6d robot_dart::Robot::external_forces (\nsize_t body_index\n) const\n
"},{"location":"api/classrobot__dart_1_1Robot/#function-fix_to_world","title":"function fix_to_world","text":"
void robot_dart::Robot::fix_to_world () 
"},{"location":"api/classrobot__dart_1_1Robot/#function-fixed","title":"function fixed","text":"
bool robot_dart::Robot::fixed () const\n
"},{"location":"api/classrobot__dart_1_1Robot/#function-force_lower_limits","title":"function force_lower_limits","text":"
Eigen::VectorXd robot_dart::Robot::force_lower_limits (\nconst std::vector< std::string > & dof_names={}\n) const\n
"},{"location":"api/classrobot__dart_1_1Robot/#function-force_position_bounds","title":"function force_position_bounds","text":"
void robot_dart::Robot::force_position_bounds () 
"},{"location":"api/classrobot__dart_1_1Robot/#function-force_torque","title":"function force_torque","text":"
std::pair< Eigen::Vector6d, Eigen::Vector6d > robot_dart::Robot::force_torque (\nsize_t joint_index\n) const\n
"},{"location":"api/classrobot__dart_1_1Robot/#function-force_upper_limits","title":"function force_upper_limits","text":"
Eigen::VectorXd robot_dart::Robot::force_upper_limits (\nconst std::vector< std::string > & dof_names={}\n) const\n
"},{"location":"api/classrobot__dart_1_1Robot/#function-forces","title":"function forces","text":"
Eigen::VectorXd robot_dart::Robot::forces (\nconst std::vector< std::string > & dof_names={}\n) const\n
"},{"location":"api/classrobot__dart_1_1Robot/#function-free","title":"function free","text":"
bool robot_dart::Robot::free () const\n
"},{"location":"api/classrobot__dart_1_1Robot/#function-free_from_world","title":"function free_from_world","text":"
void robot_dart::Robot::free_from_world (\nconst Eigen::Vector6d & pose=Eigen::Vector6d::Zero()\n) 
"},{"location":"api/classrobot__dart_1_1Robot/#function-friction_coeff-12","title":"function friction_coeff [\u00bd]","text":"
double robot_dart::Robot::friction_coeff (\nconst std::string & body_name\n) 
"},{"location":"api/classrobot__dart_1_1Robot/#function-friction_coeff-22","title":"function friction_coeff [2/2]","text":"
double robot_dart::Robot::friction_coeff (\nsize_t body_index\n) 
"},{"location":"api/classrobot__dart_1_1Robot/#function-friction_dir-12","title":"function friction_dir [\u00bd]","text":"
Eigen::Vector3d robot_dart::Robot::friction_dir (\nconst std::string & body_name\n) 
"},{"location":"api/classrobot__dart_1_1Robot/#function-friction_dir-22","title":"function friction_dir [2/2]","text":"
Eigen::Vector3d robot_dart::Robot::friction_dir (\nsize_t body_index\n) 
"},{"location":"api/classrobot__dart_1_1Robot/#function-ghost","title":"function ghost","text":"
bool robot_dart::Robot::ghost () const\n
"},{"location":"api/classrobot__dart_1_1Robot/#function-gravity_forces","title":"function gravity_forces","text":"
Eigen::VectorXd robot_dart::Robot::gravity_forces (\nconst std::vector< std::string > & dof_names={}\n) const\n
"},{"location":"api/classrobot__dart_1_1Robot/#function-inv_aug_mass_matrix","title":"function inv_aug_mass_matrix","text":"
Eigen::MatrixXd robot_dart::Robot::inv_aug_mass_matrix (\nconst std::vector< std::string > & dof_names={}\n) const\n
"},{"location":"api/classrobot__dart_1_1Robot/#function-inv_mass_matrix","title":"function inv_mass_matrix","text":"
Eigen::MatrixXd robot_dart::Robot::inv_mass_matrix (\nconst std::vector< std::string > & dof_names={}\n) const\n
"},{"location":"api/classrobot__dart_1_1Robot/#function-jacobian","title":"function jacobian","text":"
Eigen::MatrixXd robot_dart::Robot::jacobian (\nconst std::string & body_name,\nconst std::vector< std::string > & dof_names={}\n) const\n
"},{"location":"api/classrobot__dart_1_1Robot/#function-jacobian_deriv","title":"function jacobian_deriv","text":"
Eigen::MatrixXd robot_dart::Robot::jacobian_deriv (\nconst std::string & body_name,\nconst std::vector< std::string > & dof_names={}\n) const\n
"},{"location":"api/classrobot__dart_1_1Robot/#function-joint-12","title":"function joint [\u00bd]","text":"
dart::dynamics::Joint * robot_dart::Robot::joint (\nconst std::string & joint_name\n) 
"},{"location":"api/classrobot__dart_1_1Robot/#function-joint-22","title":"function joint [2/2]","text":"
dart::dynamics::Joint * robot_dart::Robot::joint (\nsize_t joint_index\n) 
"},{"location":"api/classrobot__dart_1_1Robot/#function-joint_index","title":"function joint_index","text":"
size_t robot_dart::Robot::joint_index (\nconst std::string & joint_name\n) const\n
"},{"location":"api/classrobot__dart_1_1Robot/#function-joint_map","title":"function joint_map","text":"
const std::unordered_map< std::string, size_t > & robot_dart::Robot::joint_map () const\n
"},{"location":"api/classrobot__dart_1_1Robot/#function-joint_name","title":"function joint_name","text":"
std::string robot_dart::Robot::joint_name (\nsize_t joint_index\n) const\n
"},{"location":"api/classrobot__dart_1_1Robot/#function-joint_names","title":"function joint_names","text":"
std::vector< std::string > robot_dart::Robot::joint_names () const\n
"},{"location":"api/classrobot__dart_1_1Robot/#function-locked_dof_names","title":"function locked_dof_names","text":"
std::vector< std::string > robot_dart::Robot::locked_dof_names () const\n
"},{"location":"api/classrobot__dart_1_1Robot/#function-mass_matrix","title":"function mass_matrix","text":"
Eigen::MatrixXd robot_dart::Robot::mass_matrix (\nconst std::vector< std::string > & dof_names={}\n) const\n
"},{"location":"api/classrobot__dart_1_1Robot/#function-mimic_dof_names","title":"function mimic_dof_names","text":"
std::vector< std::string > robot_dart::Robot::mimic_dof_names () const\n
"},{"location":"api/classrobot__dart_1_1Robot/#function-model_filename","title":"function model_filename","text":"
inline const std::string & robot_dart::Robot::model_filename () const\n
"},{"location":"api/classrobot__dart_1_1Robot/#function-model_packages","title":"function model_packages","text":"
inline const std::vector< std::pair< std::string, std::string > > & robot_dart::Robot::model_packages () const\n
"},{"location":"api/classrobot__dart_1_1Robot/#function-name","title":"function name","text":"
const std::string & robot_dart::Robot::name () const\n
"},{"location":"api/classrobot__dart_1_1Robot/#function-num_bodies","title":"function num_bodies","text":"
size_t robot_dart::Robot::num_bodies () const\n
"},{"location":"api/classrobot__dart_1_1Robot/#function-num_controllers","title":"function num_controllers","text":"
size_t robot_dart::Robot::num_controllers () const\n
"},{"location":"api/classrobot__dart_1_1Robot/#function-num_dofs","title":"function num_dofs","text":"
size_t robot_dart::Robot::num_dofs () const\n
"},{"location":"api/classrobot__dart_1_1Robot/#function-num_joints","title":"function num_joints","text":"
size_t robot_dart::Robot::num_joints () const\n
"},{"location":"api/classrobot__dart_1_1Robot/#function-passive_dof_names","title":"function passive_dof_names","text":"
std::vector< std::string > robot_dart::Robot::passive_dof_names () const\n
"},{"location":"api/classrobot__dart_1_1Robot/#function-position_enforced","title":"function position_enforced","text":"
std::vector< bool > robot_dart::Robot::position_enforced (\nconst std::vector< std::string > & dof_names={}\n) const\n
"},{"location":"api/classrobot__dart_1_1Robot/#function-position_lower_limits","title":"function position_lower_limits","text":"
Eigen::VectorXd robot_dart::Robot::position_lower_limits (\nconst std::vector< std::string > & dof_names={}\n) const\n
"},{"location":"api/classrobot__dart_1_1Robot/#function-position_upper_limits","title":"function position_upper_limits","text":"
Eigen::VectorXd robot_dart::Robot::position_upper_limits (\nconst std::vector< std::string > & dof_names={}\n) const\n
"},{"location":"api/classrobot__dart_1_1Robot/#function-positions","title":"function positions","text":"
Eigen::VectorXd robot_dart::Robot::positions (\nconst std::vector< std::string > & dof_names={}\n) const\n
"},{"location":"api/classrobot__dart_1_1Robot/#function-reinit_controllers","title":"function reinit_controllers","text":"
void robot_dart::Robot::reinit_controllers () 
"},{"location":"api/classrobot__dart_1_1Robot/#function-remove_all_drawing_axis","title":"function remove_all_drawing_axis","text":"
void robot_dart::Robot::remove_all_drawing_axis () 
"},{"location":"api/classrobot__dart_1_1Robot/#function-remove_controller-12","title":"function remove_controller [\u00bd]","text":"
void robot_dart::Robot::remove_controller (\nconst std::shared_ptr< control::RobotControl > & controller\n) 
"},{"location":"api/classrobot__dart_1_1Robot/#function-remove_controller-22","title":"function remove_controller [2/2]","text":"
void robot_dart::Robot::remove_controller (\nsize_t index\n) 
"},{"location":"api/classrobot__dart_1_1Robot/#function-reset","title":"function reset","text":"
virtual void robot_dart::Robot::reset () 
"},{"location":"api/classrobot__dart_1_1Robot/#function-reset_commands","title":"function reset_commands","text":"
void robot_dart::Robot::reset_commands () 
"},{"location":"api/classrobot__dart_1_1Robot/#function-restitution_coeff-12","title":"function restitution_coeff [\u00bd]","text":"
double robot_dart::Robot::restitution_coeff (\nconst std::string & body_name\n) 
"},{"location":"api/classrobot__dart_1_1Robot/#function-restitution_coeff-22","title":"function restitution_coeff [2/2]","text":"
double robot_dart::Robot::restitution_coeff (\nsize_t body_index\n) 
"},{"location":"api/classrobot__dart_1_1Robot/#function-secondary_friction_coeff-12","title":"function secondary_friction_coeff [\u00bd]","text":"
double robot_dart::Robot::secondary_friction_coeff (\nconst std::string & body_name\n) 
"},{"location":"api/classrobot__dart_1_1Robot/#function-secondary_friction_coeff-22","title":"function secondary_friction_coeff [2/2]","text":"
double robot_dart::Robot::secondary_friction_coeff (\nsize_t body_index\n) 
"},{"location":"api/classrobot__dart_1_1Robot/#function-self_colliding","title":"function self_colliding","text":"
bool robot_dart::Robot::self_colliding () const\n
"},{"location":"api/classrobot__dart_1_1Robot/#function-set_acceleration_lower_limits","title":"function set_acceleration_lower_limits","text":"
void robot_dart::Robot::set_acceleration_lower_limits (\nconst Eigen::VectorXd & accelerations,\nconst std::vector< std::string > & dof_names={}\n) 
"},{"location":"api/classrobot__dart_1_1Robot/#function-set_acceleration_upper_limits","title":"function set_acceleration_upper_limits","text":"
void robot_dart::Robot::set_acceleration_upper_limits (\nconst Eigen::VectorXd & accelerations,\nconst std::vector< std::string > & dof_names={}\n) 
"},{"location":"api/classrobot__dart_1_1Robot/#function-set_accelerations","title":"function set_accelerations","text":"
void robot_dart::Robot::set_accelerations (\nconst Eigen::VectorXd & accelerations,\nconst std::vector< std::string > & dof_names={}\n) 
"},{"location":"api/classrobot__dart_1_1Robot/#function-set_actuator_type","title":"function set_actuator_type","text":"
void robot_dart::Robot::set_actuator_type (\nconst std::string & type,\nconst std::string & joint_name,\nbool override_mimic=false,\nbool override_base=false\n) 
"},{"location":"api/classrobot__dart_1_1Robot/#function-set_actuator_types","title":"function set_actuator_types","text":"
void robot_dart::Robot::set_actuator_types (\nconst std::string & type,\nconst std::vector< std::string > & joint_names={},\nbool override_mimic=false,\nbool override_base=false\n) 
"},{"location":"api/classrobot__dart_1_1Robot/#function-set_base_pose-12","title":"function set_base_pose [\u00bd]","text":"
void robot_dart::Robot::set_base_pose (\nconst Eigen::Isometry3d & tf\n) 
"},{"location":"api/classrobot__dart_1_1Robot/#function-set_base_pose-22","title":"function set_base_pose [2/2]","text":"
void robot_dart::Robot::set_base_pose (\nconst Eigen::Vector6d & pose\n) 
"},{"location":"api/classrobot__dart_1_1Robot/#function-set_body_mass-12","title":"function set_body_mass [\u00bd]","text":"
void robot_dart::Robot::set_body_mass (\nconst std::string & body_name,\ndouble mass\n) 
"},{"location":"api/classrobot__dart_1_1Robot/#function-set_body_mass-22","title":"function set_body_mass [2/2]","text":"
void robot_dart::Robot::set_body_mass (\nsize_t body_index,\ndouble mass\n) 
"},{"location":"api/classrobot__dart_1_1Robot/#function-set_body_name","title":"function set_body_name","text":"
void robot_dart::Robot::set_body_name (\nsize_t body_index,\nconst std::string & body_name\n) 
"},{"location":"api/classrobot__dart_1_1Robot/#function-set_cast_shadows","title":"function set_cast_shadows","text":"
void robot_dart::Robot::set_cast_shadows (\nbool cast_shadows=true\n) 
"},{"location":"api/classrobot__dart_1_1Robot/#function-set_color_mode-12","title":"function set_color_mode [\u00bd]","text":"
void robot_dart::Robot::set_color_mode (\nconst std::string & color_mode\n) 
"},{"location":"api/classrobot__dart_1_1Robot/#function-set_color_mode-22","title":"function set_color_mode [2/2]","text":"
void robot_dart::Robot::set_color_mode (\nconst std::string & color_mode,\nconst std::string & body_name\n) 
"},{"location":"api/classrobot__dart_1_1Robot/#function-set_commands","title":"function set_commands","text":"
void robot_dart::Robot::set_commands (\nconst Eigen::VectorXd & commands,\nconst std::vector< std::string > & dof_names={}\n) 
"},{"location":"api/classrobot__dart_1_1Robot/#function-set_coulomb_coeffs-12","title":"function set_coulomb_coeffs [\u00bd]","text":"
void robot_dart::Robot::set_coulomb_coeffs (\nconst std::vector< double > & cfrictions,\nconst std::vector< std::string > & dof_names={}\n) 
"},{"location":"api/classrobot__dart_1_1Robot/#function-set_coulomb_coeffs-22","title":"function set_coulomb_coeffs [2/2]","text":"
void robot_dart::Robot::set_coulomb_coeffs (\ndouble cfriction,\nconst std::vector< std::string > & dof_names={}\n) 
"},{"location":"api/classrobot__dart_1_1Robot/#function-set_damping_coeffs-12","title":"function set_damping_coeffs [\u00bd]","text":"
void robot_dart::Robot::set_damping_coeffs (\nconst std::vector< double > & damps,\nconst std::vector< std::string > & dof_names={}\n) 
"},{"location":"api/classrobot__dart_1_1Robot/#function-set_damping_coeffs-22","title":"function set_damping_coeffs [2/2]","text":"
void robot_dart::Robot::set_damping_coeffs (\ndouble damp,\nconst std::vector< std::string > & dof_names={}\n) 
"},{"location":"api/classrobot__dart_1_1Robot/#function-set_draw_axis","title":"function set_draw_axis","text":"
void robot_dart::Robot::set_draw_axis (\nconst std::string & body_name,\ndouble size=0.25\n) 
"},{"location":"api/classrobot__dart_1_1Robot/#function-set_external_force-12","title":"function set_external_force [\u00bd]","text":"
void robot_dart::Robot::set_external_force (\nconst std::string & body_name,\nconst Eigen::Vector3d & force,\nconst Eigen::Vector3d & offset=Eigen::Vector3d::Zero(),\nbool force_local=false,\nbool offset_local=true\n) 
"},{"location":"api/classrobot__dart_1_1Robot/#function-set_external_force-22","title":"function set_external_force [2/2]","text":"
void robot_dart::Robot::set_external_force (\nsize_t body_index,\nconst Eigen::Vector3d & force,\nconst Eigen::Vector3d & offset=Eigen::Vector3d::Zero(),\nbool force_local=false,\nbool offset_local=true\n) 
"},{"location":"api/classrobot__dart_1_1Robot/#function-set_external_torque-12","title":"function set_external_torque [\u00bd]","text":"
void robot_dart::Robot::set_external_torque (\nconst std::string & body_name,\nconst Eigen::Vector3d & torque,\nbool local=false\n) 
"},{"location":"api/classrobot__dart_1_1Robot/#function-set_external_torque-22","title":"function set_external_torque [2/2]","text":"
void robot_dart::Robot::set_external_torque (\nsize_t body_index,\nconst Eigen::Vector3d & torque,\nbool local=false\n) 
"},{"location":"api/classrobot__dart_1_1Robot/#function-set_force_lower_limits","title":"function set_force_lower_limits","text":"
void robot_dart::Robot::set_force_lower_limits (\nconst Eigen::VectorXd & forces,\nconst std::vector< std::string > & dof_names={}\n) 
"},{"location":"api/classrobot__dart_1_1Robot/#function-set_force_upper_limits","title":"function set_force_upper_limits","text":"
void robot_dart::Robot::set_force_upper_limits (\nconst Eigen::VectorXd & forces,\nconst std::vector< std::string > & dof_names={}\n) 
"},{"location":"api/classrobot__dart_1_1Robot/#function-set_forces","title":"function set_forces","text":"
void robot_dart::Robot::set_forces (\nconst Eigen::VectorXd & forces,\nconst std::vector< std::string > & dof_names={}\n) 
"},{"location":"api/classrobot__dart_1_1Robot/#function-set_friction_coeff-12","title":"function set_friction_coeff [\u00bd]","text":"
void robot_dart::Robot::set_friction_coeff (\nconst std::string & body_name,\ndouble value\n) 
"},{"location":"api/classrobot__dart_1_1Robot/#function-set_friction_coeff-22","title":"function set_friction_coeff [2/2]","text":"
void robot_dart::Robot::set_friction_coeff (\nsize_t body_index,\ndouble value\n) 
"},{"location":"api/classrobot__dart_1_1Robot/#function-set_friction_coeffs","title":"function set_friction_coeffs","text":"
void robot_dart::Robot::set_friction_coeffs (\ndouble value\n) 
"},{"location":"api/classrobot__dart_1_1Robot/#function-set_friction_dir-12","title":"function set_friction_dir [\u00bd]","text":"
void robot_dart::Robot::set_friction_dir (\nconst std::string & body_name,\nconst Eigen::Vector3d & direction\n) 
"},{"location":"api/classrobot__dart_1_1Robot/#function-set_friction_dir-22","title":"function set_friction_dir [2/2]","text":"
void robot_dart::Robot::set_friction_dir (\nsize_t body_index,\nconst Eigen::Vector3d & direction\n) 
"},{"location":"api/classrobot__dart_1_1Robot/#function-set_ghost","title":"function set_ghost","text":"
void robot_dart::Robot::set_ghost (\nbool ghost=true\n) 
"},{"location":"api/classrobot__dart_1_1Robot/#function-set_joint_name","title":"function set_joint_name","text":"
void robot_dart::Robot::set_joint_name (\nsize_t joint_index,\nconst std::string & joint_name\n) 
"},{"location":"api/classrobot__dart_1_1Robot/#function-set_mimic","title":"function set_mimic","text":"
void robot_dart::Robot::set_mimic (\nconst std::string & joint_name,\nconst std::string & mimic_joint_name,\ndouble multiplier=1.,\ndouble offset=0.\n) 
"},{"location":"api/classrobot__dart_1_1Robot/#function-set_position_enforced-12","title":"function set_position_enforced [\u00bd]","text":"
void robot_dart::Robot::set_position_enforced (\nconst std::vector< bool > & enforced,\nconst std::vector< std::string > & dof_names={}\n) 
"},{"location":"api/classrobot__dart_1_1Robot/#function-set_position_enforced-22","title":"function set_position_enforced [2/2]","text":"
void robot_dart::Robot::set_position_enforced (\nbool enforced,\nconst std::vector< std::string > & dof_names={}\n) 
"},{"location":"api/classrobot__dart_1_1Robot/#function-set_position_lower_limits","title":"function set_position_lower_limits","text":"
void robot_dart::Robot::set_position_lower_limits (\nconst Eigen::VectorXd & positions,\nconst std::vector< std::string > & dof_names={}\n) 
"},{"location":"api/classrobot__dart_1_1Robot/#function-set_position_upper_limits","title":"function set_position_upper_limits","text":"
void robot_dart::Robot::set_position_upper_limits (\nconst Eigen::VectorXd & positions,\nconst std::vector< std::string > & dof_names={}\n) 
"},{"location":"api/classrobot__dart_1_1Robot/#function-set_positions","title":"function set_positions","text":"
void robot_dart::Robot::set_positions (\nconst Eigen::VectorXd & positions,\nconst std::vector< std::string > & dof_names={}\n) 
"},{"location":"api/classrobot__dart_1_1Robot/#function-set_restitution_coeff-12","title":"function set_restitution_coeff [\u00bd]","text":"
void robot_dart::Robot::set_restitution_coeff (\nconst std::string & body_name,\ndouble value\n) 
"},{"location":"api/classrobot__dart_1_1Robot/#function-set_restitution_coeff-22","title":"function set_restitution_coeff [2/2]","text":"
void robot_dart::Robot::set_restitution_coeff (\nsize_t body_index,\ndouble value\n) 
"},{"location":"api/classrobot__dart_1_1Robot/#function-set_restitution_coeffs","title":"function set_restitution_coeffs","text":"
void robot_dart::Robot::set_restitution_coeffs (\ndouble value\n) 
"},{"location":"api/classrobot__dart_1_1Robot/#function-set_secondary_friction_coeff-12","title":"function set_secondary_friction_coeff [\u00bd]","text":"
void robot_dart::Robot::set_secondary_friction_coeff (\nconst std::string & body_name,\ndouble value\n) 
"},{"location":"api/classrobot__dart_1_1Robot/#function-set_secondary_friction_coeff-22","title":"function set_secondary_friction_coeff [2/2]","text":"
void robot_dart::Robot::set_secondary_friction_coeff (\nsize_t body_index,\ndouble value\n) 
"},{"location":"api/classrobot__dart_1_1Robot/#function-set_secondary_friction_coeffs","title":"function set_secondary_friction_coeffs","text":"
void robot_dart::Robot::set_secondary_friction_coeffs (\ndouble value\n) 
"},{"location":"api/classrobot__dart_1_1Robot/#function-set_self_collision","title":"function set_self_collision","text":"
void robot_dart::Robot::set_self_collision (\nbool enable_self_collisions=true,\nbool enable_adjacent_collisions=false\n) 
"},{"location":"api/classrobot__dart_1_1Robot/#function-set_spring_stiffnesses-12","title":"function set_spring_stiffnesses [\u00bd]","text":"
void robot_dart::Robot::set_spring_stiffnesses (\nconst std::vector< double > & stiffnesses,\nconst std::vector< std::string > & dof_names={}\n) 
"},{"location":"api/classrobot__dart_1_1Robot/#function-set_spring_stiffnesses-22","title":"function set_spring_stiffnesses [2/2]","text":"
void robot_dart::Robot::set_spring_stiffnesses (\ndouble stiffness,\nconst std::vector< std::string > & dof_names={}\n) 
"},{"location":"api/classrobot__dart_1_1Robot/#function-set_velocities","title":"function set_velocities","text":"
void robot_dart::Robot::set_velocities (\nconst Eigen::VectorXd & velocities,\nconst std::vector< std::string > & dof_names={}\n) 
"},{"location":"api/classrobot__dart_1_1Robot/#function-set_velocity_lower_limits","title":"function set_velocity_lower_limits","text":"
void robot_dart::Robot::set_velocity_lower_limits (\nconst Eigen::VectorXd & velocities,\nconst std::vector< std::string > & dof_names={}\n) 
"},{"location":"api/classrobot__dart_1_1Robot/#function-set_velocity_upper_limits","title":"function set_velocity_upper_limits","text":"
void robot_dart::Robot::set_velocity_upper_limits (\nconst Eigen::VectorXd & velocities,\nconst std::vector< std::string > & dof_names={}\n) 
"},{"location":"api/classrobot__dart_1_1Robot/#function-skeleton","title":"function skeleton","text":"
dart::dynamics::SkeletonPtr robot_dart::Robot::skeleton () 
"},{"location":"api/classrobot__dart_1_1Robot/#function-spring_stiffnesses","title":"function spring_stiffnesses","text":"
std::vector< double > robot_dart::Robot::spring_stiffnesses (\nconst std::vector< std::string > & dof_names={}\n) const\n
"},{"location":"api/classrobot__dart_1_1Robot/#function-update","title":"function update","text":"
void robot_dart::Robot::update (\ndouble t\n) 
"},{"location":"api/classrobot__dart_1_1Robot/#function-update_joint_dof_maps","title":"function update_joint_dof_maps","text":"
void robot_dart::Robot::update_joint_dof_maps () 
"},{"location":"api/classrobot__dart_1_1Robot/#function-vec_dof","title":"function vec_dof","text":"
Eigen::VectorXd robot_dart::Robot::vec_dof (\nconst Eigen::VectorXd & vec,\nconst std::vector< std::string > & dof_names\n) const\n
"},{"location":"api/classrobot__dart_1_1Robot/#function-velocities","title":"function velocities","text":"
Eigen::VectorXd robot_dart::Robot::velocities (\nconst std::vector< std::string > & dof_names={}\n) const\n
"},{"location":"api/classrobot__dart_1_1Robot/#function-velocity_lower_limits","title":"function velocity_lower_limits","text":"
Eigen::VectorXd robot_dart::Robot::velocity_lower_limits (\nconst std::vector< std::string > & dof_names={}\n) const\n
"},{"location":"api/classrobot__dart_1_1Robot/#function-velocity_upper_limits","title":"function velocity_upper_limits","text":"
Eigen::VectorXd robot_dart::Robot::velocity_upper_limits (\nconst std::vector< std::string > & dof_names={}\n) const\n
"},{"location":"api/classrobot__dart_1_1Robot/#function-robot","title":"function ~Robot","text":"
inline virtual robot_dart::Robot::~Robot () 
"},{"location":"api/classrobot__dart_1_1Robot/#public-static-functions-documentation","title":"Public Static Functions Documentation","text":""},{"location":"api/classrobot__dart_1_1Robot/#function-create_box-12","title":"function create_box [\u00bd]","text":"
static std::shared_ptr< Robot > robot_dart::Robot::create_box (\nconst Eigen::Vector3d & dims,\nconst Eigen::Isometry3d & tf,\nconst std::string & type=\"free\",\ndouble mass=1.0,\nconst Eigen::Vector4d & color=dart::Color::Red(1.0),\nconst std::string & box_name=\"box\"\n) 
"},{"location":"api/classrobot__dart_1_1Robot/#function-create_box-22","title":"function create_box [2/2]","text":"
static std::shared_ptr< Robot > robot_dart::Robot::create_box (\nconst Eigen::Vector3d & dims,\nconst Eigen::Vector6d & pose=Eigen::Vector6d::Zero(),\nconst std::string & type=\"free\",\ndouble mass=1.0,\nconst Eigen::Vector4d & color=dart::Color::Red(1.0),\nconst std::string & box_name=\"box\"\n) 
"},{"location":"api/classrobot__dart_1_1Robot/#function-create_ellipsoid-12","title":"function create_ellipsoid [\u00bd]","text":"
static std::shared_ptr< Robot > robot_dart::Robot::create_ellipsoid (\nconst Eigen::Vector3d & dims,\nconst Eigen::Isometry3d & tf,\nconst std::string & type=\"free\",\ndouble mass=1.0,\nconst Eigen::Vector4d & color=dart::Color::Red(1.0),\nconst std::string & ellipsoid_name=\"ellipsoid\"\n) 
"},{"location":"api/classrobot__dart_1_1Robot/#function-create_ellipsoid-22","title":"function create_ellipsoid [2/2]","text":"
static std::shared_ptr< Robot > robot_dart::Robot::create_ellipsoid (\nconst Eigen::Vector3d & dims,\nconst Eigen::Vector6d & pose=Eigen::Vector6d::Zero(),\nconst std::string & type=\"free\",\ndouble mass=1.0,\nconst Eigen::Vector4d & color=dart::Color::Red(1.0),\nconst std::string & ellipsoid_name=\"ellipsoid\"\n) 
"},{"location":"api/classrobot__dart_1_1Robot/#protected-attributes-documentation","title":"Protected Attributes Documentation","text":""},{"location":"api/classrobot__dart_1_1Robot/#variable-_axis_shapes","title":"variable _axis_shapes","text":"
std::vector<std::pair<dart::dynamics::BodyNode*, double> > robot_dart::Robot::_axis_shapes;\n
"},{"location":"api/classrobot__dart_1_1Robot/#variable-_cast_shadows","title":"variable _cast_shadows","text":"
bool robot_dart::Robot::_cast_shadows;\n
"},{"location":"api/classrobot__dart_1_1Robot/#variable-_controllers","title":"variable _controllers","text":"
std::vector<std::shared_ptr<control::RobotControl> > robot_dart::Robot::_controllers;\n
"},{"location":"api/classrobot__dart_1_1Robot/#variable-_dof_map","title":"variable _dof_map","text":"
std::unordered_map<std::string, size_t> robot_dart::Robot::_dof_map;\n
"},{"location":"api/classrobot__dart_1_1Robot/#variable-_is_ghost","title":"variable _is_ghost","text":"
bool robot_dart::Robot::_is_ghost;\n
"},{"location":"api/classrobot__dart_1_1Robot/#variable-_joint_map","title":"variable _joint_map","text":"
std::unordered_map<std::string, size_t> robot_dart::Robot::_joint_map;\n
"},{"location":"api/classrobot__dart_1_1Robot/#variable-_model_filename","title":"variable _model_filename","text":"
std::string robot_dart::Robot::_model_filename;\n
"},{"location":"api/classrobot__dart_1_1Robot/#variable-_packages","title":"variable _packages","text":"
std::vector<std::pair<std::string, std::string> > robot_dart::Robot::_packages;\n
"},{"location":"api/classrobot__dart_1_1Robot/#variable-_robot_name","title":"variable _robot_name","text":"
std::string robot_dart::Robot::_robot_name;\n
"},{"location":"api/classrobot__dart_1_1Robot/#variable-_skeleton","title":"variable _skeleton","text":"
dart::dynamics::SkeletonPtr robot_dart::Robot::_skeleton;\n
"},{"location":"api/classrobot__dart_1_1Robot/#protected-functions-documentation","title":"Protected Functions Documentation","text":""},{"location":"api/classrobot__dart_1_1Robot/#function-_actuator_type","title":"function _actuator_type","text":"
dart::dynamics::Joint::ActuatorType robot_dart::Robot::_actuator_type (\nsize_t joint_index\n) const\n
"},{"location":"api/classrobot__dart_1_1Robot/#function-_actuator_types","title":"function _actuator_types","text":"
std::vector< dart::dynamics::Joint::ActuatorType > robot_dart::Robot::_actuator_types () const\n
"},{"location":"api/classrobot__dart_1_1Robot/#function-_get_path","title":"function _get_path","text":"
std::string robot_dart::Robot::_get_path (\nconst std::string & filename\n) const\n
"},{"location":"api/classrobot__dart_1_1Robot/#function-_jacobian","title":"function _jacobian","text":"
Eigen::MatrixXd robot_dart::Robot::_jacobian (\nconst Eigen::MatrixXd & full_jacobian,\nconst std::vector< std::string > & dof_names\n) const\n
"},{"location":"api/classrobot__dart_1_1Robot/#function-_load_model","title":"function _load_model","text":"
dart::dynamics::SkeletonPtr robot_dart::Robot::_load_model (\nconst std::string & filename,\nconst std::vector< std::pair< std::string, std::string > > & packages=std::vector< std::pair< std::string, std::string > >(),\nbool is_urdf_string=false\n) 
"},{"location":"api/classrobot__dart_1_1Robot/#function-_mass_matrix","title":"function _mass_matrix","text":"
Eigen::MatrixXd robot_dart::Robot::_mass_matrix (\nconst Eigen::MatrixXd & full_mass_matrix,\nconst std::vector< std::string > & dof_names\n) const\n
"},{"location":"api/classrobot__dart_1_1Robot/#function-_post_addition","title":"function _post_addition","text":"
inline virtual void robot_dart::Robot::_post_addition (\nRobotDARTSimu *\n) 
"},{"location":"api/classrobot__dart_1_1Robot/#function-_post_removal","title":"function _post_removal","text":"
inline virtual void robot_dart::Robot::_post_removal (\nRobotDARTSimu *\n) 
"},{"location":"api/classrobot__dart_1_1Robot/#function-_set_actuator_type","title":"function _set_actuator_type","text":"
void robot_dart::Robot::_set_actuator_type (\nsize_t joint_index,\ndart::dynamics::Joint::ActuatorType type,\nbool override_mimic=false,\nbool override_base=false\n) 
"},{"location":"api/classrobot__dart_1_1Robot/#function-_set_actuator_types-12","title":"function _set_actuator_types [\u00bd]","text":"
void robot_dart::Robot::_set_actuator_types (\nconst std::vector< dart::dynamics::Joint::ActuatorType > & types,\nbool override_mimic=false,\nbool override_base=false\n) 
"},{"location":"api/classrobot__dart_1_1Robot/#function-_set_actuator_types-22","title":"function _set_actuator_types [2/2]","text":"
void robot_dart::Robot::_set_actuator_types (\ndart::dynamics::Joint::ActuatorType type,\nbool override_mimic=false,\nbool override_base=false\n) 
"},{"location":"api/classrobot__dart_1_1Robot/#function-_set_color_mode-12","title":"function _set_color_mode [\u00bd]","text":"
void robot_dart::Robot::_set_color_mode (\ndart::dynamics::MeshShape::ColorMode color_mode,\ndart::dynamics::SkeletonPtr skel\n) 
"},{"location":"api/classrobot__dart_1_1Robot/#function-_set_color_mode-22","title":"function _set_color_mode [2/2]","text":"
void robot_dart::Robot::_set_color_mode (\ndart::dynamics::MeshShape::ColorMode color_mode,\ndart::dynamics::ShapeNode * sn\n) 

The documentation for this class was generated from the following file robot_dart/robot.hpp

"},{"location":"api/classrobot__dart_1_1RobotDARTSimu/","title":"Class robot_dart::RobotDARTSimu","text":"

ClassList > robot_dart > RobotDARTSimu

"},{"location":"api/classrobot__dart_1_1RobotDARTSimu/#public-types","title":"Public Types","text":"Type Name typedef std::shared_ptr< Robot > robot_t"},{"location":"api/classrobot__dart_1_1RobotDARTSimu/#public-functions","title":"Public Functions","text":"Type Name RobotDARTSimu (double timestep=0.015) std::shared_ptr< Robot > add_checkerboard_floor (double floor_width=10.0, double floor_height=0.1, double size=1., const Eigen::Isometry3d & tf=Eigen::Isometry3d::Identity(), const std::string & floor_name=\"checkerboard_floor\", const Eigen::Vector4d & first_color=dart::Color::White(1.), const Eigen::Vector4d & second_color=dart::Color::Gray(1.)) std::shared_ptr< Robot > add_floor (double floor_width=10.0, double floor_height=0.1, const Eigen::Isometry3d & tf=Eigen::Isometry3d::Identity(), const std::string & floor_name=\"floor\") void add_robot (const robot_t & robot) std::shared_ptr< T > add_sensor (Args &&... args) void add_sensor (const std::shared_ptr< sensor::Sensor > & sensor) std::shared_ptr< simu::TextData > add_text (const std::string & text, const Eigen::Affine2d & tf=Eigen::Affine2d::Identity(), Eigen::Vector4d color=Eigen::Vector4d(1, 1, 1, 1), std::uint8_t alignment=(1|3<< 3), bool draw_bg=false, Eigen::Vector4d bg_color=Eigen::Vector4d(0, 0, 0, 0.75), double font_size=28) void add_visual_robot (const robot_t & robot) void clear_robots () void clear_sensors () uint32_t collision_category (size_t robot_index, const std::string & body_name) uint32_t collision_category (size_t robot_index, size_t body_index) const std::string & collision_detector () const uint32_t collision_mask (size_t robot_index, const std::string & body_name) uint32_t collision_mask (size_t robot_index, size_t body_index) std::pair< uint32_t, uint32_t > collision_masks (size_t robot_index, const std::string & body_name) std::pair< uint32_t, uint32_t > collision_masks (size_t robot_index, size_t body_index) int control_freq () const void enable_status_bar (bool enable=true, double font_size=-1) void enable_text_panel (bool enable=true, double font_size=-1) std::shared_ptr< gui::Base > graphics () const int graphics_freq () const Eigen::Vector3d gravity () const simu::GUIData * gui_data () bool halted_sim () const size_t num_robots () const int physics_freq () const void remove_all_collision_masks () void remove_collision_masks (size_t robot_index) void remove_collision_masks (size_t robot_index, const std::string & body_name) void remove_collision_masks (size_t robot_index, size_t body_index) void remove_robot (const robot_t & robot) void remove_robot (size_t index) void remove_sensor (const std::shared_ptr< sensor::Sensor > & sensor) void remove_sensor (size_t index) void remove_sensors (const std::string & type) robot_t robot (size_t index) const int robot_index (const robot_t & robot) const const std::vector< robot_t > & robots () const void run (double max_duration=5.0, bool reset_commands=false, bool force_position_bounds=true) bool schedule (int freq) Scheduler & scheduler () const Scheduler & scheduler () const std::shared_ptr< sensor::Sensor > sensor (size_t index) const std::vector< std::shared_ptr< sensor::Sensor > > sensors () const void set_collision_detector (const std::string & collision_detector) void set_collision_masks (size_t robot_index, uint32_t category_mask, uint32_t collision_mask) void set_collision_masks (size_t robot_index, const std::string & body_name, uint32_t category_mask, uint32_t collision_mask) void set_collision_masks (size_t robot_index, size_t body_index, uint32_t category_mask, uint32_t collision_mask) void set_control_freq (int frequency) void set_graphics (const std::shared_ptr< gui::Base > & graphics) void set_graphics_freq (int frequency) void set_gravity (const Eigen::Vector3d & gravity) void set_text_panel (const std::string & str) void set_timestep (double timestep, bool update_control_freq=true) std::string status_bar_text () const bool step (bool reset_commands=false, bool force_position_bounds=true) bool step_world (bool reset_commands=false, bool force_position_bounds=true) void stop_sim (bool disable=true) std::string text_panel_text () const double timestep () const dart::simulation::WorldPtr world () ~RobotDARTSimu ()"},{"location":"api/classrobot__dart_1_1RobotDARTSimu/#protected-attributes","title":"Protected Attributes","text":"Type Name bool _break int _control_freq = = -1 std::shared_ptr< gui::Base > _graphics int _graphics_freq = = 40 std::unique_ptr< simu::GUIData > _gui_data size_t _old_index int _physics_freq = = -1 std::vector< robot_t > _robots Scheduler _scheduler std::vector< std::shared_ptr< sensor::Sensor > > _sensors std::shared_ptr< simu::TextData > _status_bar = = nullptr std::shared_ptr< simu::TextData > _text_panel = = nullptr dart::simulation::WorldPtr _world"},{"location":"api/classrobot__dart_1_1RobotDARTSimu/#protected-functions","title":"Protected Functions","text":"Type Name void _enable (std::shared_ptr< simu::TextData > & text, bool enable, double font_size)"},{"location":"api/classrobot__dart_1_1RobotDARTSimu/#public-types-documentation","title":"Public Types Documentation","text":""},{"location":"api/classrobot__dart_1_1RobotDARTSimu/#typedef-robot_t","title":"typedef robot_t","text":"
using robot_dart::RobotDARTSimu::robot_t =  std::shared_ptr<Robot>;\n
"},{"location":"api/classrobot__dart_1_1RobotDARTSimu/#public-functions-documentation","title":"Public Functions Documentation","text":""},{"location":"api/classrobot__dart_1_1RobotDARTSimu/#function-robotdartsimu","title":"function RobotDARTSimu","text":"
robot_dart::RobotDARTSimu::RobotDARTSimu (\ndouble timestep=0.015\n) 
"},{"location":"api/classrobot__dart_1_1RobotDARTSimu/#function-add_checkerboard_floor","title":"function add_checkerboard_floor","text":"
std::shared_ptr< Robot > robot_dart::RobotDARTSimu::add_checkerboard_floor (\ndouble floor_width=10.0,\ndouble floor_height=0.1,\ndouble size=1.,\nconst Eigen::Isometry3d & tf=Eigen::Isometry3d::Identity(),\nconst std::string & floor_name=\"checkerboard_floor\",\nconst Eigen::Vector4d & first_color=dart::Color::White(1.),\nconst Eigen::Vector4d & second_color=dart::Color::Gray(1.)\n) 
"},{"location":"api/classrobot__dart_1_1RobotDARTSimu/#function-add_floor","title":"function add_floor","text":"
std::shared_ptr< Robot > robot_dart::RobotDARTSimu::add_floor (\ndouble floor_width=10.0,\ndouble floor_height=0.1,\nconst Eigen::Isometry3d & tf=Eigen::Isometry3d::Identity(),\nconst std::string & floor_name=\"floor\"\n) 
"},{"location":"api/classrobot__dart_1_1RobotDARTSimu/#function-add_robot","title":"function add_robot","text":"
void robot_dart::RobotDARTSimu::add_robot (\nconst robot_t & robot\n) 
"},{"location":"api/classrobot__dart_1_1RobotDARTSimu/#function-add_sensor-12","title":"function add_sensor [\u00bd]","text":"
template<typename T typename T, typename... Args>\ninline std::shared_ptr< T > robot_dart::RobotDARTSimu::add_sensor (\nArgs &&... args\n) 
"},{"location":"api/classrobot__dart_1_1RobotDARTSimu/#function-add_sensor-22","title":"function add_sensor [2/2]","text":"
void robot_dart::RobotDARTSimu::add_sensor (\nconst std::shared_ptr< sensor::Sensor > & sensor\n) 
"},{"location":"api/classrobot__dart_1_1RobotDARTSimu/#function-add_text","title":"function add_text","text":"
std::shared_ptr< simu::TextData > robot_dart::RobotDARTSimu::add_text (\nconst std::string & text,\nconst Eigen::Affine2d & tf=Eigen::Affine2d::Identity(),\nEigen::Vector4d color=Eigen::Vector4d(1, 1, 1, 1),\nstd::uint8_t alignment=(1|3<< 3),\nbool draw_bg=false,\nEigen::Vector4d bg_color=Eigen::Vector4d(0, 0, 0, 0.75),\ndouble font_size=28\n) 
"},{"location":"api/classrobot__dart_1_1RobotDARTSimu/#function-add_visual_robot","title":"function add_visual_robot","text":"
void robot_dart::RobotDARTSimu::add_visual_robot (\nconst robot_t & robot\n) 
"},{"location":"api/classrobot__dart_1_1RobotDARTSimu/#function-clear_robots","title":"function clear_robots","text":"
void robot_dart::RobotDARTSimu::clear_robots () 
"},{"location":"api/classrobot__dart_1_1RobotDARTSimu/#function-clear_sensors","title":"function clear_sensors","text":"
void robot_dart::RobotDARTSimu::clear_sensors () 
"},{"location":"api/classrobot__dart_1_1RobotDARTSimu/#function-collision_category-12","title":"function collision_category [\u00bd]","text":"
uint32_t robot_dart::RobotDARTSimu::collision_category (\nsize_t robot_index,\nconst std::string & body_name\n) 
"},{"location":"api/classrobot__dart_1_1RobotDARTSimu/#function-collision_category-22","title":"function collision_category [2/2]","text":"
uint32_t robot_dart::RobotDARTSimu::collision_category (\nsize_t robot_index,\nsize_t body_index\n) 
"},{"location":"api/classrobot__dart_1_1RobotDARTSimu/#function-collision_detector","title":"function collision_detector","text":"
const std::string & robot_dart::RobotDARTSimu::collision_detector () const\n
"},{"location":"api/classrobot__dart_1_1RobotDARTSimu/#function-collision_mask-12","title":"function collision_mask [\u00bd]","text":"
uint32_t robot_dart::RobotDARTSimu::collision_mask (\nsize_t robot_index,\nconst std::string & body_name\n) 
"},{"location":"api/classrobot__dart_1_1RobotDARTSimu/#function-collision_mask-22","title":"function collision_mask [2/2]","text":"
uint32_t robot_dart::RobotDARTSimu::collision_mask (\nsize_t robot_index,\nsize_t body_index\n) 
"},{"location":"api/classrobot__dart_1_1RobotDARTSimu/#function-collision_masks-12","title":"function collision_masks [\u00bd]","text":"
std::pair< uint32_t, uint32_t > robot_dart::RobotDARTSimu::collision_masks (\nsize_t robot_index,\nconst std::string & body_name\n) 
"},{"location":"api/classrobot__dart_1_1RobotDARTSimu/#function-collision_masks-22","title":"function collision_masks [2/2]","text":"
std::pair< uint32_t, uint32_t > robot_dart::RobotDARTSimu::collision_masks (\nsize_t robot_index,\nsize_t body_index\n) 
"},{"location":"api/classrobot__dart_1_1RobotDARTSimu/#function-control_freq","title":"function control_freq","text":"
inline int robot_dart::RobotDARTSimu::control_freq () const\n
"},{"location":"api/classrobot__dart_1_1RobotDARTSimu/#function-enable_status_bar","title":"function enable_status_bar","text":"
void robot_dart::RobotDARTSimu::enable_status_bar (\nbool enable=true,\ndouble font_size=-1\n) 
"},{"location":"api/classrobot__dart_1_1RobotDARTSimu/#function-enable_text_panel","title":"function enable_text_panel","text":"
void robot_dart::RobotDARTSimu::enable_text_panel (\nbool enable=true,\ndouble font_size=-1\n) 
"},{"location":"api/classrobot__dart_1_1RobotDARTSimu/#function-graphics","title":"function graphics","text":"
std::shared_ptr< gui::Base > robot_dart::RobotDARTSimu::graphics () const\n
"},{"location":"api/classrobot__dart_1_1RobotDARTSimu/#function-graphics_freq","title":"function graphics_freq","text":"
inline int robot_dart::RobotDARTSimu::graphics_freq () const\n
"},{"location":"api/classrobot__dart_1_1RobotDARTSimu/#function-gravity","title":"function gravity","text":"
Eigen::Vector3d robot_dart::RobotDARTSimu::gravity () const\n
"},{"location":"api/classrobot__dart_1_1RobotDARTSimu/#function-gui_data","title":"function gui_data","text":"
simu::GUIData * robot_dart::RobotDARTSimu::gui_data () 
"},{"location":"api/classrobot__dart_1_1RobotDARTSimu/#function-halted_sim","title":"function halted_sim","text":"
bool robot_dart::RobotDARTSimu::halted_sim () const\n
"},{"location":"api/classrobot__dart_1_1RobotDARTSimu/#function-num_robots","title":"function num_robots","text":"
size_t robot_dart::RobotDARTSimu::num_robots () const\n
"},{"location":"api/classrobot__dart_1_1RobotDARTSimu/#function-physics_freq","title":"function physics_freq","text":"
inline int robot_dart::RobotDARTSimu::physics_freq () const\n
"},{"location":"api/classrobot__dart_1_1RobotDARTSimu/#function-remove_all_collision_masks","title":"function remove_all_collision_masks","text":"
void robot_dart::RobotDARTSimu::remove_all_collision_masks () 
"},{"location":"api/classrobot__dart_1_1RobotDARTSimu/#function-remove_collision_masks-13","title":"function remove_collision_masks [\u2153]","text":"
void robot_dart::RobotDARTSimu::remove_collision_masks (\nsize_t robot_index\n) 
"},{"location":"api/classrobot__dart_1_1RobotDARTSimu/#function-remove_collision_masks-23","title":"function remove_collision_masks [\u2154]","text":"
void robot_dart::RobotDARTSimu::remove_collision_masks (\nsize_t robot_index,\nconst std::string & body_name\n) 
"},{"location":"api/classrobot__dart_1_1RobotDARTSimu/#function-remove_collision_masks-33","title":"function remove_collision_masks [3/3]","text":"
void robot_dart::RobotDARTSimu::remove_collision_masks (\nsize_t robot_index,\nsize_t body_index\n) 
"},{"location":"api/classrobot__dart_1_1RobotDARTSimu/#function-remove_robot-12","title":"function remove_robot [\u00bd]","text":"
void robot_dart::RobotDARTSimu::remove_robot (\nconst robot_t & robot\n) 
"},{"location":"api/classrobot__dart_1_1RobotDARTSimu/#function-remove_robot-22","title":"function remove_robot [2/2]","text":"
void robot_dart::RobotDARTSimu::remove_robot (\nsize_t index\n) 
"},{"location":"api/classrobot__dart_1_1RobotDARTSimu/#function-remove_sensor-12","title":"function remove_sensor [\u00bd]","text":"
void robot_dart::RobotDARTSimu::remove_sensor (\nconst std::shared_ptr< sensor::Sensor > & sensor\n) 
"},{"location":"api/classrobot__dart_1_1RobotDARTSimu/#function-remove_sensor-22","title":"function remove_sensor [2/2]","text":"
void robot_dart::RobotDARTSimu::remove_sensor (\nsize_t index\n) 
"},{"location":"api/classrobot__dart_1_1RobotDARTSimu/#function-remove_sensors","title":"function remove_sensors","text":"
void robot_dart::RobotDARTSimu::remove_sensors (\nconst std::string & type\n) 
"},{"location":"api/classrobot__dart_1_1RobotDARTSimu/#function-robot","title":"function robot","text":"
robot_t robot_dart::RobotDARTSimu::robot (\nsize_t index\n) const\n
"},{"location":"api/classrobot__dart_1_1RobotDARTSimu/#function-robot_index","title":"function robot_index","text":"
int robot_dart::RobotDARTSimu::robot_index (\nconst robot_t & robot\n) const\n
"},{"location":"api/classrobot__dart_1_1RobotDARTSimu/#function-robots","title":"function robots","text":"
const std::vector< robot_t > & robot_dart::RobotDARTSimu::robots () const\n
"},{"location":"api/classrobot__dart_1_1RobotDARTSimu/#function-run","title":"function run","text":"
void robot_dart::RobotDARTSimu::run (\ndouble max_duration=5.0,\nbool reset_commands=false,\nbool force_position_bounds=true\n) 
"},{"location":"api/classrobot__dart_1_1RobotDARTSimu/#function-schedule","title":"function schedule","text":"
inline bool robot_dart::RobotDARTSimu::schedule (\nint freq\n) 
"},{"location":"api/classrobot__dart_1_1RobotDARTSimu/#function-scheduler-12","title":"function scheduler [\u00bd]","text":"
inline Scheduler & robot_dart::RobotDARTSimu::scheduler () 
"},{"location":"api/classrobot__dart_1_1RobotDARTSimu/#function-scheduler-22","title":"function scheduler [2/2]","text":"
inline const Scheduler & robot_dart::RobotDARTSimu::scheduler () const\n
"},{"location":"api/classrobot__dart_1_1RobotDARTSimu/#function-sensor","title":"function sensor","text":"
std::shared_ptr< sensor::Sensor > robot_dart::RobotDARTSimu::sensor (\nsize_t index\n) const\n
"},{"location":"api/classrobot__dart_1_1RobotDARTSimu/#function-sensors","title":"function sensors","text":"
std::vector< std::shared_ptr< sensor::Sensor > > robot_dart::RobotDARTSimu::sensors () const\n
"},{"location":"api/classrobot__dart_1_1RobotDARTSimu/#function-set_collision_detector","title":"function set_collision_detector","text":"
void robot_dart::RobotDARTSimu::set_collision_detector (\nconst std::string & collision_detector\n) 
"},{"location":"api/classrobot__dart_1_1RobotDARTSimu/#function-set_collision_masks-13","title":"function set_collision_masks [\u2153]","text":"
void robot_dart::RobotDARTSimu::set_collision_masks (\nsize_t robot_index,\nuint32_t category_mask,\nuint32_t collision_mask\n) 
"},{"location":"api/classrobot__dart_1_1RobotDARTSimu/#function-set_collision_masks-23","title":"function set_collision_masks [\u2154]","text":"
void robot_dart::RobotDARTSimu::set_collision_masks (\nsize_t robot_index,\nconst std::string & body_name,\nuint32_t category_mask,\nuint32_t collision_mask\n) 
"},{"location":"api/classrobot__dart_1_1RobotDARTSimu/#function-set_collision_masks-33","title":"function set_collision_masks [3/3]","text":"
void robot_dart::RobotDARTSimu::set_collision_masks (\nsize_t robot_index,\nsize_t body_index,\nuint32_t category_mask,\nuint32_t collision_mask\n) 
"},{"location":"api/classrobot__dart_1_1RobotDARTSimu/#function-set_control_freq","title":"function set_control_freq","text":"
inline void robot_dart::RobotDARTSimu::set_control_freq (\nint frequency\n) 
"},{"location":"api/classrobot__dart_1_1RobotDARTSimu/#function-set_graphics","title":"function set_graphics","text":"
void robot_dart::RobotDARTSimu::set_graphics (\nconst std::shared_ptr< gui::Base > & graphics\n) 
"},{"location":"api/classrobot__dart_1_1RobotDARTSimu/#function-set_graphics_freq","title":"function set_graphics_freq","text":"
inline void robot_dart::RobotDARTSimu::set_graphics_freq (\nint frequency\n) 
"},{"location":"api/classrobot__dart_1_1RobotDARTSimu/#function-set_gravity","title":"function set_gravity","text":"
void robot_dart::RobotDARTSimu::set_gravity (\nconst Eigen::Vector3d & gravity\n) 
"},{"location":"api/classrobot__dart_1_1RobotDARTSimu/#function-set_text_panel","title":"function set_text_panel","text":"
void robot_dart::RobotDARTSimu::set_text_panel (\nconst std::string & str\n) 
"},{"location":"api/classrobot__dart_1_1RobotDARTSimu/#function-set_timestep","title":"function set_timestep","text":"
void robot_dart::RobotDARTSimu::set_timestep (\ndouble timestep,\nbool update_control_freq=true\n) 
"},{"location":"api/classrobot__dart_1_1RobotDARTSimu/#function-status_bar_text","title":"function status_bar_text","text":"
std::string robot_dart::RobotDARTSimu::status_bar_text () const\n
"},{"location":"api/classrobot__dart_1_1RobotDARTSimu/#function-step","title":"function step","text":"
bool robot_dart::RobotDARTSimu::step (\nbool reset_commands=false,\nbool force_position_bounds=true\n) 
"},{"location":"api/classrobot__dart_1_1RobotDARTSimu/#function-step_world","title":"function step_world","text":"
bool robot_dart::RobotDARTSimu::step_world (\nbool reset_commands=false,\nbool force_position_bounds=true\n) 
"},{"location":"api/classrobot__dart_1_1RobotDARTSimu/#function-stop_sim","title":"function stop_sim","text":"
void robot_dart::RobotDARTSimu::stop_sim (\nbool disable=true\n) 
"},{"location":"api/classrobot__dart_1_1RobotDARTSimu/#function-text_panel_text","title":"function text_panel_text","text":"
std::string robot_dart::RobotDARTSimu::text_panel_text () const\n
"},{"location":"api/classrobot__dart_1_1RobotDARTSimu/#function-timestep","title":"function timestep","text":"
double robot_dart::RobotDARTSimu::timestep () const\n
"},{"location":"api/classrobot__dart_1_1RobotDARTSimu/#function-world","title":"function world","text":"
dart::simulation::WorldPtr robot_dart::RobotDARTSimu::world () 
"},{"location":"api/classrobot__dart_1_1RobotDARTSimu/#function-robotdartsimu_1","title":"function ~RobotDARTSimu","text":"
robot_dart::RobotDARTSimu::~RobotDARTSimu () 
"},{"location":"api/classrobot__dart_1_1RobotDARTSimu/#protected-attributes-documentation","title":"Protected Attributes Documentation","text":""},{"location":"api/classrobot__dart_1_1RobotDARTSimu/#variable-_break","title":"variable _break","text":"
bool robot_dart::RobotDARTSimu::_break;\n
"},{"location":"api/classrobot__dart_1_1RobotDARTSimu/#variable-_control_freq","title":"variable _control_freq","text":"
int robot_dart::RobotDARTSimu::_control_freq;\n
"},{"location":"api/classrobot__dart_1_1RobotDARTSimu/#variable-_graphics","title":"variable _graphics","text":"
std::shared_ptr<gui::Base> robot_dart::RobotDARTSimu::_graphics;\n
"},{"location":"api/classrobot__dart_1_1RobotDARTSimu/#variable-_graphics_freq","title":"variable _graphics_freq","text":"
int robot_dart::RobotDARTSimu::_graphics_freq;\n
"},{"location":"api/classrobot__dart_1_1RobotDARTSimu/#variable-_gui_data","title":"variable _gui_data","text":"
std::unique_ptr<simu::GUIData> robot_dart::RobotDARTSimu::_gui_data;\n
"},{"location":"api/classrobot__dart_1_1RobotDARTSimu/#variable-_old_index","title":"variable _old_index","text":"
size_t robot_dart::RobotDARTSimu::_old_index;\n
"},{"location":"api/classrobot__dart_1_1RobotDARTSimu/#variable-_physics_freq","title":"variable _physics_freq","text":"
int robot_dart::RobotDARTSimu::_physics_freq;\n
"},{"location":"api/classrobot__dart_1_1RobotDARTSimu/#variable-_robots","title":"variable _robots","text":"
std::vector<robot_t> robot_dart::RobotDARTSimu::_robots;\n
"},{"location":"api/classrobot__dart_1_1RobotDARTSimu/#variable-_scheduler","title":"variable _scheduler","text":"
Scheduler robot_dart::RobotDARTSimu::_scheduler;\n
"},{"location":"api/classrobot__dart_1_1RobotDARTSimu/#variable-_sensors","title":"variable _sensors","text":"
std::vector<std::shared_ptr<sensor::Sensor> > robot_dart::RobotDARTSimu::_sensors;\n
"},{"location":"api/classrobot__dart_1_1RobotDARTSimu/#variable-_status_bar","title":"variable _status_bar","text":"
std::shared_ptr<simu::TextData> robot_dart::RobotDARTSimu::_status_bar;\n
"},{"location":"api/classrobot__dart_1_1RobotDARTSimu/#variable-_text_panel","title":"variable _text_panel","text":"
std::shared_ptr<simu::TextData> robot_dart::RobotDARTSimu::_text_panel;\n
"},{"location":"api/classrobot__dart_1_1RobotDARTSimu/#variable-_world","title":"variable _world","text":"
dart::simulation::WorldPtr robot_dart::RobotDARTSimu::_world;\n
"},{"location":"api/classrobot__dart_1_1RobotDARTSimu/#protected-functions-documentation","title":"Protected Functions Documentation","text":""},{"location":"api/classrobot__dart_1_1RobotDARTSimu/#function-_enable","title":"function _enable","text":"
void robot_dart::RobotDARTSimu::_enable (\nstd::shared_ptr< simu::TextData > & text,\nbool enable,\ndouble font_size\n) 

The documentation for this class was generated from the following file robot_dart/robot_dart_simu.hpp

"},{"location":"api/classrobot__dart_1_1RobotPool/","title":"Class robot_dart::RobotPool","text":"

ClassList > robot_dart > RobotPool

"},{"location":"api/classrobot__dart_1_1RobotPool/#public-types","title":"Public Types","text":"Type Name typedef std::function< std::shared_ptr< Robot >()> robot_creator_t"},{"location":"api/classrobot__dart_1_1RobotPool/#public-functions","title":"Public Functions","text":"Type Name RobotPool (const robot_creator_t & robot_creator, size_t pool_size=32, bool verbose=true) RobotPool (const RobotPool &) = delete virtual void free_robot (const std::shared_ptr< Robot > & robot) virtual std::shared_ptr< Robot > get_robot (const std::string & name=\"robot\") const std::string & model_filename () const void operator= (const RobotPool &) = delete virtual ~RobotPool ()"},{"location":"api/classrobot__dart_1_1RobotPool/#protected-attributes","title":"Protected Attributes","text":"Type Name std::vector< bool > _free std::string _model_filename size_t _pool_size robot_creator_t _robot_creator std::mutex _skeleton_mutex std::vector< dart::dynamics::SkeletonPtr > _skeletons bool _verbose"},{"location":"api/classrobot__dart_1_1RobotPool/#protected-functions","title":"Protected Functions","text":"Type Name virtual void _reset_robot (const std::shared_ptr< Robot > & robot)"},{"location":"api/classrobot__dart_1_1RobotPool/#public-types-documentation","title":"Public Types Documentation","text":""},{"location":"api/classrobot__dart_1_1RobotPool/#typedef-robot_creator_t","title":"typedef robot_creator_t","text":"
using robot_dart::RobotPool::robot_creator_t =  std::function<std::shared_ptr<Robot>()>;\n
"},{"location":"api/classrobot__dart_1_1RobotPool/#public-functions-documentation","title":"Public Functions Documentation","text":""},{"location":"api/classrobot__dart_1_1RobotPool/#function-robotpool-12","title":"function RobotPool [\u00bd]","text":"
robot_dart::RobotPool::RobotPool (\nconst robot_creator_t & robot_creator,\nsize_t pool_size=32,\nbool verbose=true\n) 
"},{"location":"api/classrobot__dart_1_1RobotPool/#function-robotpool-22","title":"function RobotPool [2/2]","text":"
robot_dart::RobotPool::RobotPool (\nconst RobotPool &\n) = delete\n
"},{"location":"api/classrobot__dart_1_1RobotPool/#function-free_robot","title":"function free_robot","text":"
virtual void robot_dart::RobotPool::free_robot (\nconst std::shared_ptr< Robot > & robot\n) 
"},{"location":"api/classrobot__dart_1_1RobotPool/#function-get_robot","title":"function get_robot","text":"
virtual std::shared_ptr< Robot > robot_dart::RobotPool::get_robot (\nconst std::string & name=\"robot\"\n) 
"},{"location":"api/classrobot__dart_1_1RobotPool/#function-model_filename","title":"function model_filename","text":"
inline const std::string & robot_dart::RobotPool::model_filename () const\n
"},{"location":"api/classrobot__dart_1_1RobotPool/#function-operator","title":"function operator=","text":"
void robot_dart::RobotPool::operator= (\nconst RobotPool &\n) = delete\n
"},{"location":"api/classrobot__dart_1_1RobotPool/#function-robotpool","title":"function ~RobotPool","text":"
inline virtual robot_dart::RobotPool::~RobotPool () 
"},{"location":"api/classrobot__dart_1_1RobotPool/#protected-attributes-documentation","title":"Protected Attributes Documentation","text":""},{"location":"api/classrobot__dart_1_1RobotPool/#variable-_free","title":"variable _free","text":"
std::vector<bool> robot_dart::RobotPool::_free;\n
"},{"location":"api/classrobot__dart_1_1RobotPool/#variable-_model_filename","title":"variable _model_filename","text":"
std::string robot_dart::RobotPool::_model_filename;\n
"},{"location":"api/classrobot__dart_1_1RobotPool/#variable-_pool_size","title":"variable _pool_size","text":"
size_t robot_dart::RobotPool::_pool_size;\n
"},{"location":"api/classrobot__dart_1_1RobotPool/#variable-_robot_creator","title":"variable _robot_creator","text":"
robot_creator_t robot_dart::RobotPool::_robot_creator;\n
"},{"location":"api/classrobot__dart_1_1RobotPool/#variable-_skeleton_mutex","title":"variable _skeleton_mutex","text":"
std::mutex robot_dart::RobotPool::_skeleton_mutex;\n
"},{"location":"api/classrobot__dart_1_1RobotPool/#variable-_skeletons","title":"variable _skeletons","text":"
std::vector<dart::dynamics::SkeletonPtr> robot_dart::RobotPool::_skeletons;\n
"},{"location":"api/classrobot__dart_1_1RobotPool/#variable-_verbose","title":"variable _verbose","text":"
bool robot_dart::RobotPool::_verbose;\n
"},{"location":"api/classrobot__dart_1_1RobotPool/#protected-functions-documentation","title":"Protected Functions Documentation","text":""},{"location":"api/classrobot__dart_1_1RobotPool/#function-_reset_robot","title":"function _reset_robot","text":"
virtual void robot_dart::RobotPool::_reset_robot (\nconst std::shared_ptr< Robot > & robot\n) 

The documentation for this class was generated from the following file robot_dart/robot_pool.hpp

"},{"location":"api/classrobot__dart_1_1Scheduler/","title":"Class robot_dart::Scheduler","text":"

ClassList > robot_dart > Scheduler

"},{"location":"api/classrobot__dart_1_1Scheduler/#public-functions","title":"Public Functions","text":"Type Name Scheduler (double dt, bool sync=false) double current_time () constcurrent time according to the simulation (simulation clock) double dt () constdt used by the simulation (simulation clock) double it_duration () const double last_it_duration () const double next_time () constnext time according to the simulation (simulation clock) bool operator() (int frequency) double real_time () consttime according to the clock's computer (wall clock) double real_time_factor () const void reset (double dt, bool sync=false, double current_time=0., double real_time=0.) bool schedule (int frequency) void set_sync (bool enable) double step () bool sync () const"},{"location":"api/classrobot__dart_1_1Scheduler/#protected-types","title":"Protected Types","text":"Type Name typedef std::chrono::high_resolution_clock clock_t"},{"location":"api/classrobot__dart_1_1Scheduler/#protected-attributes","title":"Protected Attributes","text":"Type Name double _average_it_duration = = 0. int _current_step = = 0 double _current_time = = 0. double _dt double _it_duration = = 0. clock_t::time_point _last_iteration_time int _max_frequency = = -1 double _real_start_time = = 0. double _real_time = = 0. double _simu_start_time = = 0. clock_t::time_point _start_time bool _sync"},{"location":"api/classrobot__dart_1_1Scheduler/#public-functions-documentation","title":"Public Functions Documentation","text":""},{"location":"api/classrobot__dart_1_1Scheduler/#function-scheduler","title":"function Scheduler","text":"
inline robot_dart::Scheduler::Scheduler (\ndouble dt,\nbool sync=false\n) 
"},{"location":"api/classrobot__dart_1_1Scheduler/#function-current_time","title":"function current_time","text":"
inline double robot_dart::Scheduler::current_time () const\n
"},{"location":"api/classrobot__dart_1_1Scheduler/#function-dt","title":"function dt","text":"
inline double robot_dart::Scheduler::dt () const\n
"},{"location":"api/classrobot__dart_1_1Scheduler/#function-it_duration","title":"function it_duration","text":"
inline double robot_dart::Scheduler::it_duration () const\n
"},{"location":"api/classrobot__dart_1_1Scheduler/#function-last_it_duration","title":"function last_it_duration","text":"
inline double robot_dart::Scheduler::last_it_duration () const\n
"},{"location":"api/classrobot__dart_1_1Scheduler/#function-next_time","title":"function next_time","text":"
inline double robot_dart::Scheduler::next_time () const\n
"},{"location":"api/classrobot__dart_1_1Scheduler/#function-operator","title":"function operator()","text":"
inline bool robot_dart::Scheduler::operator() (\nint frequency\n) 
"},{"location":"api/classrobot__dart_1_1Scheduler/#function-real_time","title":"function real_time","text":"
inline double robot_dart::Scheduler::real_time () const\n
"},{"location":"api/classrobot__dart_1_1Scheduler/#function-real_time_factor","title":"function real_time_factor","text":"
inline double robot_dart::Scheduler::real_time_factor () const\n
"},{"location":"api/classrobot__dart_1_1Scheduler/#function-reset","title":"function reset","text":"
void robot_dart::Scheduler::reset (\ndouble dt,\nbool sync=false,\ndouble current_time=0.,\ndouble real_time=0.\n) 
"},{"location":"api/classrobot__dart_1_1Scheduler/#function-schedule","title":"function schedule","text":"
bool robot_dart::Scheduler::schedule (\nint frequency\n) 
"},{"location":"api/classrobot__dart_1_1Scheduler/#function-set_sync","title":"function set_sync","text":"
inline void robot_dart::Scheduler::set_sync (\nbool enable\n) 

synchronize the simulation clock with the wall clock (when possible, i.e. when the simulation is faster than real time)

"},{"location":"api/classrobot__dart_1_1Scheduler/#function-step","title":"function step","text":"
double robot_dart::Scheduler::step () 

call this at the end of the loop (see examples) this will synchronize with real time if requested and increase the counter; returns the real-time (in seconds)

"},{"location":"api/classrobot__dart_1_1Scheduler/#function-sync","title":"function sync","text":"
inline bool robot_dart::Scheduler::sync () const\n
"},{"location":"api/classrobot__dart_1_1Scheduler/#protected-types-documentation","title":"Protected Types Documentation","text":""},{"location":"api/classrobot__dart_1_1Scheduler/#typedef-clock_t","title":"typedef clock_t","text":"
using robot_dart::Scheduler::clock_t =  std::chrono::high_resolution_clock;\n
"},{"location":"api/classrobot__dart_1_1Scheduler/#protected-attributes-documentation","title":"Protected Attributes Documentation","text":""},{"location":"api/classrobot__dart_1_1Scheduler/#variable-_average_it_duration","title":"variable _average_it_duration","text":"
double robot_dart::Scheduler::_average_it_duration;\n
"},{"location":"api/classrobot__dart_1_1Scheduler/#variable-_current_step","title":"variable _current_step","text":"
int robot_dart::Scheduler::_current_step;\n
"},{"location":"api/classrobot__dart_1_1Scheduler/#variable-_current_time","title":"variable _current_time","text":"
double robot_dart::Scheduler::_current_time;\n
"},{"location":"api/classrobot__dart_1_1Scheduler/#variable-_dt","title":"variable _dt","text":"
double robot_dart::Scheduler::_dt;\n
"},{"location":"api/classrobot__dart_1_1Scheduler/#variable-_it_duration","title":"variable _it_duration","text":"
double robot_dart::Scheduler::_it_duration;\n
"},{"location":"api/classrobot__dart_1_1Scheduler/#variable-_last_iteration_time","title":"variable _last_iteration_time","text":"
clock_t::time_point robot_dart::Scheduler::_last_iteration_time;\n
"},{"location":"api/classrobot__dart_1_1Scheduler/#variable-_max_frequency","title":"variable _max_frequency","text":"
int robot_dart::Scheduler::_max_frequency;\n
"},{"location":"api/classrobot__dart_1_1Scheduler/#variable-_real_start_time","title":"variable _real_start_time","text":"
double robot_dart::Scheduler::_real_start_time;\n
"},{"location":"api/classrobot__dart_1_1Scheduler/#variable-_real_time","title":"variable _real_time","text":"
double robot_dart::Scheduler::_real_time;\n
"},{"location":"api/classrobot__dart_1_1Scheduler/#variable-_simu_start_time","title":"variable _simu_start_time","text":"
double robot_dart::Scheduler::_simu_start_time;\n
"},{"location":"api/classrobot__dart_1_1Scheduler/#variable-_start_time","title":"variable _start_time","text":"
clock_t::time_point robot_dart::Scheduler::_start_time;\n
"},{"location":"api/classrobot__dart_1_1Scheduler/#variable-_sync","title":"variable _sync","text":"
bool robot_dart::Scheduler::_sync;\n

The documentation for this class was generated from the following file robot_dart/scheduler.hpp

"},{"location":"api/namespacerobot__dart_1_1collision__filter/","title":"Namespace robot_dart::collision_filter","text":"

Namespace List > robot_dart > collision_filter

"},{"location":"api/namespacerobot__dart_1_1collision__filter/#classes","title":"Classes","text":"Type Name class BitmaskContactFilter

The documentation for this class was generated from the following file robot_dart/robot_dart_simu.cpp

"},{"location":"api/classrobot__dart_1_1collision__filter_1_1BitmaskContactFilter/","title":"Class robot_dart::collision_filter::BitmaskContactFilter","text":"

ClassList > robot_dart > collision_filter > BitmaskContactFilter

Inherits the following classes: dart::collision::BodyNodeCollisionFilter

"},{"location":"api/classrobot__dart_1_1collision__filter_1_1BitmaskContactFilter/#classes","title":"Classes","text":"Type Name struct Masks"},{"location":"api/classrobot__dart_1_1collision__filter_1_1BitmaskContactFilter/#public-types","title":"Public Types","text":"Type Name typedef const dart::collision::CollisionObject * DartCollisionConstPtr typedef const dart::dynamics::ShapeNode * DartShapeConstPtr"},{"location":"api/classrobot__dart_1_1collision__filter_1_1BitmaskContactFilter/#public-functions","title":"Public Functions","text":"Type Name void add_to_map (DartShapeConstPtr shape, uint32_t col_mask, uint32_t cat_mask) void add_to_map (dart::dynamics::SkeletonPtr skel, uint32_t col_mask, uint32_t cat_mask) void clear_all () bool ignoresCollision (DartCollisionConstPtr object1, DartCollisionConstPtr object2) override const Masks mask (DartShapeConstPtr shape) const void remove_from_map (DartShapeConstPtr shape) void remove_from_map (dart::dynamics::SkeletonPtr skel) virtual ~BitmaskContactFilter () = default"},{"location":"api/classrobot__dart_1_1collision__filter_1_1BitmaskContactFilter/#public-types-documentation","title":"Public Types Documentation","text":""},{"location":"api/classrobot__dart_1_1collision__filter_1_1BitmaskContactFilter/#typedef-dartcollisionconstptr","title":"typedef DartCollisionConstPtr","text":"
using robot_dart::collision_filter::BitmaskContactFilter::DartCollisionConstPtr =  const dart::collision::CollisionObject*;\n
"},{"location":"api/classrobot__dart_1_1collision__filter_1_1BitmaskContactFilter/#typedef-dartshapeconstptr","title":"typedef DartShapeConstPtr","text":"
using robot_dart::collision_filter::BitmaskContactFilter::DartShapeConstPtr =  const dart::dynamics::ShapeNode*;\n
"},{"location":"api/classrobot__dart_1_1collision__filter_1_1BitmaskContactFilter/#public-functions-documentation","title":"Public Functions Documentation","text":""},{"location":"api/classrobot__dart_1_1collision__filter_1_1BitmaskContactFilter/#function-add_to_map-12","title":"function add_to_map [\u00bd]","text":"
inline void robot_dart::collision_filter::BitmaskContactFilter::add_to_map (\nDartShapeConstPtr shape,\nuint32_t col_mask,\nuint32_t cat_mask\n) 
"},{"location":"api/classrobot__dart_1_1collision__filter_1_1BitmaskContactFilter/#function-add_to_map-22","title":"function add_to_map [2/2]","text":"
inline void robot_dart::collision_filter::BitmaskContactFilter::add_to_map (\ndart::dynamics::SkeletonPtr skel,\nuint32_t col_mask,\nuint32_t cat_mask\n) 
"},{"location":"api/classrobot__dart_1_1collision__filter_1_1BitmaskContactFilter/#function-clear_all","title":"function clear_all","text":"
inline void robot_dart::collision_filter::BitmaskContactFilter::clear_all () 
"},{"location":"api/classrobot__dart_1_1collision__filter_1_1BitmaskContactFilter/#function-ignorescollision","title":"function ignoresCollision","text":"
inline bool robot_dart::collision_filter::BitmaskContactFilter::ignoresCollision (\nDartCollisionConstPtr object1,\nDartCollisionConstPtr object2\n) override const\n
"},{"location":"api/classrobot__dart_1_1collision__filter_1_1BitmaskContactFilter/#function-mask","title":"function mask","text":"
inline Masks robot_dart::collision_filter::BitmaskContactFilter::mask (\nDartShapeConstPtr shape\n) const\n
"},{"location":"api/classrobot__dart_1_1collision__filter_1_1BitmaskContactFilter/#function-remove_from_map-12","title":"function remove_from_map [\u00bd]","text":"
inline void robot_dart::collision_filter::BitmaskContactFilter::remove_from_map (\nDartShapeConstPtr shape\n) 
"},{"location":"api/classrobot__dart_1_1collision__filter_1_1BitmaskContactFilter/#function-remove_from_map-22","title":"function remove_from_map [2/2]","text":"
inline void robot_dart::collision_filter::BitmaskContactFilter::remove_from_map (\ndart::dynamics::SkeletonPtr skel\n) 
"},{"location":"api/classrobot__dart_1_1collision__filter_1_1BitmaskContactFilter/#function-bitmaskcontactfilter","title":"function ~BitmaskContactFilter","text":"
virtual robot_dart::collision_filter::BitmaskContactFilter::~BitmaskContactFilter () = default\n

The documentation for this class was generated from the following file robot_dart/robot_dart_simu.cpp

"},{"location":"api/structrobot__dart_1_1collision__filter_1_1BitmaskContactFilter_1_1Masks/","title":"Struct robot_dart::collision_filter::BitmaskContactFilter::Masks","text":"

ClassList > robot_dart > collision_filter > BitmaskContactFilter > Masks

"},{"location":"api/structrobot__dart_1_1collision__filter_1_1BitmaskContactFilter_1_1Masks/#public-attributes","title":"Public Attributes","text":"Type Name uint32_t category_mask = = 0xffffffff uint32_t collision_mask = = 0xffffffff"},{"location":"api/structrobot__dart_1_1collision__filter_1_1BitmaskContactFilter_1_1Masks/#public-attributes-documentation","title":"Public Attributes Documentation","text":""},{"location":"api/structrobot__dart_1_1collision__filter_1_1BitmaskContactFilter_1_1Masks/#variable-category_mask","title":"variable category_mask","text":"
uint32_t robot_dart::collision_filter::BitmaskContactFilter::Masks::category_mask;\n
"},{"location":"api/structrobot__dart_1_1collision__filter_1_1BitmaskContactFilter_1_1Masks/#variable-collision_mask","title":"variable collision_mask","text":"
uint32_t robot_dart::collision_filter::BitmaskContactFilter::Masks::collision_mask;\n

The documentation for this class was generated from the following file robot_dart/robot_dart_simu.cpp

"},{"location":"api/namespacerobot__dart_1_1control/","title":"Namespace robot_dart::control","text":"

Namespace List > robot_dart > control

"},{"location":"api/namespacerobot__dart_1_1control/#classes","title":"Classes","text":"Type Name class PDControl class PolicyControl <typename Policy> class RobotControl class SimpleControl

The documentation for this class was generated from the following file robot_dart/control/pd_control.cpp

"},{"location":"api/classrobot__dart_1_1control_1_1PDControl/","title":"Class robot_dart::control::PDControl","text":"

ClassList > robot_dart > control > PDControl

Inherits the following classes: robot_dart::control::RobotControl

"},{"location":"api/classrobot__dart_1_1control_1_1PDControl/#public-functions","title":"Public Functions","text":"Type Name PDControl () PDControl (const Eigen::VectorXd & ctrl, bool full_control=false, bool use_angular_errors=true) PDControl (const Eigen::VectorXd & ctrl, const std::vector< std::string > & controllable_dofs, bool use_angular_errors=true) virtual Eigen::VectorXd calculate (double) override virtual std::shared_ptr< RobotControl > clone () override const virtual void configure () override std::pair< Eigen::VectorXd, Eigen::VectorXd > pd () const void set_pd (double p, double d) void set_pd (const Eigen::VectorXd & p, const Eigen::VectorXd & d) void set_use_angular_errors (bool enable=true) bool using_angular_errors () const"},{"location":"api/classrobot__dart_1_1control_1_1PDControl/#public-functions-inherited-from-robot_dartcontrolrobotcontrol","title":"Public Functions inherited from robot_dart::control::RobotControl","text":"

See robot_dart::control::RobotControl

Type Name RobotControl () RobotControl (const Eigen::VectorXd & ctrl, bool full_control=false) RobotControl (const Eigen::VectorXd & ctrl, const std::vector< std::string > & controllable_dofs) void activate (bool enable=true) bool active () const virtual Eigen::VectorXd calculate (double t) = 0 virtual std::shared_ptr< RobotControl > clone () const = 0 virtual void configure () = 0 const std::vector< std::string > & controllable_dofs () const void init () const Eigen::VectorXd & parameters () const std::shared_ptr< Robot > robot () const void set_parameters (const Eigen::VectorXd & ctrl) void set_robot (const std::shared_ptr< Robot > & robot) void set_weight (double weight) double weight () const virtual ~RobotControl ()"},{"location":"api/classrobot__dart_1_1control_1_1PDControl/#protected-attributes","title":"Protected Attributes","text":"Type Name Eigen::VectorXd _Kd Eigen::VectorXd _Kp bool _use_angular_errors"},{"location":"api/classrobot__dart_1_1control_1_1PDControl/#protected-attributes-inherited-from-robot_dartcontrolrobotcontrol","title":"Protected Attributes inherited from robot_dart::control::RobotControl","text":"

See robot_dart::control::RobotControl

Type Name bool _active bool _check_free = = false int _control_dof std::vector< std::string > _controllable_dofs Eigen::VectorXd _ctrl int _dof std::weak_ptr< Robot > _robot double _weight"},{"location":"api/classrobot__dart_1_1control_1_1PDControl/#protected-static-functions","title":"Protected Static Functions","text":"Type Name double _angle_dist (double target, double current)"},{"location":"api/classrobot__dart_1_1control_1_1PDControl/#public-functions-documentation","title":"Public Functions Documentation","text":""},{"location":"api/classrobot__dart_1_1control_1_1PDControl/#function-pdcontrol-13","title":"function PDControl [\u2153]","text":"
robot_dart::control::PDControl::PDControl () 
"},{"location":"api/classrobot__dart_1_1control_1_1PDControl/#function-pdcontrol-23","title":"function PDControl [\u2154]","text":"
robot_dart::control::PDControl::PDControl (\nconst Eigen::VectorXd & ctrl,\nbool full_control=false,\nbool use_angular_errors=true\n) 
"},{"location":"api/classrobot__dart_1_1control_1_1PDControl/#function-pdcontrol-33","title":"function PDControl [3/3]","text":"
robot_dart::control::PDControl::PDControl (\nconst Eigen::VectorXd & ctrl,\nconst std::vector< std::string > & controllable_dofs,\nbool use_angular_errors=true\n) 
"},{"location":"api/classrobot__dart_1_1control_1_1PDControl/#function-calculate","title":"function calculate","text":"
virtual Eigen::VectorXd robot_dart::control::PDControl::calculate (\ndouble\n) override\n

Implements robot_dart::control::RobotControl::calculate

"},{"location":"api/classrobot__dart_1_1control_1_1PDControl/#function-clone","title":"function clone","text":"
virtual std::shared_ptr< RobotControl > robot_dart::control::PDControl::clone () override const\n

Implements robot_dart::control::RobotControl::clone

"},{"location":"api/classrobot__dart_1_1control_1_1PDControl/#function-configure","title":"function configure","text":"
virtual void robot_dart::control::PDControl::configure () override\n

Implements robot_dart::control::RobotControl::configure

"},{"location":"api/classrobot__dart_1_1control_1_1PDControl/#function-pd","title":"function pd","text":"
std::pair< Eigen::VectorXd, Eigen::VectorXd > robot_dart::control::PDControl::pd () const\n
"},{"location":"api/classrobot__dart_1_1control_1_1PDControl/#function-set_pd-12","title":"function set_pd [\u00bd]","text":"
void robot_dart::control::PDControl::set_pd (\ndouble p,\ndouble d\n) 
"},{"location":"api/classrobot__dart_1_1control_1_1PDControl/#function-set_pd-22","title":"function set_pd [2/2]","text":"
void robot_dart::control::PDControl::set_pd (\nconst Eigen::VectorXd & p,\nconst Eigen::VectorXd & d\n) 
"},{"location":"api/classrobot__dart_1_1control_1_1PDControl/#function-set_use_angular_errors","title":"function set_use_angular_errors","text":"
void robot_dart::control::PDControl::set_use_angular_errors (\nbool enable=true\n) 
"},{"location":"api/classrobot__dart_1_1control_1_1PDControl/#function-using_angular_errors","title":"function using_angular_errors","text":"
bool robot_dart::control::PDControl::using_angular_errors () const\n
"},{"location":"api/classrobot__dart_1_1control_1_1PDControl/#protected-attributes-documentation","title":"Protected Attributes Documentation","text":""},{"location":"api/classrobot__dart_1_1control_1_1PDControl/#variable-_kd","title":"variable _Kd","text":"
Eigen::VectorXd robot_dart::control::PDControl::_Kd;\n
"},{"location":"api/classrobot__dart_1_1control_1_1PDControl/#variable-_kp","title":"variable _Kp","text":"
Eigen::VectorXd robot_dart::control::PDControl::_Kp;\n
"},{"location":"api/classrobot__dart_1_1control_1_1PDControl/#variable-_use_angular_errors","title":"variable _use_angular_errors","text":"
bool robot_dart::control::PDControl::_use_angular_errors;\n
"},{"location":"api/classrobot__dart_1_1control_1_1PDControl/#protected-static-functions-documentation","title":"Protected Static Functions Documentation","text":""},{"location":"api/classrobot__dart_1_1control_1_1PDControl/#function-_angle_dist","title":"function _angle_dist","text":"
static double robot_dart::control::PDControl::_angle_dist (\ndouble target,\ndouble current\n) 

The documentation for this class was generated from the following file robot_dart/control/pd_control.hpp

"},{"location":"api/classrobot__dart_1_1control_1_1PolicyControl/","title":"Class robot_dart::control::PolicyControl","text":"

template <typename Policy typename Policy>

ClassList > robot_dart > control > PolicyControl

Inherits the following classes: robot_dart::control::RobotControl

"},{"location":"api/classrobot__dart_1_1control_1_1PolicyControl/#public-functions","title":"Public Functions","text":"Type Name PolicyControl () PolicyControl (double dt, const Eigen::VectorXd & ctrl, bool full_control=false) PolicyControl (const Eigen::VectorXd & ctrl, bool full_control=false) PolicyControl (double dt, const Eigen::VectorXd & ctrl, const std::vector< std::string > & controllable_dofs) PolicyControl (const Eigen::VectorXd & ctrl, const std::vector< std::string > & controllable_dofs) virtual Eigen::VectorXd calculate (double t) override virtual std::shared_ptr< RobotControl > clone () override const virtual void configure () override Eigen::VectorXd h_params () const void set_h_params (const Eigen::VectorXd & h_params)"},{"location":"api/classrobot__dart_1_1control_1_1PolicyControl/#public-functions-inherited-from-robot_dartcontrolrobotcontrol","title":"Public Functions inherited from robot_dart::control::RobotControl","text":"

See robot_dart::control::RobotControl

Type Name RobotControl () RobotControl (const Eigen::VectorXd & ctrl, bool full_control=false) RobotControl (const Eigen::VectorXd & ctrl, const std::vector< std::string > & controllable_dofs) void activate (bool enable=true) bool active () const virtual Eigen::VectorXd calculate (double t) = 0 virtual std::shared_ptr< RobotControl > clone () const = 0 virtual void configure () = 0 const std::vector< std::string > & controllable_dofs () const void init () const Eigen::VectorXd & parameters () const std::shared_ptr< Robot > robot () const void set_parameters (const Eigen::VectorXd & ctrl) void set_robot (const std::shared_ptr< Robot > & robot) void set_weight (double weight) double weight () const virtual ~RobotControl ()"},{"location":"api/classrobot__dart_1_1control_1_1PolicyControl/#protected-attributes","title":"Protected Attributes","text":"Type Name double _dt bool _first bool _full_dt int _i Policy _policy Eigen::VectorXd _prev_commands double _prev_time double _threshold"},{"location":"api/classrobot__dart_1_1control_1_1PolicyControl/#protected-attributes-inherited-from-robot_dartcontrolrobotcontrol","title":"Protected Attributes inherited from robot_dart::control::RobotControl","text":"

See robot_dart::control::RobotControl

Type Name bool _active bool _check_free = = false int _control_dof std::vector< std::string > _controllable_dofs Eigen::VectorXd _ctrl int _dof std::weak_ptr< Robot > _robot double _weight"},{"location":"api/classrobot__dart_1_1control_1_1PolicyControl/#public-functions-documentation","title":"Public Functions Documentation","text":""},{"location":"api/classrobot__dart_1_1control_1_1PolicyControl/#function-policycontrol-15","title":"function PolicyControl [\u2155]","text":"
inline robot_dart::control::PolicyControl::PolicyControl () 
"},{"location":"api/classrobot__dart_1_1control_1_1PolicyControl/#function-policycontrol-25","title":"function PolicyControl [\u2156]","text":"
inline robot_dart::control::PolicyControl::PolicyControl (\ndouble dt,\nconst Eigen::VectorXd & ctrl,\nbool full_control=false\n) 
"},{"location":"api/classrobot__dart_1_1control_1_1PolicyControl/#function-policycontrol-35","title":"function PolicyControl [\u2157]","text":"
inline robot_dart::control::PolicyControl::PolicyControl (\nconst Eigen::VectorXd & ctrl,\nbool full_control=false\n) 
"},{"location":"api/classrobot__dart_1_1control_1_1PolicyControl/#function-policycontrol-45","title":"function PolicyControl [\u2158]","text":"
inline robot_dart::control::PolicyControl::PolicyControl (\ndouble dt,\nconst Eigen::VectorXd & ctrl,\nconst std::vector< std::string > & controllable_dofs\n) 
"},{"location":"api/classrobot__dart_1_1control_1_1PolicyControl/#function-policycontrol-55","title":"function PolicyControl [5/5]","text":"
inline robot_dart::control::PolicyControl::PolicyControl (\nconst Eigen::VectorXd & ctrl,\nconst std::vector< std::string > & controllable_dofs\n) 
"},{"location":"api/classrobot__dart_1_1control_1_1PolicyControl/#function-calculate","title":"function calculate","text":"
inline virtual Eigen::VectorXd robot_dart::control::PolicyControl::calculate (\ndouble t\n) override\n

Implements robot_dart::control::RobotControl::calculate

"},{"location":"api/classrobot__dart_1_1control_1_1PolicyControl/#function-clone","title":"function clone","text":"
inline virtual std::shared_ptr< RobotControl > robot_dart::control::PolicyControl::clone () override const\n

Implements robot_dart::control::RobotControl::clone

"},{"location":"api/classrobot__dart_1_1control_1_1PolicyControl/#function-configure","title":"function configure","text":"
inline virtual void robot_dart::control::PolicyControl::configure () override\n

Implements robot_dart::control::RobotControl::configure

"},{"location":"api/classrobot__dart_1_1control_1_1PolicyControl/#function-h_params","title":"function h_params","text":"
inline Eigen::VectorXd robot_dart::control::PolicyControl::h_params () const\n
"},{"location":"api/classrobot__dart_1_1control_1_1PolicyControl/#function-set_h_params","title":"function set_h_params","text":"
inline void robot_dart::control::PolicyControl::set_h_params (\nconst Eigen::VectorXd & h_params\n) 
"},{"location":"api/classrobot__dart_1_1control_1_1PolicyControl/#protected-attributes-documentation","title":"Protected Attributes Documentation","text":""},{"location":"api/classrobot__dart_1_1control_1_1PolicyControl/#variable-_dt","title":"variable _dt","text":"
double robot_dart::control::PolicyControl< Policy >::_dt;\n
"},{"location":"api/classrobot__dart_1_1control_1_1PolicyControl/#variable-_first","title":"variable _first","text":"
bool robot_dart::control::PolicyControl< Policy >::_first;\n
"},{"location":"api/classrobot__dart_1_1control_1_1PolicyControl/#variable-_full_dt","title":"variable _full_dt","text":"
bool robot_dart::control::PolicyControl< Policy >::_full_dt;\n
"},{"location":"api/classrobot__dart_1_1control_1_1PolicyControl/#variable-_i","title":"variable _i","text":"
int robot_dart::control::PolicyControl< Policy >::_i;\n
"},{"location":"api/classrobot__dart_1_1control_1_1PolicyControl/#variable-_policy","title":"variable _policy","text":"
Policy robot_dart::control::PolicyControl< Policy >::_policy;\n
"},{"location":"api/classrobot__dart_1_1control_1_1PolicyControl/#variable-_prev_commands","title":"variable _prev_commands","text":"
Eigen::VectorXd robot_dart::control::PolicyControl< Policy >::_prev_commands;\n
"},{"location":"api/classrobot__dart_1_1control_1_1PolicyControl/#variable-_prev_time","title":"variable _prev_time","text":"
double robot_dart::control::PolicyControl< Policy >::_prev_time;\n
"},{"location":"api/classrobot__dart_1_1control_1_1PolicyControl/#variable-_threshold","title":"variable _threshold","text":"
double robot_dart::control::PolicyControl< Policy >::_threshold;\n

The documentation for this class was generated from the following file robot_dart/control/policy_control.hpp

"},{"location":"api/classrobot__dart_1_1control_1_1RobotControl/","title":"Class robot_dart::control::RobotControl","text":"

ClassList > robot_dart > control > RobotControl

Inherited by the following classes: robot_dart::control::PDControl, robot_dart::control::PolicyControl, robot_dart::control::SimpleControl

"},{"location":"api/classrobot__dart_1_1control_1_1RobotControl/#public-functions","title":"Public Functions","text":"Type Name RobotControl () RobotControl (const Eigen::VectorXd & ctrl, bool full_control=false) RobotControl (const Eigen::VectorXd & ctrl, const std::vector< std::string > & controllable_dofs) void activate (bool enable=true) bool active () const virtual Eigen::VectorXd calculate (double t) = 0 virtual std::shared_ptr< RobotControl > clone () const = 0 virtual void configure () = 0 const std::vector< std::string > & controllable_dofs () const void init () const Eigen::VectorXd & parameters () const std::shared_ptr< Robot > robot () const void set_parameters (const Eigen::VectorXd & ctrl) void set_robot (const std::shared_ptr< Robot > & robot) void set_weight (double weight) double weight () const virtual ~RobotControl ()"},{"location":"api/classrobot__dart_1_1control_1_1RobotControl/#protected-attributes","title":"Protected Attributes","text":"Type Name bool _active bool _check_free = = false int _control_dof std::vector< std::string > _controllable_dofs Eigen::VectorXd _ctrl int _dof std::weak_ptr< Robot > _robot double _weight"},{"location":"api/classrobot__dart_1_1control_1_1RobotControl/#public-functions-documentation","title":"Public Functions Documentation","text":""},{"location":"api/classrobot__dart_1_1control_1_1RobotControl/#function-robotcontrol-13","title":"function RobotControl [\u2153]","text":"
robot_dart::control::RobotControl::RobotControl () 
"},{"location":"api/classrobot__dart_1_1control_1_1RobotControl/#function-robotcontrol-23","title":"function RobotControl [\u2154]","text":"
robot_dart::control::RobotControl::RobotControl (\nconst Eigen::VectorXd & ctrl,\nbool full_control=false\n) 
"},{"location":"api/classrobot__dart_1_1control_1_1RobotControl/#function-robotcontrol-33","title":"function RobotControl [3/3]","text":"
robot_dart::control::RobotControl::RobotControl (\nconst Eigen::VectorXd & ctrl,\nconst std::vector< std::string > & controllable_dofs\n) 
"},{"location":"api/classrobot__dart_1_1control_1_1RobotControl/#function-activate","title":"function activate","text":"
void robot_dart::control::RobotControl::activate (\nbool enable=true\n) 
"},{"location":"api/classrobot__dart_1_1control_1_1RobotControl/#function-active","title":"function active","text":"
bool robot_dart::control::RobotControl::active () const\n
"},{"location":"api/classrobot__dart_1_1control_1_1RobotControl/#function-calculate","title":"function calculate","text":"
virtual Eigen::VectorXd robot_dart::control::RobotControl::calculate (\ndouble t\n) = 0\n
"},{"location":"api/classrobot__dart_1_1control_1_1RobotControl/#function-clone","title":"function clone","text":"
virtual std::shared_ptr< RobotControl > robot_dart::control::RobotControl::clone () const = 0\n
"},{"location":"api/classrobot__dart_1_1control_1_1RobotControl/#function-configure","title":"function configure","text":"
virtual void robot_dart::control::RobotControl::configure () = 0\n
"},{"location":"api/classrobot__dart_1_1control_1_1RobotControl/#function-controllable_dofs","title":"function controllable_dofs","text":"
const std::vector< std::string > & robot_dart::control::RobotControl::controllable_dofs () const\n
"},{"location":"api/classrobot__dart_1_1control_1_1RobotControl/#function-init","title":"function init","text":"
void robot_dart::control::RobotControl::init () 
"},{"location":"api/classrobot__dart_1_1control_1_1RobotControl/#function-parameters","title":"function parameters","text":"
const Eigen::VectorXd & robot_dart::control::RobotControl::parameters () const\n
"},{"location":"api/classrobot__dart_1_1control_1_1RobotControl/#function-robot","title":"function robot","text":"
std::shared_ptr< Robot > robot_dart::control::RobotControl::robot () const\n
"},{"location":"api/classrobot__dart_1_1control_1_1RobotControl/#function-set_parameters","title":"function set_parameters","text":"
void robot_dart::control::RobotControl::set_parameters (\nconst Eigen::VectorXd & ctrl\n) 
"},{"location":"api/classrobot__dart_1_1control_1_1RobotControl/#function-set_robot","title":"function set_robot","text":"
void robot_dart::control::RobotControl::set_robot (\nconst std::shared_ptr< Robot > & robot\n) 
"},{"location":"api/classrobot__dart_1_1control_1_1RobotControl/#function-set_weight","title":"function set_weight","text":"
void robot_dart::control::RobotControl::set_weight (\ndouble weight\n) 
"},{"location":"api/classrobot__dart_1_1control_1_1RobotControl/#function-weight","title":"function weight","text":"
double robot_dart::control::RobotControl::weight () const\n
"},{"location":"api/classrobot__dart_1_1control_1_1RobotControl/#function-robotcontrol","title":"function ~RobotControl","text":"
inline virtual robot_dart::control::RobotControl::~RobotControl () 
"},{"location":"api/classrobot__dart_1_1control_1_1RobotControl/#protected-attributes-documentation","title":"Protected Attributes Documentation","text":""},{"location":"api/classrobot__dart_1_1control_1_1RobotControl/#variable-_active","title":"variable _active","text":"
bool robot_dart::control::RobotControl::_active;\n
"},{"location":"api/classrobot__dart_1_1control_1_1RobotControl/#variable-_check_free","title":"variable _check_free","text":"
bool robot_dart::control::RobotControl::_check_free;\n
"},{"location":"api/classrobot__dart_1_1control_1_1RobotControl/#variable-_control_dof","title":"variable _control_dof","text":"
int robot_dart::control::RobotControl::_control_dof;\n
"},{"location":"api/classrobot__dart_1_1control_1_1RobotControl/#variable-_controllable_dofs","title":"variable _controllable_dofs","text":"
std::vector<std::string> robot_dart::control::RobotControl::_controllable_dofs;\n
"},{"location":"api/classrobot__dart_1_1control_1_1RobotControl/#variable-_ctrl","title":"variable _ctrl","text":"
Eigen::VectorXd robot_dart::control::RobotControl::_ctrl;\n
"},{"location":"api/classrobot__dart_1_1control_1_1RobotControl/#variable-_dof","title":"variable _dof","text":"
int robot_dart::control::RobotControl::_dof;\n
"},{"location":"api/classrobot__dart_1_1control_1_1RobotControl/#variable-_robot","title":"variable _robot","text":"
std::weak_ptr<Robot> robot_dart::control::RobotControl::_robot;\n
"},{"location":"api/classrobot__dart_1_1control_1_1RobotControl/#variable-_weight","title":"variable _weight","text":"
double robot_dart::control::RobotControl::_weight;\n

The documentation for this class was generated from the following file robot_dart/control/robot_control.hpp

"},{"location":"api/classrobot__dart_1_1control_1_1SimpleControl/","title":"Class robot_dart::control::SimpleControl","text":"

ClassList > robot_dart > control > SimpleControl

Inherits the following classes: robot_dart::control::RobotControl

"},{"location":"api/classrobot__dart_1_1control_1_1SimpleControl/#public-functions","title":"Public Functions","text":"Type Name SimpleControl () SimpleControl (const Eigen::VectorXd & ctrl, bool full_control=false) SimpleControl (const Eigen::VectorXd & ctrl, const std::vector< std::string > & controllable_dofs) virtual Eigen::VectorXd calculate (double) override virtual std::shared_ptr< RobotControl > clone () override const virtual void configure () override"},{"location":"api/classrobot__dart_1_1control_1_1SimpleControl/#public-functions-inherited-from-robot_dartcontrolrobotcontrol","title":"Public Functions inherited from robot_dart::control::RobotControl","text":"

See robot_dart::control::RobotControl

Type Name RobotControl () RobotControl (const Eigen::VectorXd & ctrl, bool full_control=false) RobotControl (const Eigen::VectorXd & ctrl, const std::vector< std::string > & controllable_dofs) void activate (bool enable=true) bool active () const virtual Eigen::VectorXd calculate (double t) = 0 virtual std::shared_ptr< RobotControl > clone () const = 0 virtual void configure () = 0 const std::vector< std::string > & controllable_dofs () const void init () const Eigen::VectorXd & parameters () const std::shared_ptr< Robot > robot () const void set_parameters (const Eigen::VectorXd & ctrl) void set_robot (const std::shared_ptr< Robot > & robot) void set_weight (double weight) double weight () const virtual ~RobotControl ()"},{"location":"api/classrobot__dart_1_1control_1_1SimpleControl/#protected-attributes-inherited-from-robot_dartcontrolrobotcontrol","title":"Protected Attributes inherited from robot_dart::control::RobotControl","text":"

See robot_dart::control::RobotControl

Type Name bool _active bool _check_free = = false int _control_dof std::vector< std::string > _controllable_dofs Eigen::VectorXd _ctrl int _dof std::weak_ptr< Robot > _robot double _weight"},{"location":"api/classrobot__dart_1_1control_1_1SimpleControl/#public-functions-documentation","title":"Public Functions Documentation","text":""},{"location":"api/classrobot__dart_1_1control_1_1SimpleControl/#function-simplecontrol-13","title":"function SimpleControl [\u2153]","text":"
robot_dart::control::SimpleControl::SimpleControl () 
"},{"location":"api/classrobot__dart_1_1control_1_1SimpleControl/#function-simplecontrol-23","title":"function SimpleControl [\u2154]","text":"
robot_dart::control::SimpleControl::SimpleControl (\nconst Eigen::VectorXd & ctrl,\nbool full_control=false\n) 
"},{"location":"api/classrobot__dart_1_1control_1_1SimpleControl/#function-simplecontrol-33","title":"function SimpleControl [3/3]","text":"
robot_dart::control::SimpleControl::SimpleControl (\nconst Eigen::VectorXd & ctrl,\nconst std::vector< std::string > & controllable_dofs\n) 
"},{"location":"api/classrobot__dart_1_1control_1_1SimpleControl/#function-calculate","title":"function calculate","text":"
virtual Eigen::VectorXd robot_dart::control::SimpleControl::calculate (\ndouble\n) override\n

Implements robot_dart::control::RobotControl::calculate

"},{"location":"api/classrobot__dart_1_1control_1_1SimpleControl/#function-clone","title":"function clone","text":"
virtual std::shared_ptr< RobotControl > robot_dart::control::SimpleControl::clone () override const\n

Implements robot_dart::control::RobotControl::clone

"},{"location":"api/classrobot__dart_1_1control_1_1SimpleControl/#function-configure","title":"function configure","text":"
virtual void robot_dart::control::SimpleControl::configure () override\n

Implements robot_dart::control::RobotControl::configure

The documentation for this class was generated from the following file robot_dart/control/simple_control.hpp

"},{"location":"api/namespacerobot__dart_1_1detail/","title":"Namespace robot_dart::detail","text":"

Namespace List > robot_dart > detail

"},{"location":"api/namespacerobot__dart_1_1detail/#public-functions","title":"Public Functions","text":"Type Name void add_dof_data (const Eigen::VectorXd & data, dart::dynamics::SkeletonPtr skeleton, const std::vector< std::string > & dof_names, const std::unordered_map< std::string, size_t > & dof_map) Eigen::VectorXd dof_data (dart::dynamics::SkeletonPtr skeleton, const std::vector< std::string > & dof_names, const std::unordered_map< std::string, size_t > & dof_map) void set_dof_data (const Eigen::VectorXd & data, dart::dynamics::SkeletonPtr skeleton, const std::vector< std::string > & dof_names, const std::unordered_map< std::string, size_t > & dof_map)"},{"location":"api/namespacerobot__dart_1_1detail/#public-functions-documentation","title":"Public Functions Documentation","text":""},{"location":"api/namespacerobot__dart_1_1detail/#function-add_dof_data","title":"function add_dof_data","text":"
template<int content>\nvoid robot_dart::detail::add_dof_data (\nconst Eigen::VectorXd & data,\ndart::dynamics::SkeletonPtr skeleton,\nconst std::vector< std::string > & dof_names,\nconst std::unordered_map< std::string, size_t > & dof_map\n) 
"},{"location":"api/namespacerobot__dart_1_1detail/#function-dof_data","title":"function dof_data","text":"
template<int content>\nEigen::VectorXd robot_dart::detail::dof_data (\ndart::dynamics::SkeletonPtr skeleton,\nconst std::vector< std::string > & dof_names,\nconst std::unordered_map< std::string, size_t > & dof_map\n) 
"},{"location":"api/namespacerobot__dart_1_1detail/#function-set_dof_data","title":"function set_dof_data","text":"
template<int content>\nvoid robot_dart::detail::set_dof_data (\nconst Eigen::VectorXd & data,\ndart::dynamics::SkeletonPtr skeleton,\nconst std::vector< std::string > & dof_names,\nconst std::unordered_map< std::string, size_t > & dof_map\n) 

The documentation for this class was generated from the following file robot_dart/robot.cpp

"},{"location":"api/namespacerobot__dart_1_1gui/","title":"Namespace robot_dart::gui","text":"

Namespace List > robot_dart > gui

"},{"location":"api/namespacerobot__dart_1_1gui/#namespaces","title":"Namespaces","text":"Type Name namespace magnum"},{"location":"api/namespacerobot__dart_1_1gui/#classes","title":"Classes","text":"Type Name class Base struct DepthImage struct GrayscaleImage struct Image"},{"location":"api/namespacerobot__dart_1_1gui/#public-functions","title":"Public Functions","text":"Type Name GrayscaleImage convert_rgb_to_grayscale (const Image & rgb) std::vector< Eigen::Vector3d > point_cloud_from_depth_array (const DepthImage & depth_image, const Eigen::Matrix3d & intrinsic_matrix, const Eigen::Matrix4d & tf, double far_plane) void save_png_image (const std::string & filename, const Image & rgb) void save_png_image (const std::string & filename, const GrayscaleImage & gray)"},{"location":"api/namespacerobot__dart_1_1gui/#public-functions-documentation","title":"Public Functions Documentation","text":""},{"location":"api/namespacerobot__dart_1_1gui/#function-convert_rgb_to_grayscale","title":"function convert_rgb_to_grayscale","text":"
GrayscaleImage robot_dart::gui::convert_rgb_to_grayscale (\nconst Image & rgb\n) 
"},{"location":"api/namespacerobot__dart_1_1gui/#function-point_cloud_from_depth_array","title":"function point_cloud_from_depth_array","text":"
std::vector< Eigen::Vector3d > robot_dart::gui::point_cloud_from_depth_array (\nconst DepthImage & depth_image,\nconst Eigen::Matrix3d & intrinsic_matrix,\nconst Eigen::Matrix4d & tf,\ndouble far_plane\n) 
"},{"location":"api/namespacerobot__dart_1_1gui/#function-save_png_image","title":"function save_png_image","text":"
void robot_dart::gui::save_png_image (\nconst std::string & filename,\nconst Image & rgb\n) 
"},{"location":"api/namespacerobot__dart_1_1gui/#function-save_png_image_1","title":"function save_png_image","text":"
void robot_dart::gui::save_png_image (\nconst std::string & filename,\nconst GrayscaleImage & gray\n) 

The documentation for this class was generated from the following file robot_dart/gui/base.hpp

"},{"location":"api/classrobot__dart_1_1gui_1_1Base/","title":"Class robot_dart::gui::Base","text":"

ClassList > robot_dart > gui > Base

Inherited by the following classes: robot_dart::gui::magnum::BaseGraphics, robot_dart::gui::magnum::BaseGraphics, robot_dart::gui::magnum::BaseGraphics

"},{"location":"api/classrobot__dart_1_1gui_1_1Base/#public-functions","title":"Public Functions","text":"Type Name Base () virtual DepthImage depth_array () virtual GrayscaleImage depth_image () virtual bool done () const virtual size_t height () const virtual Image image () virtual GrayscaleImage raw_depth_image () virtual void refresh () virtual void set_enable (bool) virtual void set_fps (int) virtual void set_render_period (double) virtual void set_simu (RobotDARTSimu * simu) const RobotDARTSimu * simu () const virtual size_t width () const virtual ~Base ()"},{"location":"api/classrobot__dart_1_1gui_1_1Base/#protected-attributes","title":"Protected Attributes","text":"Type Name RobotDARTSimu * _simu = = nullptr"},{"location":"api/classrobot__dart_1_1gui_1_1Base/#public-functions-documentation","title":"Public Functions Documentation","text":""},{"location":"api/classrobot__dart_1_1gui_1_1Base/#function-base","title":"function Base","text":"
inline robot_dart::gui::Base::Base () 
"},{"location":"api/classrobot__dart_1_1gui_1_1Base/#function-depth_array","title":"function depth_array","text":"
inline virtual DepthImage robot_dart::gui::Base::depth_array () 
"},{"location":"api/classrobot__dart_1_1gui_1_1Base/#function-depth_image","title":"function depth_image","text":"
inline virtual GrayscaleImage robot_dart::gui::Base::depth_image () 
"},{"location":"api/classrobot__dart_1_1gui_1_1Base/#function-done","title":"function done","text":"
inline virtual bool robot_dart::gui::Base::done () const\n
"},{"location":"api/classrobot__dart_1_1gui_1_1Base/#function-height","title":"function height","text":"
inline virtual size_t robot_dart::gui::Base::height () const\n
"},{"location":"api/classrobot__dart_1_1gui_1_1Base/#function-image","title":"function image","text":"
inline virtual Image robot_dart::gui::Base::image () 
"},{"location":"api/classrobot__dart_1_1gui_1_1Base/#function-raw_depth_image","title":"function raw_depth_image","text":"
inline virtual GrayscaleImage robot_dart::gui::Base::raw_depth_image () 
"},{"location":"api/classrobot__dart_1_1gui_1_1Base/#function-refresh","title":"function refresh","text":"
inline virtual void robot_dart::gui::Base::refresh () 
"},{"location":"api/classrobot__dart_1_1gui_1_1Base/#function-set_enable","title":"function set_enable","text":"
inline virtual void robot_dart::gui::Base::set_enable (\nbool\n) 
"},{"location":"api/classrobot__dart_1_1gui_1_1Base/#function-set_fps","title":"function set_fps","text":"
inline virtual void robot_dart::gui::Base::set_fps (\nint\n) 
"},{"location":"api/classrobot__dart_1_1gui_1_1Base/#function-set_render_period","title":"function set_render_period","text":"
inline virtual void robot_dart::gui::Base::set_render_period (\ndouble\n) 
"},{"location":"api/classrobot__dart_1_1gui_1_1Base/#function-set_simu","title":"function set_simu","text":"
inline virtual void robot_dart::gui::Base::set_simu (\nRobotDARTSimu * simu\n) 
"},{"location":"api/classrobot__dart_1_1gui_1_1Base/#function-simu","title":"function simu","text":"
inline const RobotDARTSimu * robot_dart::gui::Base::simu () const\n
"},{"location":"api/classrobot__dart_1_1gui_1_1Base/#function-width","title":"function width","text":"
inline virtual size_t robot_dart::gui::Base::width () const\n
"},{"location":"api/classrobot__dart_1_1gui_1_1Base/#function-base_1","title":"function ~Base","text":"
inline virtual robot_dart::gui::Base::~Base () 
"},{"location":"api/classrobot__dart_1_1gui_1_1Base/#protected-attributes-documentation","title":"Protected Attributes Documentation","text":""},{"location":"api/classrobot__dart_1_1gui_1_1Base/#variable-_simu","title":"variable _simu","text":"
RobotDARTSimu* robot_dart::gui::Base::_simu;\n

The documentation for this class was generated from the following file robot_dart/gui/base.hpp

"},{"location":"api/structrobot__dart_1_1gui_1_1DepthImage/","title":"Struct robot_dart::gui::DepthImage","text":"

ClassList > robot_dart > gui > DepthImage

"},{"location":"api/structrobot__dart_1_1gui_1_1DepthImage/#public-attributes","title":"Public Attributes","text":"Type Name std::vector< double > data size_t height = = 0 size_t width = = 0"},{"location":"api/structrobot__dart_1_1gui_1_1DepthImage/#public-attributes-documentation","title":"Public Attributes Documentation","text":""},{"location":"api/structrobot__dart_1_1gui_1_1DepthImage/#variable-data","title":"variable data","text":"
std::vector<double> robot_dart::gui::DepthImage::data;\n
"},{"location":"api/structrobot__dart_1_1gui_1_1DepthImage/#variable-height","title":"variable height","text":"
size_t robot_dart::gui::DepthImage::height;\n
"},{"location":"api/structrobot__dart_1_1gui_1_1DepthImage/#variable-width","title":"variable width","text":"
size_t robot_dart::gui::DepthImage::width;\n

The documentation for this class was generated from the following file robot_dart/gui/helper.hpp

"},{"location":"api/structrobot__dart_1_1gui_1_1GrayscaleImage/","title":"Struct robot_dart::gui::GrayscaleImage","text":"

ClassList > robot_dart > gui > GrayscaleImage

"},{"location":"api/structrobot__dart_1_1gui_1_1GrayscaleImage/#public-attributes","title":"Public Attributes","text":"Type Name std::vector< uint8_t > data size_t height = = 0 size_t width = = 0"},{"location":"api/structrobot__dart_1_1gui_1_1GrayscaleImage/#public-attributes-documentation","title":"Public Attributes Documentation","text":""},{"location":"api/structrobot__dart_1_1gui_1_1GrayscaleImage/#variable-data","title":"variable data","text":"
std::vector<uint8_t> robot_dart::gui::GrayscaleImage::data;\n
"},{"location":"api/structrobot__dart_1_1gui_1_1GrayscaleImage/#variable-height","title":"variable height","text":"
size_t robot_dart::gui::GrayscaleImage::height;\n
"},{"location":"api/structrobot__dart_1_1gui_1_1GrayscaleImage/#variable-width","title":"variable width","text":"
size_t robot_dart::gui::GrayscaleImage::width;\n

The documentation for this class was generated from the following file robot_dart/gui/helper.hpp

"},{"location":"api/structrobot__dart_1_1gui_1_1Image/","title":"Struct robot_dart::gui::Image","text":"

ClassList > robot_dart > gui > Image

"},{"location":"api/structrobot__dart_1_1gui_1_1Image/#public-attributes","title":"Public Attributes","text":"Type Name size_t channels = = 3 std::vector< uint8_t > data size_t height = = 0 size_t width = = 0"},{"location":"api/structrobot__dart_1_1gui_1_1Image/#public-attributes-documentation","title":"Public Attributes Documentation","text":""},{"location":"api/structrobot__dart_1_1gui_1_1Image/#variable-channels","title":"variable channels","text":"
size_t robot_dart::gui::Image::channels;\n
"},{"location":"api/structrobot__dart_1_1gui_1_1Image/#variable-data","title":"variable data","text":"
std::vector<uint8_t> robot_dart::gui::Image::data;\n
"},{"location":"api/structrobot__dart_1_1gui_1_1Image/#variable-height","title":"variable height","text":"
size_t robot_dart::gui::Image::height;\n
"},{"location":"api/structrobot__dart_1_1gui_1_1Image/#variable-width","title":"variable width","text":"
size_t robot_dart::gui::Image::width;\n

The documentation for this class was generated from the following file robot_dart/gui/helper.hpp

"},{"location":"api/namespacerobot__dart_1_1gui_1_1magnum/","title":"Namespace robot_dart::gui::magnum","text":"

Namespace List > robot_dart > gui > magnum

"},{"location":"api/namespacerobot__dart_1_1gui_1_1magnum/#namespaces","title":"Namespaces","text":"Type Name namespace gs namespace sensor"},{"location":"api/namespacerobot__dart_1_1gui_1_1magnum/#classes","title":"Classes","text":"Type Name class BaseApplication class BaseGraphics <typename T> class CubeMapShadowedColorObject class CubeMapShadowedObject struct DebugDrawData class DrawableObject class GlfwApplication struct GlobalData class Graphics struct GraphicsConfiguration struct ObjectStruct struct ShadowData class ShadowedColorObject class ShadowedObject class WindowlessGLApplication class WindowlessGraphics"},{"location":"api/namespacerobot__dart_1_1gui_1_1magnum/#public-types","title":"Public Types","text":"Type Name typedef Magnum::SceneGraph::Camera3D Camera3D typedef Magnum::SceneGraph::Object< Magnum::SceneGraph::MatrixTransformation3D > Object3D typedef Magnum::SceneGraph::Scene< Magnum::SceneGraph::MatrixTransformation3D > Scene3D"},{"location":"api/namespacerobot__dart_1_1gui_1_1magnum/#public-functions","title":"Public Functions","text":"Type Name BaseApplication * make_application (RobotDARTSimu * simu, const GraphicsConfiguration & configuration=GraphicsConfiguration())"},{"location":"api/namespacerobot__dart_1_1gui_1_1magnum/#public-types-documentation","title":"Public Types Documentation","text":""},{"location":"api/namespacerobot__dart_1_1gui_1_1magnum/#typedef-camera3d","title":"typedef Camera3D","text":"
using robot_dart::gui::magnum::Camera3D = typedef Magnum::SceneGraph::Camera3D;\n
"},{"location":"api/namespacerobot__dart_1_1gui_1_1magnum/#typedef-object3d","title":"typedef Object3D","text":"
using robot_dart::gui::magnum::Object3D = typedef Magnum::SceneGraph::Object<Magnum::SceneGraph::MatrixTransformation3D>;\n
"},{"location":"api/namespacerobot__dart_1_1gui_1_1magnum/#typedef-scene3d","title":"typedef Scene3D","text":"
using robot_dart::gui::magnum::Scene3D = typedef Magnum::SceneGraph::Scene<Magnum::SceneGraph::MatrixTransformation3D>;\n
"},{"location":"api/namespacerobot__dart_1_1gui_1_1magnum/#public-functions-documentation","title":"Public Functions Documentation","text":""},{"location":"api/namespacerobot__dart_1_1gui_1_1magnum/#function-make_application","title":"function make_application","text":"
template<typename T typename T>\ninline BaseApplication * robot_dart::gui::magnum::make_application (\nRobotDARTSimu * simu,\nconst GraphicsConfiguration & configuration=GraphicsConfiguration ()\n) 

The documentation for this class was generated from the following file robot_dart/gui/magnum/base_application.cpp

"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1BaseApplication/","title":"Class robot_dart::gui::magnum::BaseApplication","text":"

ClassList > robot_dart > gui > magnum > BaseApplication

Inherited by the following classes: robot_dart::gui::magnum::GlfwApplication, robot_dart::gui::magnum::WindowlessGLApplication

"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1BaseApplication/#public-functions","title":"Public Functions","text":"Type Name BaseApplication (const GraphicsConfiguration & configuration=GraphicsConfiguration()) void add_light (const gs::Light & light) bool attach_camera (gs::Camera & camera, dart::dynamics::BodyNode * body) gs::Camera & camera () const gs::Camera & camera () const void clear_lights () DebugDrawData debug_draw_data () DepthImage depth_array () GrayscaleImage depth_image () bool done () const Magnum::SceneGraph::DrawableGroup3D & drawables () void enable_shadows (bool enable=true, bool drawTransparentShadows=false) Corrade::Containers::Optional< Magnum::Image2D > & image () void init (RobotDARTSimu * simu, const GraphicsConfiguration & configuration) gs::Light & light (size_t i) std::vector< gs::Light > & lights () void look_at (const Eigen::Vector3d & camera_pos, const Eigen::Vector3d & look_at, const Eigen::Vector3d & up) size_t num_lights () const GrayscaleImage raw_depth_image () void record_video (const std::string & video_fname, int fps) virtual void render () void render_shadows () Scene3D & scene () bool shadowed () const bool transparent_shadows () const void update_graphics () void update_lights (const gs::Camera & camera) virtual ~BaseApplication ()"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1BaseApplication/#protected-attributes","title":"Protected Attributes","text":"Type Name std::unique_ptr< Magnum::GL::Mesh > _3D_axis_mesh std::unique_ptr< Magnum::Shaders::VertexColorGL3D > _3D_axis_shader std::unique_ptr< Magnum::GL::Mesh > _background_mesh std::unique_ptr< Magnum::Shaders::FlatGL2D > _background_shader std::unique_ptr< gs::Camera > _camera std::unique_ptr< gs::PhongMultiLight > _color_shader GraphicsConfiguration _configuration Magnum::SceneGraph::DrawableGroup3D _cubemap_color_drawables std::unique_ptr< gs::CubeMapColor > _cubemap_color_shader Magnum::SceneGraph::DrawableGroup3D _cubemap_drawables std::unique_ptr< gs::CubeMap > _cubemap_shader std::unique_ptr< gs::CubeMapColor > _cubemap_texture_color_shader std::unique_ptr< gs::CubeMap > _cubemap_texture_shader std::unique_ptr< Magnum::DartIntegration::World > _dart_world bool _done = = false std::unordered_map< Magnum::DartIntegration::Object *, ObjectStruct * > _drawable_objects Magnum::SceneGraph::DrawableGroup3D _drawables Corrade::Containers::Pointer< Magnum::Text::AbstractFont > _font Corrade::PluginManager::Manager< Magnum::Text::AbstractFont > _font_manager Corrade::Containers::Pointer< Magnum::Text::DistanceFieldGlyphCache > _glyph_cache Corrade::PluginManager::Manager< Magnum::Trade::AbstractImporter > _importer_manager std::vector< gs::Light > _lights int _max_lights = = 5 Scene3D _scene std::unique_ptr< Camera3D > _shadow_camera Object3D * _shadow_camera_object std::unique_ptr< Magnum::GL::CubeMapTextureArray > _shadow_color_cube_map std::unique_ptr< gs::ShadowMapColor > _shadow_color_shader std::unique_ptr< Magnum::GL::Texture2DArray > _shadow_color_texture std::unique_ptr< Magnum::GL::CubeMapTextureArray > _shadow_cube_map std::vector< ShadowData > _shadow_data int _shadow_map_size = = 512 std::unique_ptr< gs::ShadowMap > _shadow_shader std::unique_ptr< Magnum::GL::Texture2DArray > _shadow_texture std::unique_ptr< gs::ShadowMapColor > _shadow_texture_color_shader std::unique_ptr< gs::ShadowMap > _shadow_texture_shader bool _shadowed = = true Magnum::SceneGraph::DrawableGroup3D _shadowed_color_drawables Magnum::SceneGraph::DrawableGroup3D _shadowed_drawables RobotDARTSimu * _simu Corrade::Containers::Pointer< Magnum::GL::Buffer > _text_indices std::unique_ptr< Magnum::Shaders::DistanceFieldVectorGL2D > _text_shader Corrade::Containers::Pointer< Magnum::GL::Buffer > _text_vertices std::unique_ptr< gs::PhongMultiLight > _texture_shader int _transparentSize = = 0 bool _transparent_shadows = = false"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1BaseApplication/#protected-functions","title":"Protected Functions","text":"Type Name void _gl_clean_up () void _prepare_shadows ()"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1BaseApplication/#public-functions-documentation","title":"Public Functions Documentation","text":""},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1BaseApplication/#function-baseapplication","title":"function BaseApplication","text":"
robot_dart::gui::magnum::BaseApplication::BaseApplication (\nconst GraphicsConfiguration & configuration=GraphicsConfiguration ()\n) 
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1BaseApplication/#function-add_light","title":"function add_light","text":"
void robot_dart::gui::magnum::BaseApplication::add_light (\nconst gs::Light & light\n) 
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1BaseApplication/#function-attach_camera","title":"function attach_camera","text":"
bool robot_dart::gui::magnum::BaseApplication::attach_camera (\ngs::Camera & camera,\ndart::dynamics::BodyNode * body\n) 
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1BaseApplication/#function-camera-12","title":"function camera [\u00bd]","text":"
inline gs::Camera & robot_dart::gui::magnum::BaseApplication::camera () 
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1BaseApplication/#function-camera-22","title":"function camera [2/2]","text":"
inline const gs::Camera & robot_dart::gui::magnum::BaseApplication::camera () const\n
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1BaseApplication/#function-clear_lights","title":"function clear_lights","text":"
void robot_dart::gui::magnum::BaseApplication::clear_lights () 
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1BaseApplication/#function-debug_draw_data","title":"function debug_draw_data","text":"
inline DebugDrawData robot_dart::gui::magnum::BaseApplication::debug_draw_data () 
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1BaseApplication/#function-depth_array","title":"function depth_array","text":"
DepthImage robot_dart::gui::magnum::BaseApplication::depth_array () 
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1BaseApplication/#function-depth_image","title":"function depth_image","text":"
GrayscaleImage robot_dart::gui::magnum::BaseApplication::depth_image () 
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1BaseApplication/#function-done","title":"function done","text":"
bool robot_dart::gui::magnum::BaseApplication::done () const\n
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1BaseApplication/#function-drawables","title":"function drawables","text":"
inline Magnum::SceneGraph::DrawableGroup3D & robot_dart::gui::magnum::BaseApplication::drawables () 
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1BaseApplication/#function-enable_shadows","title":"function enable_shadows","text":"
void robot_dart::gui::magnum::BaseApplication::enable_shadows (\nbool enable=true,\nbool drawTransparentShadows=false\n) 
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1BaseApplication/#function-image","title":"function image","text":"
inline Corrade::Containers::Optional< Magnum::Image2D > & robot_dart::gui::magnum::BaseApplication::image () 
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1BaseApplication/#function-init","title":"function init","text":"
void robot_dart::gui::magnum::BaseApplication::init (\nRobotDARTSimu * simu,\nconst GraphicsConfiguration & configuration\n) 
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1BaseApplication/#function-light","title":"function light","text":"
gs::Light & robot_dart::gui::magnum::BaseApplication::light (\nsize_t i\n) 
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1BaseApplication/#function-lights","title":"function lights","text":"
std::vector< gs::Light > & robot_dart::gui::magnum::BaseApplication::lights () 
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1BaseApplication/#function-look_at","title":"function look_at","text":"
void robot_dart::gui::magnum::BaseApplication::look_at (\nconst Eigen::Vector3d & camera_pos,\nconst Eigen::Vector3d & look_at,\nconst Eigen::Vector3d & up\n) 
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1BaseApplication/#function-num_lights","title":"function num_lights","text":"
size_t robot_dart::gui::magnum::BaseApplication::num_lights () const\n
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1BaseApplication/#function-raw_depth_image","title":"function raw_depth_image","text":"
GrayscaleImage robot_dart::gui::magnum::BaseApplication::raw_depth_image () 
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1BaseApplication/#function-record_video","title":"function record_video","text":"
inline void robot_dart::gui::magnum::BaseApplication::record_video (\nconst std::string & video_fname,\nint fps\n) 
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1BaseApplication/#function-render","title":"function render","text":"
inline virtual void robot_dart::gui::magnum::BaseApplication::render () 
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1BaseApplication/#function-render_shadows","title":"function render_shadows","text":"
void robot_dart::gui::magnum::BaseApplication::render_shadows () 
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1BaseApplication/#function-scene","title":"function scene","text":"
inline Scene3D & robot_dart::gui::magnum::BaseApplication::scene () 
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1BaseApplication/#function-shadowed","title":"function shadowed","text":"
inline bool robot_dart::gui::magnum::BaseApplication::shadowed () const\n
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1BaseApplication/#function-transparent_shadows","title":"function transparent_shadows","text":"
inline bool robot_dart::gui::magnum::BaseApplication::transparent_shadows () const\n
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1BaseApplication/#function-update_graphics","title":"function update_graphics","text":"
void robot_dart::gui::magnum::BaseApplication::update_graphics () 
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1BaseApplication/#function-update_lights","title":"function update_lights","text":"
void robot_dart::gui::magnum::BaseApplication::update_lights (\nconst gs::Camera & camera\n) 
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1BaseApplication/#function-baseapplication_1","title":"function ~BaseApplication","text":"
inline virtual robot_dart::gui::magnum::BaseApplication::~BaseApplication () 
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1BaseApplication/#protected-attributes-documentation","title":"Protected Attributes Documentation","text":""},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1BaseApplication/#variable-_3d_axis_mesh","title":"variable _3D_axis_mesh","text":"
std::unique_ptr<Magnum::GL::Mesh> robot_dart::gui::magnum::BaseApplication::_3D_axis_mesh;\n
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1BaseApplication/#variable-_3d_axis_shader","title":"variable _3D_axis_shader","text":"
std::unique_ptr<Magnum::Shaders::VertexColorGL3D> robot_dart::gui::magnum::BaseApplication::_3D_axis_shader;\n
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1BaseApplication/#variable-_background_mesh","title":"variable _background_mesh","text":"
std::unique_ptr<Magnum::GL::Mesh> robot_dart::gui::magnum::BaseApplication::_background_mesh;\n
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1BaseApplication/#variable-_background_shader","title":"variable _background_shader","text":"
std::unique_ptr<Magnum::Shaders::FlatGL2D> robot_dart::gui::magnum::BaseApplication::_background_shader;\n
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1BaseApplication/#variable-_camera","title":"variable _camera","text":"
std::unique_ptr<gs::Camera> robot_dart::gui::magnum::BaseApplication::_camera;\n
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1BaseApplication/#variable-_color_shader","title":"variable _color_shader","text":"
std::unique_ptr<gs::PhongMultiLight> robot_dart::gui::magnum::BaseApplication::_color_shader;\n
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1BaseApplication/#variable-_configuration","title":"variable _configuration","text":"
GraphicsConfiguration robot_dart::gui::magnum::BaseApplication::_configuration;\n
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1BaseApplication/#variable-_cubemap_color_drawables","title":"variable _cubemap_color_drawables","text":"
Magnum::SceneGraph::DrawableGroup3D robot_dart::gui::magnum::BaseApplication::_cubemap_color_drawables;\n
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1BaseApplication/#variable-_cubemap_color_shader","title":"variable _cubemap_color_shader","text":"
std::unique_ptr<gs::CubeMapColor> robot_dart::gui::magnum::BaseApplication::_cubemap_color_shader;\n
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1BaseApplication/#variable-_cubemap_drawables","title":"variable _cubemap_drawables","text":"
Magnum::SceneGraph::DrawableGroup3D robot_dart::gui::magnum::BaseApplication::_cubemap_drawables;\n
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1BaseApplication/#variable-_cubemap_shader","title":"variable _cubemap_shader","text":"
std::unique_ptr<gs::CubeMap> robot_dart::gui::magnum::BaseApplication::_cubemap_shader;\n
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1BaseApplication/#variable-_cubemap_texture_color_shader","title":"variable _cubemap_texture_color_shader","text":"
std::unique_ptr<gs::CubeMapColor> robot_dart::gui::magnum::BaseApplication::_cubemap_texture_color_shader;\n
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1BaseApplication/#variable-_cubemap_texture_shader","title":"variable _cubemap_texture_shader","text":"
std::unique_ptr<gs::CubeMap> robot_dart::gui::magnum::BaseApplication::_cubemap_texture_shader;\n
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1BaseApplication/#variable-_dart_world","title":"variable _dart_world","text":"
std::unique_ptr<Magnum::DartIntegration::World> robot_dart::gui::magnum::BaseApplication::_dart_world;\n
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1BaseApplication/#variable-_done","title":"variable _done","text":"
bool robot_dart::gui::magnum::BaseApplication::_done;\n
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1BaseApplication/#variable-_drawable_objects","title":"variable _drawable_objects","text":"
std::unordered_map<Magnum::DartIntegration::Object*, ObjectStruct*> robot_dart::gui::magnum::BaseApplication::_drawable_objects;\n
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1BaseApplication/#variable-_drawables","title":"variable _drawables","text":"
Magnum::SceneGraph::DrawableGroup3D robot_dart::gui::magnum::BaseApplication::_drawables;\n
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1BaseApplication/#variable-_font","title":"variable _font","text":"
Corrade::Containers::Pointer<Magnum::Text::AbstractFont> robot_dart::gui::magnum::BaseApplication::_font;\n
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1BaseApplication/#variable-_font_manager","title":"variable _font_manager","text":"
Corrade::PluginManager::Manager<Magnum::Text::AbstractFont> robot_dart::gui::magnum::BaseApplication::_font_manager;\n
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1BaseApplication/#variable-_glyph_cache","title":"variable _glyph_cache","text":"
Corrade::Containers::Pointer<Magnum::Text::DistanceFieldGlyphCache> robot_dart::gui::magnum::BaseApplication::_glyph_cache;\n
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1BaseApplication/#variable-_importer_manager","title":"variable _importer_manager","text":"
Corrade::PluginManager::Manager<Magnum::Trade::AbstractImporter> robot_dart::gui::magnum::BaseApplication::_importer_manager;\n
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1BaseApplication/#variable-_lights","title":"variable _lights","text":"
std::vector<gs::Light> robot_dart::gui::magnum::BaseApplication::_lights;\n
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1BaseApplication/#variable-_max_lights","title":"variable _max_lights","text":"
int robot_dart::gui::magnum::BaseApplication::_max_lights;\n
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1BaseApplication/#variable-_scene","title":"variable _scene","text":"
Scene3D robot_dart::gui::magnum::BaseApplication::_scene;\n
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1BaseApplication/#variable-_shadow_camera","title":"variable _shadow_camera","text":"
std::unique_ptr<Camera3D> robot_dart::gui::magnum::BaseApplication::_shadow_camera;\n
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1BaseApplication/#variable-_shadow_camera_object","title":"variable _shadow_camera_object","text":"
Object3D* robot_dart::gui::magnum::BaseApplication::_shadow_camera_object;\n
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1BaseApplication/#variable-_shadow_color_cube_map","title":"variable _shadow_color_cube_map","text":"
std::unique_ptr<Magnum::GL::CubeMapTextureArray> robot_dart::gui::magnum::BaseApplication::_shadow_color_cube_map;\n
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1BaseApplication/#variable-_shadow_color_shader","title":"variable _shadow_color_shader","text":"
std::unique_ptr<gs::ShadowMapColor> robot_dart::gui::magnum::BaseApplication::_shadow_color_shader;\n
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1BaseApplication/#variable-_shadow_color_texture","title":"variable _shadow_color_texture","text":"
std::unique_ptr<Magnum::GL::Texture2DArray> robot_dart::gui::magnum::BaseApplication::_shadow_color_texture;\n
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1BaseApplication/#variable-_shadow_cube_map","title":"variable _shadow_cube_map","text":"
std::unique_ptr<Magnum::GL::CubeMapTextureArray> robot_dart::gui::magnum::BaseApplication::_shadow_cube_map;\n
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1BaseApplication/#variable-_shadow_data","title":"variable _shadow_data","text":"
std::vector<ShadowData> robot_dart::gui::magnum::BaseApplication::_shadow_data;\n
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1BaseApplication/#variable-_shadow_map_size","title":"variable _shadow_map_size","text":"
int robot_dart::gui::magnum::BaseApplication::_shadow_map_size;\n
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1BaseApplication/#variable-_shadow_shader","title":"variable _shadow_shader","text":"
std::unique_ptr<gs::ShadowMap> robot_dart::gui::magnum::BaseApplication::_shadow_shader;\n
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1BaseApplication/#variable-_shadow_texture","title":"variable _shadow_texture","text":"
std::unique_ptr<Magnum::GL::Texture2DArray> robot_dart::gui::magnum::BaseApplication::_shadow_texture;\n
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1BaseApplication/#variable-_shadow_texture_color_shader","title":"variable _shadow_texture_color_shader","text":"
std::unique_ptr<gs::ShadowMapColor> robot_dart::gui::magnum::BaseApplication::_shadow_texture_color_shader;\n
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1BaseApplication/#variable-_shadow_texture_shader","title":"variable _shadow_texture_shader","text":"
std::unique_ptr<gs::ShadowMap> robot_dart::gui::magnum::BaseApplication::_shadow_texture_shader;\n
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1BaseApplication/#variable-_shadowed","title":"variable _shadowed","text":"
bool robot_dart::gui::magnum::BaseApplication::_shadowed;\n
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1BaseApplication/#variable-_shadowed_color_drawables","title":"variable _shadowed_color_drawables","text":"
Magnum::SceneGraph::DrawableGroup3D robot_dart::gui::magnum::BaseApplication::_shadowed_color_drawables;\n
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1BaseApplication/#variable-_shadowed_drawables","title":"variable _shadowed_drawables","text":"
Magnum::SceneGraph::DrawableGroup3D robot_dart::gui::magnum::BaseApplication::_shadowed_drawables;\n
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1BaseApplication/#variable-_simu","title":"variable _simu","text":"
RobotDARTSimu* robot_dart::gui::magnum::BaseApplication::_simu;\n
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1BaseApplication/#variable-_text_indices","title":"variable _text_indices","text":"
Corrade::Containers::Pointer<Magnum::GL::Buffer> robot_dart::gui::magnum::BaseApplication::_text_indices;\n
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1BaseApplication/#variable-_text_shader","title":"variable _text_shader","text":"
std::unique_ptr<Magnum::Shaders::DistanceFieldVectorGL2D> robot_dart::gui::magnum::BaseApplication::_text_shader;\n
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1BaseApplication/#variable-_text_vertices","title":"variable _text_vertices","text":"
Corrade::Containers::Pointer<Magnum::GL::Buffer> robot_dart::gui::magnum::BaseApplication::_text_vertices;\n
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1BaseApplication/#variable-_texture_shader","title":"variable _texture_shader","text":"
std::unique_ptr<gs::PhongMultiLight> robot_dart::gui::magnum::BaseApplication::_texture_shader;\n
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1BaseApplication/#variable-_transparentsize","title":"variable _transparentSize","text":"
int robot_dart::gui::magnum::BaseApplication::_transparentSize;\n
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1BaseApplication/#variable-_transparent_shadows","title":"variable _transparent_shadows","text":"
bool robot_dart::gui::magnum::BaseApplication::_transparent_shadows;\n
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1BaseApplication/#protected-functions-documentation","title":"Protected Functions Documentation","text":""},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1BaseApplication/#function-_gl_clean_up","title":"function _gl_clean_up","text":"
void robot_dart::gui::magnum::BaseApplication::_gl_clean_up () 
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1BaseApplication/#function-_prepare_shadows","title":"function _prepare_shadows","text":"
void robot_dart::gui::magnum::BaseApplication::_prepare_shadows () 

The documentation for this class was generated from the following file robot_dart/gui/magnum/base_application.hpp

"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1BaseGraphics/","title":"Class robot_dart::gui::magnum::BaseGraphics","text":"

template <typename T typename T>

ClassList > robot_dart > gui > magnum > BaseGraphics

Inherits the following classes: robot_dart::gui::Base

"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1BaseGraphics/#public-functions","title":"Public Functions","text":"Type Name BaseGraphics (const GraphicsConfiguration & configuration=GraphicsConfiguration()) void add_light (const magnum::Light & light) gs::Camera & camera () const gs::Camera & camera () const Eigen::Matrix4d camera_extrinsic_matrix () const Eigen::Matrix3d camera_intrinsic_matrix () const void clear_lights () virtual DepthImage depth_array () override virtual GrayscaleImage depth_image () override virtual bool done () override const void enable_shadows (bool enable=true, bool transparent=true) virtual size_t height () override const virtual Image image () override magnum::Light & light (size_t i) std::vector< gs::Light > & lights () void look_at (const Eigen::Vector3d & camera_pos, const Eigen::Vector3d & look_at=Eigen::Vector3d(0, 0, 0), const Eigen::Vector3d & up=Eigen::Vector3d(0, 0, 1)) BaseApplication * magnum_app () const BaseApplication * magnum_app () const Magnum::Image2D * magnum_image () size_t num_lights () const virtual GrayscaleImage raw_depth_image () override void record_video (const std::string & video_fname, int fps=-1) virtual void refresh () override virtual void set_enable (bool enable) override virtual void set_fps (int fps) override virtual void set_simu (RobotDARTSimu * simu) override bool shadowed () const bool transparent_shadows () const virtual size_t width () override const virtual ~BaseGraphics ()"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1BaseGraphics/#public-functions-inherited-from-robot_dartguibase","title":"Public Functions inherited from robot_dart::gui::Base","text":"

See robot_dart::gui::Base

Type Name Base () virtual DepthImage depth_array () virtual GrayscaleImage depth_image () virtual bool done () const virtual size_t height () const virtual Image image () virtual GrayscaleImage raw_depth_image () virtual void refresh () virtual void set_enable (bool) virtual void set_fps (int) virtual void set_render_period (double) virtual void set_simu (RobotDARTSimu * simu) const RobotDARTSimu * simu () const virtual size_t width () const virtual ~Base ()"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1BaseGraphics/#protected-attributes","title":"Protected Attributes","text":"Type Name GraphicsConfiguration _configuration bool _enabled int _fps std::unique_ptr< BaseApplication > _magnum_app Corrade::Utility::Debug _magnum_silence_output = {nullptr}"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1BaseGraphics/#protected-attributes-inherited-from-robot_dartguibase","title":"Protected Attributes inherited from robot_dart::gui::Base","text":"

See robot_dart::gui::Base

Type Name RobotDARTSimu * _simu = = nullptr"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1BaseGraphics/#public-functions-documentation","title":"Public Functions Documentation","text":""},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1BaseGraphics/#function-basegraphics","title":"function BaseGraphics","text":"
inline robot_dart::gui::magnum::BaseGraphics::BaseGraphics (\nconst GraphicsConfiguration & configuration=GraphicsConfiguration ()\n) 
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1BaseGraphics/#function-add_light","title":"function add_light","text":"
inline void robot_dart::gui::magnum::BaseGraphics::add_light (\nconst magnum::gs::Light & light\n) 
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1BaseGraphics/#function-camera-12","title":"function camera [\u00bd]","text":"
inline gs::Camera & robot_dart::gui::magnum::BaseGraphics::camera () 
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1BaseGraphics/#function-camera-22","title":"function camera [2/2]","text":"
inline const gs::Camera & robot_dart::gui::magnum::BaseGraphics::camera () const\n
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1BaseGraphics/#function-camera_extrinsic_matrix","title":"function camera_extrinsic_matrix","text":"
inline Eigen::Matrix4d robot_dart::gui::magnum::BaseGraphics::camera_extrinsic_matrix () const\n
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1BaseGraphics/#function-camera_intrinsic_matrix","title":"function camera_intrinsic_matrix","text":"
inline Eigen::Matrix3d robot_dart::gui::magnum::BaseGraphics::camera_intrinsic_matrix () const\n
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1BaseGraphics/#function-clear_lights","title":"function clear_lights","text":"
inline void robot_dart::gui::magnum::BaseGraphics::clear_lights () 
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1BaseGraphics/#function-depth_array","title":"function depth_array","text":"
inline virtual DepthImage robot_dart::gui::magnum::BaseGraphics::depth_array () override\n

Implements robot_dart::gui::Base::depth_array

"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1BaseGraphics/#function-depth_image","title":"function depth_image","text":"
inline virtual GrayscaleImage robot_dart::gui::magnum::BaseGraphics::depth_image () override\n

Implements robot_dart::gui::Base::depth_image

"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1BaseGraphics/#function-done","title":"function done","text":"
inline virtual bool robot_dart::gui::magnum::BaseGraphics::done () override const\n

Implements robot_dart::gui::Base::done

"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1BaseGraphics/#function-enable_shadows","title":"function enable_shadows","text":"
inline void robot_dart::gui::magnum::BaseGraphics::enable_shadows (\nbool enable=true,\nbool transparent=true\n) 
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1BaseGraphics/#function-height","title":"function height","text":"
inline virtual size_t robot_dart::gui::magnum::BaseGraphics::height () override const\n

Implements robot_dart::gui::Base::height

"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1BaseGraphics/#function-image","title":"function image","text":"
inline virtual Image robot_dart::gui::magnum::BaseGraphics::image () override\n

Implements robot_dart::gui::Base::image

"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1BaseGraphics/#function-light","title":"function light","text":"
inline magnum::gs::Light & robot_dart::gui::magnum::BaseGraphics::light (\nsize_t i\n) 
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1BaseGraphics/#function-lights","title":"function lights","text":"
inline std::vector< gs::Light > & robot_dart::gui::magnum::BaseGraphics::lights () 
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1BaseGraphics/#function-look_at","title":"function look_at","text":"
inline void robot_dart::gui::magnum::BaseGraphics::look_at (\nconst Eigen::Vector3d & camera_pos,\nconst Eigen::Vector3d & look_at=Eigen::Vector3d(0, 0, 0),\nconst Eigen::Vector3d & up=Eigen::Vector3d(0, 0, 1)\n) 
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1BaseGraphics/#function-magnum_app-12","title":"function magnum_app [\u00bd]","text":"
inline BaseApplication * robot_dart::gui::magnum::BaseGraphics::magnum_app () 
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1BaseGraphics/#function-magnum_app-22","title":"function magnum_app [2/2]","text":"
inline const BaseApplication * robot_dart::gui::magnum::BaseGraphics::magnum_app () const\n
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1BaseGraphics/#function-magnum_image","title":"function magnum_image","text":"
inline Magnum::Image2D * robot_dart::gui::magnum::BaseGraphics::magnum_image () 
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1BaseGraphics/#function-num_lights","title":"function num_lights","text":"
inline size_t robot_dart::gui::magnum::BaseGraphics::num_lights () const\n
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1BaseGraphics/#function-raw_depth_image","title":"function raw_depth_image","text":"
inline virtual GrayscaleImage robot_dart::gui::magnum::BaseGraphics::raw_depth_image () override\n

Implements robot_dart::gui::Base::raw_depth_image

"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1BaseGraphics/#function-record_video","title":"function record_video","text":"
inline void robot_dart::gui::magnum::BaseGraphics::record_video (\nconst std::string & video_fname,\nint fps=-1\n) 
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1BaseGraphics/#function-refresh","title":"function refresh","text":"
inline virtual void robot_dart::gui::magnum::BaseGraphics::refresh () override\n

Implements robot_dart::gui::Base::refresh

"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1BaseGraphics/#function-set_enable","title":"function set_enable","text":"
inline virtual void robot_dart::gui::magnum::BaseGraphics::set_enable (\nbool enable\n) override\n

Implements robot_dart::gui::Base::set_enable

"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1BaseGraphics/#function-set_fps","title":"function set_fps","text":"
inline virtual void robot_dart::gui::magnum::BaseGraphics::set_fps (\nint fps\n) override\n

Implements robot_dart::gui::Base::set_fps

"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1BaseGraphics/#function-set_simu","title":"function set_simu","text":"
inline virtual void robot_dart::gui::magnum::BaseGraphics::set_simu (\nRobotDARTSimu * simu\n) override\n

Implements robot_dart::gui::Base::set_simu

"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1BaseGraphics/#function-shadowed","title":"function shadowed","text":"
inline bool robot_dart::gui::magnum::BaseGraphics::shadowed () const\n
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1BaseGraphics/#function-transparent_shadows","title":"function transparent_shadows","text":"
inline bool robot_dart::gui::magnum::BaseGraphics::transparent_shadows () const\n
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1BaseGraphics/#function-width","title":"function width","text":"
inline virtual size_t robot_dart::gui::magnum::BaseGraphics::width () override const\n

Implements robot_dart::gui::Base::width

"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1BaseGraphics/#function-basegraphics_1","title":"function ~BaseGraphics","text":"
inline virtual robot_dart::gui::magnum::BaseGraphics::~BaseGraphics () 
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1BaseGraphics/#protected-attributes-documentation","title":"Protected Attributes Documentation","text":""},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1BaseGraphics/#variable-_configuration","title":"variable _configuration","text":"
GraphicsConfiguration robot_dart::gui::magnum::BaseGraphics< T >::_configuration;\n
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1BaseGraphics/#variable-_enabled","title":"variable _enabled","text":"
bool robot_dart::gui::magnum::BaseGraphics< T >::_enabled;\n
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1BaseGraphics/#variable-_fps","title":"variable _fps","text":"
int robot_dart::gui::magnum::BaseGraphics< T >::_fps;\n
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1BaseGraphics/#variable-_magnum_app","title":"variable _magnum_app","text":"
std::unique_ptr<BaseApplication> robot_dart::gui::magnum::BaseGraphics< T >::_magnum_app;\n
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1BaseGraphics/#variable-_magnum_silence_output","title":"variable _magnum_silence_output","text":"
Corrade::Utility::Debug robot_dart::gui::magnum::BaseGraphics< T >::_magnum_silence_output;\n

The documentation for this class was generated from the following file robot_dart/gui/magnum/base_graphics.hpp

"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1CubeMapShadowedColorObject/","title":"Class robot_dart::gui::magnum::CubeMapShadowedColorObject","text":"

ClassList > robot_dart > gui > magnum > CubeMapShadowedColorObject

Inherits the following classes: Object3D, Magnum::SceneGraph::Drawable3D

"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1CubeMapShadowedColorObject/#public-functions","title":"Public Functions","text":"Type Name CubeMapShadowedColorObject (RobotDARTSimu * simu, dart::dynamics::ShapeNode * shape, const std::vector< std::reference_wrapper< Magnum::GL::Mesh > > & meshes, gs::CubeMapColor & shader, gs::CubeMapColor & texture_shader, Object3D * parent, Magnum::SceneGraph::DrawableGroup3D * group) CubeMapShadowedColorObject & set_materials (const std::vector< gs::Material > & materials) CubeMapShadowedColorObject & set_meshes (const std::vector< std::reference_wrapper< Magnum::GL::Mesh > > & meshes) CubeMapShadowedColorObject & set_scalings (const std::vector< Magnum::Vector3 > & scalings) dart::dynamics::ShapeNode * shape () const RobotDARTSimu * simu () const"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1CubeMapShadowedColorObject/#public-functions-documentation","title":"Public Functions Documentation","text":""},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1CubeMapShadowedColorObject/#function-cubemapshadowedcolorobject","title":"function CubeMapShadowedColorObject","text":"
explicit robot_dart::gui::magnum::CubeMapShadowedColorObject::CubeMapShadowedColorObject (\nRobotDARTSimu * simu,\ndart::dynamics::ShapeNode * shape,\nconst std::vector< std::reference_wrapper< Magnum::GL::Mesh > > & meshes,\ngs::CubeMapColor & shader,\ngs::CubeMapColor & texture_shader,\nObject3D * parent,\nMagnum::SceneGraph::DrawableGroup3D * group\n) 
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1CubeMapShadowedColorObject/#function-set_materials","title":"function set_materials","text":"
CubeMapShadowedColorObject & robot_dart::gui::magnum::CubeMapShadowedColorObject::set_materials (\nconst std::vector< gs::Material > & materials\n) 
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1CubeMapShadowedColorObject/#function-set_meshes","title":"function set_meshes","text":"
CubeMapShadowedColorObject & robot_dart::gui::magnum::CubeMapShadowedColorObject::set_meshes (\nconst std::vector< std::reference_wrapper< Magnum::GL::Mesh > > & meshes\n) 
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1CubeMapShadowedColorObject/#function-set_scalings","title":"function set_scalings","text":"
CubeMapShadowedColorObject & robot_dart::gui::magnum::CubeMapShadowedColorObject::set_scalings (\nconst std::vector< Magnum::Vector3 > & scalings\n) 
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1CubeMapShadowedColorObject/#function-shape","title":"function shape","text":"
inline dart::dynamics::ShapeNode * robot_dart::gui::magnum::CubeMapShadowedColorObject::shape () const\n
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1CubeMapShadowedColorObject/#function-simu","title":"function simu","text":"
inline RobotDARTSimu * robot_dart::gui::magnum::CubeMapShadowedColorObject::simu () const\n

The documentation for this class was generated from the following file robot_dart/gui/magnum/drawables.hpp

"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1CubeMapShadowedObject/","title":"Class robot_dart::gui::magnum::CubeMapShadowedObject","text":"

ClassList > robot_dart > gui > magnum > CubeMapShadowedObject

Inherits the following classes: Object3D, Magnum::SceneGraph::Drawable3D

"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1CubeMapShadowedObject/#public-functions","title":"Public Functions","text":"Type Name CubeMapShadowedObject (RobotDARTSimu * simu, dart::dynamics::ShapeNode * shape, const std::vector< std::reference_wrapper< Magnum::GL::Mesh > > & meshes, gs::CubeMap & shader, gs::CubeMap & texture_shader, Object3D * parent, Magnum::SceneGraph::DrawableGroup3D * group) CubeMapShadowedObject & set_materials (const std::vector< gs::Material > & materials) CubeMapShadowedObject & set_meshes (const std::vector< std::reference_wrapper< Magnum::GL::Mesh > > & meshes) CubeMapShadowedObject & set_scalings (const std::vector< Magnum::Vector3 > & scalings) dart::dynamics::ShapeNode * shape () const RobotDARTSimu * simu () const"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1CubeMapShadowedObject/#public-functions-documentation","title":"Public Functions Documentation","text":""},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1CubeMapShadowedObject/#function-cubemapshadowedobject","title":"function CubeMapShadowedObject","text":"
explicit robot_dart::gui::magnum::CubeMapShadowedObject::CubeMapShadowedObject (\nRobotDARTSimu * simu,\ndart::dynamics::ShapeNode * shape,\nconst std::vector< std::reference_wrapper< Magnum::GL::Mesh > > & meshes,\ngs::CubeMap & shader,\ngs::CubeMap & texture_shader,\nObject3D * parent,\nMagnum::SceneGraph::DrawableGroup3D * group\n) 
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1CubeMapShadowedObject/#function-set_materials","title":"function set_materials","text":"
CubeMapShadowedObject & robot_dart::gui::magnum::CubeMapShadowedObject::set_materials (\nconst std::vector< gs::Material > & materials\n) 
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1CubeMapShadowedObject/#function-set_meshes","title":"function set_meshes","text":"
CubeMapShadowedObject & robot_dart::gui::magnum::CubeMapShadowedObject::set_meshes (\nconst std::vector< std::reference_wrapper< Magnum::GL::Mesh > > & meshes\n) 
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1CubeMapShadowedObject/#function-set_scalings","title":"function set_scalings","text":"
CubeMapShadowedObject & robot_dart::gui::magnum::CubeMapShadowedObject::set_scalings (\nconst std::vector< Magnum::Vector3 > & scalings\n) 
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1CubeMapShadowedObject/#function-shape","title":"function shape","text":"
inline dart::dynamics::ShapeNode * robot_dart::gui::magnum::CubeMapShadowedObject::shape () const\n
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1CubeMapShadowedObject/#function-simu","title":"function simu","text":"
inline RobotDARTSimu * robot_dart::gui::magnum::CubeMapShadowedObject::simu () const\n

The documentation for this class was generated from the following file robot_dart/gui/magnum/drawables.hpp

"},{"location":"api/structrobot__dart_1_1gui_1_1magnum_1_1DebugDrawData/","title":"Struct robot_dart::gui::magnum::DebugDrawData","text":"

ClassList > robot_dart > gui > magnum > DebugDrawData

"},{"location":"api/structrobot__dart_1_1gui_1_1magnum_1_1DebugDrawData/#public-attributes","title":"Public Attributes","text":"Type Name Magnum::GL::Mesh * axes_mesh Magnum::Shaders::VertexColorGL3D * axes_shader Magnum::GL::Mesh * background_mesh Magnum::Shaders::FlatGL2D * background_shader Magnum::Text::DistanceFieldGlyphCache * cache Magnum::Text::AbstractFont * font Magnum::GL::Buffer * text_indices Magnum::Shaders::DistanceFieldVectorGL2D * text_shader Magnum::GL::Buffer * text_vertices"},{"location":"api/structrobot__dart_1_1gui_1_1magnum_1_1DebugDrawData/#public-attributes-documentation","title":"Public Attributes Documentation","text":""},{"location":"api/structrobot__dart_1_1gui_1_1magnum_1_1DebugDrawData/#variable-axes_mesh","title":"variable axes_mesh","text":"
Magnum::GL::Mesh* robot_dart::gui::magnum::DebugDrawData::axes_mesh;\n
"},{"location":"api/structrobot__dart_1_1gui_1_1magnum_1_1DebugDrawData/#variable-axes_shader","title":"variable axes_shader","text":"
Magnum::Shaders::VertexColorGL3D* robot_dart::gui::magnum::DebugDrawData::axes_shader;\n
"},{"location":"api/structrobot__dart_1_1gui_1_1magnum_1_1DebugDrawData/#variable-background_mesh","title":"variable background_mesh","text":"
Magnum::GL::Mesh* robot_dart::gui::magnum::DebugDrawData::background_mesh;\n
"},{"location":"api/structrobot__dart_1_1gui_1_1magnum_1_1DebugDrawData/#variable-background_shader","title":"variable background_shader","text":"
Magnum::Shaders::FlatGL2D* robot_dart::gui::magnum::DebugDrawData::background_shader;\n
"},{"location":"api/structrobot__dart_1_1gui_1_1magnum_1_1DebugDrawData/#variable-cache","title":"variable cache","text":"
Magnum::Text::DistanceFieldGlyphCache* robot_dart::gui::magnum::DebugDrawData::cache;\n
"},{"location":"api/structrobot__dart_1_1gui_1_1magnum_1_1DebugDrawData/#variable-font","title":"variable font","text":"
Magnum::Text::AbstractFont* robot_dart::gui::magnum::DebugDrawData::font;\n
"},{"location":"api/structrobot__dart_1_1gui_1_1magnum_1_1DebugDrawData/#variable-text_indices","title":"variable text_indices","text":"
Magnum::GL::Buffer* robot_dart::gui::magnum::DebugDrawData::text_indices;\n
"},{"location":"api/structrobot__dart_1_1gui_1_1magnum_1_1DebugDrawData/#variable-text_shader","title":"variable text_shader","text":"
Magnum::Shaders::DistanceFieldVectorGL2D* robot_dart::gui::magnum::DebugDrawData::text_shader;\n
"},{"location":"api/structrobot__dart_1_1gui_1_1magnum_1_1DebugDrawData/#variable-text_vertices","title":"variable text_vertices","text":"
Magnum::GL::Buffer* robot_dart::gui::magnum::DebugDrawData::text_vertices;\n

The documentation for this class was generated from the following file robot_dart/gui/magnum/base_application.hpp

"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1DrawableObject/","title":"Class robot_dart::gui::magnum::DrawableObject","text":"

ClassList > robot_dart > gui > magnum > DrawableObject

Inherits the following classes: Object3D, Magnum::SceneGraph::Drawable3D

"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1DrawableObject/#public-functions","title":"Public Functions","text":"Type Name DrawableObject (RobotDARTSimu * simu, dart::dynamics::ShapeNode * shape, const std::vector< std::reference_wrapper< Magnum::GL::Mesh > > & meshes, const std::vector< gs::Material > & materials, gs::PhongMultiLight & color, gs::PhongMultiLight & texture, Object3D * parent, Magnum::SceneGraph::DrawableGroup3D * group) const std::vector< gs::Material > & materials () const DrawableObject & set_color_shader (std::reference_wrapper< gs::PhongMultiLight > shader) DrawableObject & set_materials (const std::vector< gs::Material > & materials) DrawableObject & set_meshes (const std::vector< std::reference_wrapper< Magnum::GL::Mesh > > & meshes) DrawableObject & set_scalings (const std::vector< Magnum::Vector3 > & scalings) DrawableObject & set_soft_bodies (const std::vector< bool > & softBody) DrawableObject & set_texture_shader (std::reference_wrapper< gs::PhongMultiLight > shader) DrawableObject & set_transparent (bool transparent=true) dart::dynamics::ShapeNode * shape () const RobotDARTSimu * simu () const bool transparent () const"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1DrawableObject/#public-functions-documentation","title":"Public Functions Documentation","text":""},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1DrawableObject/#function-drawableobject","title":"function DrawableObject","text":"
explicit robot_dart::gui::magnum::DrawableObject::DrawableObject (\nRobotDARTSimu * simu,\ndart::dynamics::ShapeNode * shape,\nconst std::vector< std::reference_wrapper< Magnum::GL::Mesh > > & meshes,\nconst std::vector< gs::Material > & materials,\ngs::PhongMultiLight & color,\ngs::PhongMultiLight & texture,\nObject3D * parent,\nMagnum::SceneGraph::DrawableGroup3D * group\n) 
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1DrawableObject/#function-materials","title":"function materials","text":"
inline const std::vector< gs::Material > & robot_dart::gui::magnum::DrawableObject::materials () const\n
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1DrawableObject/#function-set_color_shader","title":"function set_color_shader","text":"
DrawableObject & robot_dart::gui::magnum::DrawableObject::set_color_shader (\nstd::reference_wrapper< gs::PhongMultiLight > shader\n) 
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1DrawableObject/#function-set_materials","title":"function set_materials","text":"
DrawableObject & robot_dart::gui::magnum::DrawableObject::set_materials (\nconst std::vector< gs::Material > & materials\n) 
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1DrawableObject/#function-set_meshes","title":"function set_meshes","text":"
DrawableObject & robot_dart::gui::magnum::DrawableObject::set_meshes (\nconst std::vector< std::reference_wrapper< Magnum::GL::Mesh > > & meshes\n) 
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1DrawableObject/#function-set_scalings","title":"function set_scalings","text":"
DrawableObject & robot_dart::gui::magnum::DrawableObject::set_scalings (\nconst std::vector< Magnum::Vector3 > & scalings\n) 
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1DrawableObject/#function-set_soft_bodies","title":"function set_soft_bodies","text":"
DrawableObject & robot_dart::gui::magnum::DrawableObject::set_soft_bodies (\nconst std::vector< bool > & softBody\n) 
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1DrawableObject/#function-set_texture_shader","title":"function set_texture_shader","text":"
DrawableObject & robot_dart::gui::magnum::DrawableObject::set_texture_shader (\nstd::reference_wrapper< gs::PhongMultiLight > shader\n) 
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1DrawableObject/#function-set_transparent","title":"function set_transparent","text":"
DrawableObject & robot_dart::gui::magnum::DrawableObject::set_transparent (\nbool transparent=true\n) 
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1DrawableObject/#function-shape","title":"function shape","text":"
inline dart::dynamics::ShapeNode * robot_dart::gui::magnum::DrawableObject::shape () const\n
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1DrawableObject/#function-simu","title":"function simu","text":"
inline RobotDARTSimu * robot_dart::gui::magnum::DrawableObject::simu () const\n
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1DrawableObject/#function-transparent","title":"function transparent","text":"
inline bool robot_dart::gui::magnum::DrawableObject::transparent () const\n

The documentation for this class was generated from the following file robot_dart/gui/magnum/drawables.hpp

"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1GlfwApplication/","title":"Class robot_dart::gui::magnum::GlfwApplication","text":"

ClassList > robot_dart > gui > magnum > GlfwApplication

Inherits the following classes: robot_dart::gui::magnum::BaseApplication, Magnum::Platform::Application

"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1GlfwApplication/#public-functions","title":"Public Functions","text":"Type Name GlfwApplication (int argc, char ** argv, RobotDARTSimu * simu, const GraphicsConfiguration & configuration=GraphicsConfiguration()) virtual void render () override ~GlfwApplication ()"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1GlfwApplication/#public-functions-inherited-from-robot_dartguimagnumbaseapplication","title":"Public Functions inherited from robot_dart::gui::magnum::BaseApplication","text":"

See robot_dart::gui::magnum::BaseApplication

Type Name BaseApplication (const GraphicsConfiguration & configuration=GraphicsConfiguration()) void add_light (const gs::Light & light) bool attach_camera (gs::Camera & camera, dart::dynamics::BodyNode * body) gs::Camera & camera () const gs::Camera & camera () const void clear_lights () DebugDrawData debug_draw_data () DepthImage depth_array () GrayscaleImage depth_image () bool done () const Magnum::SceneGraph::DrawableGroup3D & drawables () void enable_shadows (bool enable=true, bool drawTransparentShadows=false) Corrade::Containers::Optional< Magnum::Image2D > & image () void init (RobotDARTSimu * simu, const GraphicsConfiguration & configuration) gs::Light & light (size_t i) std::vector< gs::Light > & lights () void look_at (const Eigen::Vector3d & camera_pos, const Eigen::Vector3d & look_at, const Eigen::Vector3d & up) size_t num_lights () const GrayscaleImage raw_depth_image () void record_video (const std::string & video_fname, int fps) virtual void render () void render_shadows () Scene3D & scene () bool shadowed () const bool transparent_shadows () const void update_graphics () void update_lights (const gs::Camera & camera) virtual ~BaseApplication ()"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1GlfwApplication/#protected-attributes","title":"Protected Attributes","text":"Type Name Magnum::Color4 _bg_color bool _draw_debug bool _draw_main_camera RobotDARTSimu * _simu Magnum::Float _speed_move Magnum::Float _speed_strafe"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1GlfwApplication/#protected-attributes-inherited-from-robot_dartguimagnumbaseapplication","title":"Protected Attributes inherited from robot_dart::gui::magnum::BaseApplication","text":"

See robot_dart::gui::magnum::BaseApplication

Type Name std::unique_ptr< Magnum::GL::Mesh > _3D_axis_mesh std::unique_ptr< Magnum::Shaders::VertexColorGL3D > _3D_axis_shader std::unique_ptr< Magnum::GL::Mesh > _background_mesh std::unique_ptr< Magnum::Shaders::FlatGL2D > _background_shader std::unique_ptr< gs::Camera > _camera std::unique_ptr< gs::PhongMultiLight > _color_shader GraphicsConfiguration _configuration Magnum::SceneGraph::DrawableGroup3D _cubemap_color_drawables std::unique_ptr< gs::CubeMapColor > _cubemap_color_shader Magnum::SceneGraph::DrawableGroup3D _cubemap_drawables std::unique_ptr< gs::CubeMap > _cubemap_shader std::unique_ptr< gs::CubeMapColor > _cubemap_texture_color_shader std::unique_ptr< gs::CubeMap > _cubemap_texture_shader std::unique_ptr< Magnum::DartIntegration::World > _dart_world bool _done = = false std::unordered_map< Magnum::DartIntegration::Object *, ObjectStruct * > _drawable_objects Magnum::SceneGraph::DrawableGroup3D _drawables Corrade::Containers::Pointer< Magnum::Text::AbstractFont > _font Corrade::PluginManager::Manager< Magnum::Text::AbstractFont > _font_manager Corrade::Containers::Pointer< Magnum::Text::DistanceFieldGlyphCache > _glyph_cache Corrade::PluginManager::Manager< Magnum::Trade::AbstractImporter > _importer_manager std::vector< gs::Light > _lights int _max_lights = = 5 Scene3D _scene std::unique_ptr< Camera3D > _shadow_camera Object3D * _shadow_camera_object std::unique_ptr< Magnum::GL::CubeMapTextureArray > _shadow_color_cube_map std::unique_ptr< gs::ShadowMapColor > _shadow_color_shader std::unique_ptr< Magnum::GL::Texture2DArray > _shadow_color_texture std::unique_ptr< Magnum::GL::CubeMapTextureArray > _shadow_cube_map std::vector< ShadowData > _shadow_data int _shadow_map_size = = 512 std::unique_ptr< gs::ShadowMap > _shadow_shader std::unique_ptr< Magnum::GL::Texture2DArray > _shadow_texture std::unique_ptr< gs::ShadowMapColor > _shadow_texture_color_shader std::unique_ptr< gs::ShadowMap > _shadow_texture_shader bool _shadowed = = true Magnum::SceneGraph::DrawableGroup3D _shadowed_color_drawables Magnum::SceneGraph::DrawableGroup3D _shadowed_drawables RobotDARTSimu * _simu Corrade::Containers::Pointer< Magnum::GL::Buffer > _text_indices std::unique_ptr< Magnum::Shaders::DistanceFieldVectorGL2D > _text_shader Corrade::Containers::Pointer< Magnum::GL::Buffer > _text_vertices std::unique_ptr< gs::PhongMultiLight > _texture_shader int _transparentSize = = 0 bool _transparent_shadows = = false"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1GlfwApplication/#protected-static-attributes","title":"Protected Static Attributes","text":"Type Name constexpr Magnum::Float _speed = = 0.05f"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1GlfwApplication/#protected-functions","title":"Protected Functions","text":"Type Name void drawEvent () override void exitEvent (ExitEvent & event) override virtual void keyPressEvent (KeyEvent & event) override virtual void keyReleaseEvent (KeyEvent & event) override virtual void mouseMoveEvent (MouseMoveEvent & event) override virtual void mouseScrollEvent (MouseScrollEvent & event) override void viewportEvent (ViewportEvent & event) override"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1GlfwApplication/#protected-functions-inherited-from-robot_dartguimagnumbaseapplication","title":"Protected Functions inherited from robot_dart::gui::magnum::BaseApplication","text":"

See robot_dart::gui::magnum::BaseApplication

Type Name void _gl_clean_up () void _prepare_shadows ()"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1GlfwApplication/#public-functions-documentation","title":"Public Functions Documentation","text":""},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1GlfwApplication/#function-glfwapplication","title":"function GlfwApplication","text":"
explicit robot_dart::gui::magnum::GlfwApplication::GlfwApplication (\nint argc,\nchar ** argv,\nRobotDARTSimu * simu,\nconst GraphicsConfiguration & configuration=GraphicsConfiguration ()\n) 
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1GlfwApplication/#function-render","title":"function render","text":"
virtual void robot_dart::gui::magnum::GlfwApplication::render () override\n

Implements robot_dart::gui::magnum::BaseApplication::render

"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1GlfwApplication/#function-glfwapplication_1","title":"function ~GlfwApplication","text":"
robot_dart::gui::magnum::GlfwApplication::~GlfwApplication () 
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1GlfwApplication/#protected-attributes-documentation","title":"Protected Attributes Documentation","text":""},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1GlfwApplication/#variable-_bg_color","title":"variable _bg_color","text":"
Magnum::Color4 robot_dart::gui::magnum::GlfwApplication::_bg_color;\n
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1GlfwApplication/#variable-_draw_debug","title":"variable _draw_debug","text":"
bool robot_dart::gui::magnum::GlfwApplication::_draw_debug;\n
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1GlfwApplication/#variable-_draw_main_camera","title":"variable _draw_main_camera","text":"
bool robot_dart::gui::magnum::GlfwApplication::_draw_main_camera;\n
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1GlfwApplication/#variable-_simu","title":"variable _simu","text":"
RobotDARTSimu* robot_dart::gui::magnum::GlfwApplication::_simu;\n
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1GlfwApplication/#variable-_speed_move","title":"variable _speed_move","text":"
Magnum::Float robot_dart::gui::magnum::GlfwApplication::_speed_move;\n
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1GlfwApplication/#variable-_speed_strafe","title":"variable _speed_strafe","text":"
Magnum::Float robot_dart::gui::magnum::GlfwApplication::_speed_strafe;\n
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1GlfwApplication/#protected-static-attributes-documentation","title":"Protected Static Attributes Documentation","text":""},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1GlfwApplication/#variable-_speed","title":"variable _speed","text":"
constexpr Magnum::Float robot_dart::gui::magnum::GlfwApplication::_speed;\n
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1GlfwApplication/#protected-functions-documentation","title":"Protected Functions Documentation","text":""},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1GlfwApplication/#function-drawevent","title":"function drawEvent","text":"
void robot_dart::gui::magnum::GlfwApplication::drawEvent () override\n
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1GlfwApplication/#function-exitevent","title":"function exitEvent","text":"
void robot_dart::gui::magnum::GlfwApplication::exitEvent (\nExitEvent & event\n) override\n
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1GlfwApplication/#function-keypressevent","title":"function keyPressEvent","text":"
virtual void robot_dart::gui::magnum::GlfwApplication::keyPressEvent (\nKeyEvent & event\n) override\n
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1GlfwApplication/#function-keyreleaseevent","title":"function keyReleaseEvent","text":"
virtual void robot_dart::gui::magnum::GlfwApplication::keyReleaseEvent (\nKeyEvent & event\n) override\n
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1GlfwApplication/#function-mousemoveevent","title":"function mouseMoveEvent","text":"
virtual void robot_dart::gui::magnum::GlfwApplication::mouseMoveEvent (\nMouseMoveEvent & event\n) override\n
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1GlfwApplication/#function-mousescrollevent","title":"function mouseScrollEvent","text":"
virtual void robot_dart::gui::magnum::GlfwApplication::mouseScrollEvent (\nMouseScrollEvent & event\n) override\n
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1GlfwApplication/#function-viewportevent","title":"function viewportEvent","text":"
void robot_dart::gui::magnum::GlfwApplication::viewportEvent (\nViewportEvent & event\n) override\n

The documentation for this class was generated from the following file robot_dart/gui/magnum/glfw_application.hpp

"},{"location":"api/structrobot__dart_1_1gui_1_1magnum_1_1GlobalData/","title":"Struct robot_dart::gui::magnum::GlobalData","text":"

ClassList > robot_dart > gui > magnum > GlobalData

"},{"location":"api/structrobot__dart_1_1gui_1_1magnum_1_1GlobalData/#public-functions","title":"Public Functions","text":"Type Name GlobalData (const GlobalData &) = delete void free_gl_context (Magnum::Platform::WindowlessGLContext * context) Magnum::Platform::WindowlessGLContext * gl_context () void operator= (const GlobalData &) = delete void set_max_contexts (size_t N)"},{"location":"api/structrobot__dart_1_1gui_1_1magnum_1_1GlobalData/#public-static-functions","title":"Public Static Functions","text":"Type Name GlobalData * instance ()"},{"location":"api/structrobot__dart_1_1gui_1_1magnum_1_1GlobalData/#public-functions-documentation","title":"Public Functions Documentation","text":""},{"location":"api/structrobot__dart_1_1gui_1_1magnum_1_1GlobalData/#function-globaldata-12","title":"function GlobalData [\u00bd]","text":"
robot_dart::gui::magnum::GlobalData::GlobalData (\nconst GlobalData &\n) = delete\n
"},{"location":"api/structrobot__dart_1_1gui_1_1magnum_1_1GlobalData/#function-free_gl_context","title":"function free_gl_context","text":"
void robot_dart::gui::magnum::GlobalData::free_gl_context (\nMagnum::Platform::WindowlessGLContext * context\n) 
"},{"location":"api/structrobot__dart_1_1gui_1_1magnum_1_1GlobalData/#function-gl_context","title":"function gl_context","text":"
Magnum::Platform::WindowlessGLContext * robot_dart::gui::magnum::GlobalData::gl_context () 
"},{"location":"api/structrobot__dart_1_1gui_1_1magnum_1_1GlobalData/#function-operator","title":"function operator=","text":"
void robot_dart::gui::magnum::GlobalData::operator= (\nconst GlobalData &\n) = delete\n
"},{"location":"api/structrobot__dart_1_1gui_1_1magnum_1_1GlobalData/#function-set_max_contexts","title":"function set_max_contexts","text":"
void robot_dart::gui::magnum::GlobalData::set_max_contexts (\nsize_t N\n) 
"},{"location":"api/structrobot__dart_1_1gui_1_1magnum_1_1GlobalData/#public-static-functions-documentation","title":"Public Static Functions Documentation","text":""},{"location":"api/structrobot__dart_1_1gui_1_1magnum_1_1GlobalData/#function-instance","title":"function instance","text":"
static inline GlobalData * robot_dart::gui::magnum::GlobalData::instance () 

The documentation for this class was generated from the following file robot_dart/gui/magnum/base_application.hpp

"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1Graphics/","title":"Class robot_dart::gui::magnum::Graphics","text":"

ClassList > robot_dart > gui > magnum > Graphics

Inherits the following classes: robot_dart::gui::magnum::BaseGraphics

"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1Graphics/#public-functions","title":"Public Functions","text":"Type Name Graphics (const GraphicsConfiguration & configuration=default_configuration()) virtual void set_simu (RobotDARTSimu * simu) override ~Graphics ()"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1Graphics/#public-functions-inherited-from-robot_dartguimagnumbasegraphics","title":"Public Functions inherited from robot_dart::gui::magnum::BaseGraphics","text":"

See robot_dart::gui::magnum::BaseGraphics

Type Name BaseGraphics (const GraphicsConfiguration & configuration=GraphicsConfiguration()) void add_light (const magnum::Light & light) gs::Camera & camera () const gs::Camera & camera () const Eigen::Matrix4d camera_extrinsic_matrix () const Eigen::Matrix3d camera_intrinsic_matrix () const void clear_lights () virtual DepthImage depth_array () override virtual GrayscaleImage depth_image () override virtual bool done () override const void enable_shadows (bool enable=true, bool transparent=true) virtual size_t height () override const virtual Image image () override magnum::Light & light (size_t i) std::vector< gs::Light > & lights () void look_at (const Eigen::Vector3d & camera_pos, const Eigen::Vector3d & look_at=Eigen::Vector3d(0, 0, 0), const Eigen::Vector3d & up=Eigen::Vector3d(0, 0, 1)) BaseApplication * magnum_app () const BaseApplication * magnum_app () const Magnum::Image2D * magnum_image () size_t num_lights () const virtual GrayscaleImage raw_depth_image () override void record_video (const std::string & video_fname, int fps=-1) virtual void refresh () override virtual void set_enable (bool enable) override virtual void set_fps (int fps) override virtual void set_simu (RobotDARTSimu * simu) override bool shadowed () const bool transparent_shadows () const virtual size_t width () override const virtual ~BaseGraphics ()"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1Graphics/#public-functions-inherited-from-robot_dartguibase","title":"Public Functions inherited from robot_dart::gui::Base","text":"

See robot_dart::gui::Base

Type Name Base () virtual DepthImage depth_array () virtual GrayscaleImage depth_image () virtual bool done () const virtual size_t height () const virtual Image image () virtual GrayscaleImage raw_depth_image () virtual void refresh () virtual void set_enable (bool) virtual void set_fps (int) virtual void set_render_period (double) virtual void set_simu (RobotDARTSimu * simu) const RobotDARTSimu * simu () const virtual size_t width () const virtual ~Base ()"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1Graphics/#public-static-functions","title":"Public Static Functions","text":"Type Name GraphicsConfiguration default_configuration ()"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1Graphics/#protected-attributes-inherited-from-robot_dartguimagnumbasegraphics","title":"Protected Attributes inherited from robot_dart::gui::magnum::BaseGraphics","text":"

See robot_dart::gui::magnum::BaseGraphics

Type Name GraphicsConfiguration _configuration bool _enabled int _fps std::unique_ptr< BaseApplication > _magnum_app Corrade::Utility::Debug _magnum_silence_output = {nullptr}"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1Graphics/#protected-attributes-inherited-from-robot_dartguibase","title":"Protected Attributes inherited from robot_dart::gui::Base","text":"

See robot_dart::gui::Base

Type Name RobotDARTSimu * _simu = = nullptr"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1Graphics/#public-functions-documentation","title":"Public Functions Documentation","text":""},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1Graphics/#function-graphics","title":"function Graphics","text":"
inline robot_dart::gui::magnum::Graphics::Graphics (\nconst GraphicsConfiguration & configuration=default_configuration()\n) 
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1Graphics/#function-set_simu","title":"function set_simu","text":"
virtual void robot_dart::gui::magnum::Graphics::set_simu (\nRobotDARTSimu * simu\n) override\n

Implements robot_dart::gui::magnum::BaseGraphics::set_simu

"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1Graphics/#function-graphics_1","title":"function ~Graphics","text":"
inline robot_dart::gui::magnum::Graphics::~Graphics () 
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1Graphics/#public-static-functions-documentation","title":"Public Static Functions Documentation","text":""},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1Graphics/#function-default_configuration","title":"function default_configuration","text":"
static GraphicsConfiguration robot_dart::gui::magnum::Graphics::default_configuration () 

The documentation for this class was generated from the following file robot_dart/gui/magnum/graphics.hpp

"},{"location":"api/structrobot__dart_1_1gui_1_1magnum_1_1GraphicsConfiguration/","title":"Struct robot_dart::gui::magnum::GraphicsConfiguration","text":"

ClassList > robot_dart > gui > magnum > GraphicsConfiguration

"},{"location":"api/structrobot__dart_1_1gui_1_1magnum_1_1GraphicsConfiguration/#public-attributes","title":"Public Attributes","text":"Type Name Eigen::Vector4d bg_color = {0.0, 0.0, 0.0, 1.0} bool draw_debug = = true bool draw_main_camera = = true bool draw_text = = true size_t height = = 480 size_t max_lights = = 3 size_t shadow_map_size = = 1024 bool shadowed = = true double specular_strength = = 0.25 std::string title = = \"DART\" bool transparent_shadows = = true size_t width = = 640"},{"location":"api/structrobot__dart_1_1gui_1_1magnum_1_1GraphicsConfiguration/#public-attributes-documentation","title":"Public Attributes Documentation","text":""},{"location":"api/structrobot__dart_1_1gui_1_1magnum_1_1GraphicsConfiguration/#variable-bg_color","title":"variable bg_color","text":"
Eigen::Vector4d robot_dart::gui::magnum::GraphicsConfiguration::bg_color;\n
"},{"location":"api/structrobot__dart_1_1gui_1_1magnum_1_1GraphicsConfiguration/#variable-draw_debug","title":"variable draw_debug","text":"
bool robot_dart::gui::magnum::GraphicsConfiguration::draw_debug;\n
"},{"location":"api/structrobot__dart_1_1gui_1_1magnum_1_1GraphicsConfiguration/#variable-draw_main_camera","title":"variable draw_main_camera","text":"
bool robot_dart::gui::magnum::GraphicsConfiguration::draw_main_camera;\n
"},{"location":"api/structrobot__dart_1_1gui_1_1magnum_1_1GraphicsConfiguration/#variable-draw_text","title":"variable draw_text","text":"
bool robot_dart::gui::magnum::GraphicsConfiguration::draw_text;\n
"},{"location":"api/structrobot__dart_1_1gui_1_1magnum_1_1GraphicsConfiguration/#variable-height","title":"variable height","text":"
size_t robot_dart::gui::magnum::GraphicsConfiguration::height;\n
"},{"location":"api/structrobot__dart_1_1gui_1_1magnum_1_1GraphicsConfiguration/#variable-max_lights","title":"variable max_lights","text":"
size_t robot_dart::gui::magnum::GraphicsConfiguration::max_lights;\n
"},{"location":"api/structrobot__dart_1_1gui_1_1magnum_1_1GraphicsConfiguration/#variable-shadow_map_size","title":"variable shadow_map_size","text":"
size_t robot_dart::gui::magnum::GraphicsConfiguration::shadow_map_size;\n
"},{"location":"api/structrobot__dart_1_1gui_1_1magnum_1_1GraphicsConfiguration/#variable-shadowed","title":"variable shadowed","text":"
bool robot_dart::gui::magnum::GraphicsConfiguration::shadowed;\n
"},{"location":"api/structrobot__dart_1_1gui_1_1magnum_1_1GraphicsConfiguration/#variable-specular_strength","title":"variable specular_strength","text":"
double robot_dart::gui::magnum::GraphicsConfiguration::specular_strength;\n
"},{"location":"api/structrobot__dart_1_1gui_1_1magnum_1_1GraphicsConfiguration/#variable-title","title":"variable title","text":"
std::string robot_dart::gui::magnum::GraphicsConfiguration::title;\n
"},{"location":"api/structrobot__dart_1_1gui_1_1magnum_1_1GraphicsConfiguration/#variable-transparent_shadows","title":"variable transparent_shadows","text":"
bool robot_dart::gui::magnum::GraphicsConfiguration::transparent_shadows;\n
"},{"location":"api/structrobot__dart_1_1gui_1_1magnum_1_1GraphicsConfiguration/#variable-width","title":"variable width","text":"
size_t robot_dart::gui::magnum::GraphicsConfiguration::width;\n

The documentation for this class was generated from the following file robot_dart/gui/magnum/base_application.hpp

"},{"location":"api/structrobot__dart_1_1gui_1_1magnum_1_1ObjectStruct/","title":"Struct robot_dart::gui::magnum::ObjectStruct","text":"

ClassList > robot_dart > gui > magnum > ObjectStruct

"},{"location":"api/structrobot__dart_1_1gui_1_1magnum_1_1ObjectStruct/#public-attributes","title":"Public Attributes","text":"Type Name CubeMapShadowedObject * cubemapped CubeMapShadowedColorObject * cubemapped_color DrawableObject * drawable ShadowedObject * shadowed ShadowedColorObject * shadowed_color"},{"location":"api/structrobot__dart_1_1gui_1_1magnum_1_1ObjectStruct/#public-attributes-documentation","title":"Public Attributes Documentation","text":""},{"location":"api/structrobot__dart_1_1gui_1_1magnum_1_1ObjectStruct/#variable-cubemapped","title":"variable cubemapped","text":"
CubeMapShadowedObject* robot_dart::gui::magnum::ObjectStruct::cubemapped;\n
"},{"location":"api/structrobot__dart_1_1gui_1_1magnum_1_1ObjectStruct/#variable-cubemapped_color","title":"variable cubemapped_color","text":"
CubeMapShadowedColorObject* robot_dart::gui::magnum::ObjectStruct::cubemapped_color;\n
"},{"location":"api/structrobot__dart_1_1gui_1_1magnum_1_1ObjectStruct/#variable-drawable","title":"variable drawable","text":"
DrawableObject* robot_dart::gui::magnum::ObjectStruct::drawable;\n
"},{"location":"api/structrobot__dart_1_1gui_1_1magnum_1_1ObjectStruct/#variable-shadowed","title":"variable shadowed","text":"
ShadowedObject* robot_dart::gui::magnum::ObjectStruct::shadowed;\n
"},{"location":"api/structrobot__dart_1_1gui_1_1magnum_1_1ObjectStruct/#variable-shadowed_color","title":"variable shadowed_color","text":"
ShadowedColorObject* robot_dart::gui::magnum::ObjectStruct::shadowed_color;\n

The documentation for this class was generated from the following file robot_dart/gui/magnum/drawables.hpp

"},{"location":"api/structrobot__dart_1_1gui_1_1magnum_1_1ShadowData/","title":"Struct robot_dart::gui::magnum::ShadowData","text":"

ClassList > robot_dart > gui > magnum > ShadowData

"},{"location":"api/structrobot__dart_1_1gui_1_1magnum_1_1ShadowData/#public-attributes","title":"Public Attributes","text":"Type Name Magnum::GL::Framebuffer shadow_color_framebuffer = {Magnum::NoCreate} Magnum::GL::Framebuffer shadow_framebuffer = {Magnum::NoCreate}"},{"location":"api/structrobot__dart_1_1gui_1_1magnum_1_1ShadowData/#public-attributes-documentation","title":"Public Attributes Documentation","text":""},{"location":"api/structrobot__dart_1_1gui_1_1magnum_1_1ShadowData/#variable-shadow_color_framebuffer","title":"variable shadow_color_framebuffer","text":"
Magnum::GL::Framebuffer robot_dart::gui::magnum::ShadowData::shadow_color_framebuffer;\n
"},{"location":"api/structrobot__dart_1_1gui_1_1magnum_1_1ShadowData/#variable-shadow_framebuffer","title":"variable shadow_framebuffer","text":"
Magnum::GL::Framebuffer robot_dart::gui::magnum::ShadowData::shadow_framebuffer;\n

The documentation for this class was generated from the following file robot_dart/gui/magnum/drawables.hpp

"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1ShadowedColorObject/","title":"Class robot_dart::gui::magnum::ShadowedColorObject","text":"

ClassList > robot_dart > gui > magnum > ShadowedColorObject

Inherits the following classes: Object3D, Magnum::SceneGraph::Drawable3D

"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1ShadowedColorObject/#public-functions","title":"Public Functions","text":"Type Name ShadowedColorObject (RobotDARTSimu * simu, dart::dynamics::ShapeNode * shape, const std::vector< std::reference_wrapper< Magnum::GL::Mesh > > & meshes, gs::ShadowMapColor & shader, gs::ShadowMapColor & texture_shader, Object3D * parent, Magnum::SceneGraph::DrawableGroup3D * group) ShadowedColorObject & set_materials (const std::vector< gs::Material > & materials) ShadowedColorObject & set_meshes (const std::vector< std::reference_wrapper< Magnum::GL::Mesh > > & meshes) ShadowedColorObject & set_scalings (const std::vector< Magnum::Vector3 > & scalings) dart::dynamics::ShapeNode * shape () const RobotDARTSimu * simu () const"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1ShadowedColorObject/#public-functions-documentation","title":"Public Functions Documentation","text":""},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1ShadowedColorObject/#function-shadowedcolorobject","title":"function ShadowedColorObject","text":"
explicit robot_dart::gui::magnum::ShadowedColorObject::ShadowedColorObject (\nRobotDARTSimu * simu,\ndart::dynamics::ShapeNode * shape,\nconst std::vector< std::reference_wrapper< Magnum::GL::Mesh > > & meshes,\ngs::ShadowMapColor & shader,\ngs::ShadowMapColor & texture_shader,\nObject3D * parent,\nMagnum::SceneGraph::DrawableGroup3D * group\n) 
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1ShadowedColorObject/#function-set_materials","title":"function set_materials","text":"
ShadowedColorObject & robot_dart::gui::magnum::ShadowedColorObject::set_materials (\nconst std::vector< gs::Material > & materials\n) 
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1ShadowedColorObject/#function-set_meshes","title":"function set_meshes","text":"
ShadowedColorObject & robot_dart::gui::magnum::ShadowedColorObject::set_meshes (\nconst std::vector< std::reference_wrapper< Magnum::GL::Mesh > > & meshes\n) 
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1ShadowedColorObject/#function-set_scalings","title":"function set_scalings","text":"
ShadowedColorObject & robot_dart::gui::magnum::ShadowedColorObject::set_scalings (\nconst std::vector< Magnum::Vector3 > & scalings\n) 
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1ShadowedColorObject/#function-shape","title":"function shape","text":"
inline dart::dynamics::ShapeNode * robot_dart::gui::magnum::ShadowedColorObject::shape () const\n
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1ShadowedColorObject/#function-simu","title":"function simu","text":"
inline RobotDARTSimu * robot_dart::gui::magnum::ShadowedColorObject::simu () const\n

The documentation for this class was generated from the following file robot_dart/gui/magnum/drawables.hpp

"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1ShadowedObject/","title":"Class robot_dart::gui::magnum::ShadowedObject","text":"

ClassList > robot_dart > gui > magnum > ShadowedObject

Inherits the following classes: Object3D, Magnum::SceneGraph::Drawable3D

"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1ShadowedObject/#public-functions","title":"Public Functions","text":"Type Name ShadowedObject (RobotDARTSimu * simu, dart::dynamics::ShapeNode * shape, const std::vector< std::reference_wrapper< Magnum::GL::Mesh > > & meshes, gs::ShadowMap & shader, gs::ShadowMap & texture_shader, Object3D * parent, Magnum::SceneGraph::DrawableGroup3D * group) ShadowedObject & set_materials (const std::vector< gs::Material > & materials) ShadowedObject & set_meshes (const std::vector< std::reference_wrapper< Magnum::GL::Mesh > > & meshes) ShadowedObject & set_scalings (const std::vector< Magnum::Vector3 > & scalings) dart::dynamics::ShapeNode * shape () const RobotDARTSimu * simu () const"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1ShadowedObject/#public-functions-documentation","title":"Public Functions Documentation","text":""},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1ShadowedObject/#function-shadowedobject","title":"function ShadowedObject","text":"
explicit robot_dart::gui::magnum::ShadowedObject::ShadowedObject (\nRobotDARTSimu * simu,\ndart::dynamics::ShapeNode * shape,\nconst std::vector< std::reference_wrapper< Magnum::GL::Mesh > > & meshes,\ngs::ShadowMap & shader,\ngs::ShadowMap & texture_shader,\nObject3D * parent,\nMagnum::SceneGraph::DrawableGroup3D * group\n) 
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1ShadowedObject/#function-set_materials","title":"function set_materials","text":"
ShadowedObject & robot_dart::gui::magnum::ShadowedObject::set_materials (\nconst std::vector< gs::Material > & materials\n) 
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1ShadowedObject/#function-set_meshes","title":"function set_meshes","text":"
ShadowedObject & robot_dart::gui::magnum::ShadowedObject::set_meshes (\nconst std::vector< std::reference_wrapper< Magnum::GL::Mesh > > & meshes\n) 
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1ShadowedObject/#function-set_scalings","title":"function set_scalings","text":"
ShadowedObject & robot_dart::gui::magnum::ShadowedObject::set_scalings (\nconst std::vector< Magnum::Vector3 > & scalings\n) 
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1ShadowedObject/#function-shape","title":"function shape","text":"
inline dart::dynamics::ShapeNode * robot_dart::gui::magnum::ShadowedObject::shape () const\n
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1ShadowedObject/#function-simu","title":"function simu","text":"
inline RobotDARTSimu * robot_dart::gui::magnum::ShadowedObject::simu () const\n

The documentation for this class was generated from the following file robot_dart/gui/magnum/drawables.hpp

"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1WindowlessGLApplication/","title":"Class robot_dart::gui::magnum::WindowlessGLApplication","text":"

ClassList > robot_dart > gui > magnum > WindowlessGLApplication

Inherits the following classes: robot_dart::gui::magnum::BaseApplication, Magnum::Platform::WindowlessApplication

"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1WindowlessGLApplication/#public-functions","title":"Public Functions","text":"Type Name WindowlessGLApplication (int argc, char ** argv, RobotDARTSimu * simu, const GraphicsConfiguration & configuration=GraphicsConfiguration()) virtual void render () override ~WindowlessGLApplication ()"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1WindowlessGLApplication/#public-functions-inherited-from-robot_dartguimagnumbaseapplication","title":"Public Functions inherited from robot_dart::gui::magnum::BaseApplication","text":"

See robot_dart::gui::magnum::BaseApplication

Type Name BaseApplication (const GraphicsConfiguration & configuration=GraphicsConfiguration()) void add_light (const gs::Light & light) bool attach_camera (gs::Camera & camera, dart::dynamics::BodyNode * body) gs::Camera & camera () const gs::Camera & camera () const void clear_lights () DebugDrawData debug_draw_data () DepthImage depth_array () GrayscaleImage depth_image () bool done () const Magnum::SceneGraph::DrawableGroup3D & drawables () void enable_shadows (bool enable=true, bool drawTransparentShadows=false) Corrade::Containers::Optional< Magnum::Image2D > & image () void init (RobotDARTSimu * simu, const GraphicsConfiguration & configuration) gs::Light & light (size_t i) std::vector< gs::Light > & lights () void look_at (const Eigen::Vector3d & camera_pos, const Eigen::Vector3d & look_at, const Eigen::Vector3d & up) size_t num_lights () const GrayscaleImage raw_depth_image () void record_video (const std::string & video_fname, int fps) virtual void render () void render_shadows () Scene3D & scene () bool shadowed () const bool transparent_shadows () const void update_graphics () void update_lights (const gs::Camera & camera) virtual ~BaseApplication ()"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1WindowlessGLApplication/#protected-attributes","title":"Protected Attributes","text":"Type Name Magnum::Color4 _bg_color Magnum::GL::Renderbuffer _color = {Magnum::NoCreate} Magnum::GL::Renderbuffer _depth = {Magnum::NoCreate} bool _draw_debug bool _draw_main_camera Magnum::PixelFormat _format Magnum::GL::Framebuffer _framebuffer = {Magnum::NoCreate} RobotDARTSimu * _simu"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1WindowlessGLApplication/#protected-attributes-inherited-from-robot_dartguimagnumbaseapplication","title":"Protected Attributes inherited from robot_dart::gui::magnum::BaseApplication","text":"

See robot_dart::gui::magnum::BaseApplication

Type Name std::unique_ptr< Magnum::GL::Mesh > _3D_axis_mesh std::unique_ptr< Magnum::Shaders::VertexColorGL3D > _3D_axis_shader std::unique_ptr< Magnum::GL::Mesh > _background_mesh std::unique_ptr< Magnum::Shaders::FlatGL2D > _background_shader std::unique_ptr< gs::Camera > _camera std::unique_ptr< gs::PhongMultiLight > _color_shader GraphicsConfiguration _configuration Magnum::SceneGraph::DrawableGroup3D _cubemap_color_drawables std::unique_ptr< gs::CubeMapColor > _cubemap_color_shader Magnum::SceneGraph::DrawableGroup3D _cubemap_drawables std::unique_ptr< gs::CubeMap > _cubemap_shader std::unique_ptr< gs::CubeMapColor > _cubemap_texture_color_shader std::unique_ptr< gs::CubeMap > _cubemap_texture_shader std::unique_ptr< Magnum::DartIntegration::World > _dart_world bool _done = = false std::unordered_map< Magnum::DartIntegration::Object *, ObjectStruct * > _drawable_objects Magnum::SceneGraph::DrawableGroup3D _drawables Corrade::Containers::Pointer< Magnum::Text::AbstractFont > _font Corrade::PluginManager::Manager< Magnum::Text::AbstractFont > _font_manager Corrade::Containers::Pointer< Magnum::Text::DistanceFieldGlyphCache > _glyph_cache Corrade::PluginManager::Manager< Magnum::Trade::AbstractImporter > _importer_manager std::vector< gs::Light > _lights int _max_lights = = 5 Scene3D _scene std::unique_ptr< Camera3D > _shadow_camera Object3D * _shadow_camera_object std::unique_ptr< Magnum::GL::CubeMapTextureArray > _shadow_color_cube_map std::unique_ptr< gs::ShadowMapColor > _shadow_color_shader std::unique_ptr< Magnum::GL::Texture2DArray > _shadow_color_texture std::unique_ptr< Magnum::GL::CubeMapTextureArray > _shadow_cube_map std::vector< ShadowData > _shadow_data int _shadow_map_size = = 512 std::unique_ptr< gs::ShadowMap > _shadow_shader std::unique_ptr< Magnum::GL::Texture2DArray > _shadow_texture std::unique_ptr< gs::ShadowMapColor > _shadow_texture_color_shader std::unique_ptr< gs::ShadowMap > _shadow_texture_shader bool _shadowed = = true Magnum::SceneGraph::DrawableGroup3D _shadowed_color_drawables Magnum::SceneGraph::DrawableGroup3D _shadowed_drawables RobotDARTSimu * _simu Corrade::Containers::Pointer< Magnum::GL::Buffer > _text_indices std::unique_ptr< Magnum::Shaders::DistanceFieldVectorGL2D > _text_shader Corrade::Containers::Pointer< Magnum::GL::Buffer > _text_vertices std::unique_ptr< gs::PhongMultiLight > _texture_shader int _transparentSize = = 0 bool _transparent_shadows = = false"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1WindowlessGLApplication/#protected-functions","title":"Protected Functions","text":"Type Name virtual int exec () override"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1WindowlessGLApplication/#protected-functions-inherited-from-robot_dartguimagnumbaseapplication","title":"Protected Functions inherited from robot_dart::gui::magnum::BaseApplication","text":"

See robot_dart::gui::magnum::BaseApplication

Type Name void _gl_clean_up () void _prepare_shadows ()"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1WindowlessGLApplication/#public-functions-documentation","title":"Public Functions Documentation","text":""},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1WindowlessGLApplication/#function-windowlessglapplication","title":"function WindowlessGLApplication","text":"
explicit robot_dart::gui::magnum::WindowlessGLApplication::WindowlessGLApplication (\nint argc,\nchar ** argv,\nRobotDARTSimu * simu,\nconst GraphicsConfiguration & configuration=GraphicsConfiguration ()\n) 
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1WindowlessGLApplication/#function-render","title":"function render","text":"
virtual void robot_dart::gui::magnum::WindowlessGLApplication::render () override\n

Implements robot_dart::gui::magnum::BaseApplication::render

"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1WindowlessGLApplication/#function-windowlessglapplication_1","title":"function ~WindowlessGLApplication","text":"
robot_dart::gui::magnum::WindowlessGLApplication::~WindowlessGLApplication () 
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1WindowlessGLApplication/#protected-attributes-documentation","title":"Protected Attributes Documentation","text":""},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1WindowlessGLApplication/#variable-_bg_color","title":"variable _bg_color","text":"
Magnum::Color4 robot_dart::gui::magnum::WindowlessGLApplication::_bg_color;\n
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1WindowlessGLApplication/#variable-_color","title":"variable _color","text":"
Magnum::GL::Renderbuffer robot_dart::gui::magnum::WindowlessGLApplication::_color;\n
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1WindowlessGLApplication/#variable-_depth","title":"variable _depth","text":"
Magnum::GL::Renderbuffer robot_dart::gui::magnum::WindowlessGLApplication::_depth;\n
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1WindowlessGLApplication/#variable-_draw_debug","title":"variable _draw_debug","text":"
bool robot_dart::gui::magnum::WindowlessGLApplication::_draw_debug;\n
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1WindowlessGLApplication/#variable-_draw_main_camera","title":"variable _draw_main_camera","text":"
bool robot_dart::gui::magnum::WindowlessGLApplication::_draw_main_camera;\n
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1WindowlessGLApplication/#variable-_format","title":"variable _format","text":"
Magnum::PixelFormat robot_dart::gui::magnum::WindowlessGLApplication::_format;\n
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1WindowlessGLApplication/#variable-_framebuffer","title":"variable _framebuffer","text":"
Magnum::GL::Framebuffer robot_dart::gui::magnum::WindowlessGLApplication::_framebuffer;\n
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1WindowlessGLApplication/#variable-_simu","title":"variable _simu","text":"
RobotDARTSimu* robot_dart::gui::magnum::WindowlessGLApplication::_simu;\n
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1WindowlessGLApplication/#protected-functions-documentation","title":"Protected Functions Documentation","text":""},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1WindowlessGLApplication/#function-exec","title":"function exec","text":"
inline virtual int robot_dart::gui::magnum::WindowlessGLApplication::exec () override\n

The documentation for this class was generated from the following file robot_dart/gui/magnum/windowless_gl_application.hpp

"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1WindowlessGraphics/","title":"Class robot_dart::gui::magnum::WindowlessGraphics","text":"

ClassList > robot_dart > gui > magnum > WindowlessGraphics

Inherits the following classes: robot_dart::gui::magnum::BaseGraphics

"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1WindowlessGraphics/#public-functions","title":"Public Functions","text":"Type Name WindowlessGraphics (const GraphicsConfiguration & configuration=default_configuration()) virtual void set_simu (RobotDARTSimu * simu) override ~WindowlessGraphics ()"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1WindowlessGraphics/#public-functions-inherited-from-robot_dartguimagnumbasegraphics","title":"Public Functions inherited from robot_dart::gui::magnum::BaseGraphics","text":"

See robot_dart::gui::magnum::BaseGraphics

Type Name BaseGraphics (const GraphicsConfiguration & configuration=GraphicsConfiguration()) void add_light (const magnum::Light & light) gs::Camera & camera () const gs::Camera & camera () const Eigen::Matrix4d camera_extrinsic_matrix () const Eigen::Matrix3d camera_intrinsic_matrix () const void clear_lights () virtual DepthImage depth_array () override virtual GrayscaleImage depth_image () override virtual bool done () override const void enable_shadows (bool enable=true, bool transparent=true) virtual size_t height () override const virtual Image image () override magnum::Light & light (size_t i) std::vector< gs::Light > & lights () void look_at (const Eigen::Vector3d & camera_pos, const Eigen::Vector3d & look_at=Eigen::Vector3d(0, 0, 0), const Eigen::Vector3d & up=Eigen::Vector3d(0, 0, 1)) BaseApplication * magnum_app () const BaseApplication * magnum_app () const Magnum::Image2D * magnum_image () size_t num_lights () const virtual GrayscaleImage raw_depth_image () override void record_video (const std::string & video_fname, int fps=-1) virtual void refresh () override virtual void set_enable (bool enable) override virtual void set_fps (int fps) override virtual void set_simu (RobotDARTSimu * simu) override bool shadowed () const bool transparent_shadows () const virtual size_t width () override const virtual ~BaseGraphics ()"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1WindowlessGraphics/#public-functions-inherited-from-robot_dartguibase","title":"Public Functions inherited from robot_dart::gui::Base","text":"

See robot_dart::gui::Base

Type Name Base () virtual DepthImage depth_array () virtual GrayscaleImage depth_image () virtual bool done () const virtual size_t height () const virtual Image image () virtual GrayscaleImage raw_depth_image () virtual void refresh () virtual void set_enable (bool) virtual void set_fps (int) virtual void set_render_period (double) virtual void set_simu (RobotDARTSimu * simu) const RobotDARTSimu * simu () const virtual size_t width () const virtual ~Base ()"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1WindowlessGraphics/#public-static-functions","title":"Public Static Functions","text":"Type Name GraphicsConfiguration default_configuration ()"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1WindowlessGraphics/#protected-attributes-inherited-from-robot_dartguimagnumbasegraphics","title":"Protected Attributes inherited from robot_dart::gui::magnum::BaseGraphics","text":"

See robot_dart::gui::magnum::BaseGraphics

Type Name GraphicsConfiguration _configuration bool _enabled int _fps std::unique_ptr< BaseApplication > _magnum_app Corrade::Utility::Debug _magnum_silence_output = {nullptr}"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1WindowlessGraphics/#protected-attributes-inherited-from-robot_dartguibase","title":"Protected Attributes inherited from robot_dart::gui::Base","text":"

See robot_dart::gui::Base

Type Name RobotDARTSimu * _simu = = nullptr"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1WindowlessGraphics/#public-functions-documentation","title":"Public Functions Documentation","text":""},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1WindowlessGraphics/#function-windowlessgraphics","title":"function WindowlessGraphics","text":"
inline robot_dart::gui::magnum::WindowlessGraphics::WindowlessGraphics (\nconst GraphicsConfiguration & configuration=default_configuration()\n) 
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1WindowlessGraphics/#function-set_simu","title":"function set_simu","text":"
virtual void robot_dart::gui::magnum::WindowlessGraphics::set_simu (\nRobotDARTSimu * simu\n) override\n

Implements robot_dart::gui::magnum::BaseGraphics::set_simu

"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1WindowlessGraphics/#function-windowlessgraphics_1","title":"function ~WindowlessGraphics","text":"
inline robot_dart::gui::magnum::WindowlessGraphics::~WindowlessGraphics () 
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1WindowlessGraphics/#public-static-functions-documentation","title":"Public Static Functions Documentation","text":""},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1WindowlessGraphics/#function-default_configuration","title":"function default_configuration","text":"
static GraphicsConfiguration robot_dart::gui::magnum::WindowlessGraphics::default_configuration () 

The documentation for this class was generated from the following file robot_dart/gui/magnum/windowless_graphics.hpp

"},{"location":"api/namespacerobot__dart_1_1gui_1_1magnum_1_1gs/","title":"Namespace robot_dart::gui::magnum::gs","text":"

Namespace List > robot_dart > gui > magnum > gs

"},{"location":"api/namespacerobot__dart_1_1gui_1_1magnum_1_1gs/#classes","title":"Classes","text":"Type Name class Camera class CubeMap class CubeMapColor class Light class Material class PhongMultiLight class ShadowMap class ShadowMapColor"},{"location":"api/namespacerobot__dart_1_1gui_1_1magnum_1_1gs/#public-functions","title":"Public Functions","text":"Type Name Light create_directional_light (const Magnum::Vector3 & direction, const Material & material) Light create_point_light (const Magnum::Vector3 & position, const Material & material, Magnum::Float intensity, const Magnum::Vector3 & attenuationTerms) Light create_spot_light (const Magnum::Vector3 & position, const Material & material, const Magnum::Vector3 & spot_direction, Magnum::Float spot_exponent, Magnum::Float spot_cut_off, Magnum::Float intensity, const Magnum::Vector3 & attenuationTerms) DepthImage depth_array_from_image (Magnum::Image2D * image, Magnum::Float near_plane, Magnum::Float far_plane) GrayscaleImage depth_from_image (Magnum::Image2D * image, bool linearize, Magnum::Float near_plane, Magnum::Float far_plane) Image rgb_from_image (Magnum::Image2D * image)"},{"location":"api/namespacerobot__dart_1_1gui_1_1magnum_1_1gs/#public-static-functions","title":"Public Static Functions","text":"Type Name fs::path search_path (const fs::path & filename)"},{"location":"api/namespacerobot__dart_1_1gui_1_1magnum_1_1gs/#public-functions-documentation","title":"Public Functions Documentation","text":""},{"location":"api/namespacerobot__dart_1_1gui_1_1magnum_1_1gs/#function-create_directional_light","title":"function create_directional_light","text":"
inline Light robot_dart::gui::magnum::gs::create_directional_light (\nconst Magnum::Vector3 & direction,\nconst Material & material\n) 
"},{"location":"api/namespacerobot__dart_1_1gui_1_1magnum_1_1gs/#function-create_point_light","title":"function create_point_light","text":"
inline Light robot_dart::gui::magnum::gs::create_point_light (\nconst Magnum::Vector3 & position,\nconst Material & material,\nMagnum::Float intensity,\nconst Magnum::Vector3 & attenuationTerms\n) 
"},{"location":"api/namespacerobot__dart_1_1gui_1_1magnum_1_1gs/#function-create_spot_light","title":"function create_spot_light","text":"
inline Light robot_dart::gui::magnum::gs::create_spot_light (\nconst Magnum::Vector3 & position,\nconst Material & material,\nconst Magnum::Vector3 & spot_direction,\nMagnum::Float spot_exponent,\nMagnum::Float spot_cut_off,\nMagnum::Float intensity,\nconst Magnum::Vector3 & attenuationTerms\n) 
"},{"location":"api/namespacerobot__dart_1_1gui_1_1magnum_1_1gs/#function-depth_array_from_image","title":"function depth_array_from_image","text":"
DepthImage robot_dart::gui::magnum::gs::depth_array_from_image (\nMagnum::Image2D * image,\nMagnum::Float near_plane,\nMagnum::Float far_plane\n) 
"},{"location":"api/namespacerobot__dart_1_1gui_1_1magnum_1_1gs/#function-depth_from_image","title":"function depth_from_image","text":"
GrayscaleImage robot_dart::gui::magnum::gs::depth_from_image (\nMagnum::Image2D * image,\nbool linearize,\nMagnum::Float near_plane,\nMagnum::Float far_plane\n) 
"},{"location":"api/namespacerobot__dart_1_1gui_1_1magnum_1_1gs/#function-rgb_from_image","title":"function rgb_from_image","text":"
Image robot_dart::gui::magnum::gs::rgb_from_image (\nMagnum::Image2D * image\n) 
"},{"location":"api/namespacerobot__dart_1_1gui_1_1magnum_1_1gs/#public-static-functions-documentation","title":"Public Static Functions Documentation","text":""},{"location":"api/namespacerobot__dart_1_1gui_1_1magnum_1_1gs/#function-search_path","title":"function search_path","text":"
static fs::path robot_dart::gui::magnum::gs::search_path (\nconst fs::path & filename\n) 

The documentation for this class was generated from the following file robot_dart/gui/magnum/gs/camera.cpp

"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1Camera/","title":"Class robot_dart::gui::magnum::Camera","text":"

ClassList > robot_dart > gui > magnum > gs > Camera

Inherits the following classes: Object3D

"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1Camera/#public-functions","title":"Public Functions","text":"Type Name Camera (Object3D & object, Magnum::Int width, Magnum::Int height) Camera3D & camera () const Object3D & camera_object () const Corrade::Containers::Optional< Magnum::Image2D > & depth_image () void draw (Magnum::SceneGraph::DrawableGroup3D & drawables, Magnum::GL::AbstractFramebuffer & framebuffer, Magnum::PixelFormat format, RobotDARTSimu * simu, const DebugDrawData & debug_data, bool draw_debug=true) Magnum::Matrix4 extrinsic_matrix () const Magnum::Float far_plane () const Camera & forward (Magnum::Float speed) Magnum::Float fov () const Magnum::Int height () const Corrade::Containers::Optional< Magnum::Image2D > & image () Magnum::Matrix3 intrinsic_matrix () const Camera & look_at (const Magnum::Vector3 & camera, const Magnum::Vector3 & center, const Magnum::Vector3 & up=Magnum::Vector3::zAxis()) Camera & move (const Magnum::Vector2i & shift) Magnum::Float near_plane () const void record (bool recording, bool recording_depth=false) void record_video (const std::string & video_fname, int fps) bool recording () bool recording_depth () Object3D & root_object () Camera & set_camera_params (Magnum::Float near_plane, Magnum::Float far_plane, Magnum::Float fov, Magnum::Int width, Magnum::Int height) Camera & set_far_plane (Magnum::Float far_plane) Camera & set_fov (Magnum::Float fov) Camera & set_near_plane (Magnum::Float near_plane) Camera & set_speed (const Magnum::Vector2 & speed) Camera & set_viewport (const Magnum::Vector2i & size) Magnum::Vector2 speed () const Camera & strafe (Magnum::Float speed) void transform_lights (std::vector< gs::Light > & lights) const Magnum::Int width () const ~Camera ()"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1Camera/#public-functions-documentation","title":"Public Functions Documentation","text":""},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1Camera/#function-camera","title":"function Camera","text":"
explicit robot_dart::gui::magnum::gs::Camera::Camera (\nObject3D & object,\nMagnum::Int width,\nMagnum::Int height\n) 
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1Camera/#function-camera_1","title":"function camera","text":"
Camera3D & robot_dart::gui::magnum::gs::Camera::camera () const\n
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1Camera/#function-camera_object","title":"function camera_object","text":"
Object3D & robot_dart::gui::magnum::gs::Camera::camera_object () const\n
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1Camera/#function-depth_image","title":"function depth_image","text":"
inline Corrade::Containers::Optional< Magnum::Image2D > & robot_dart::gui::magnum::gs::Camera::depth_image () 
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1Camera/#function-draw","title":"function draw","text":"
void robot_dart::gui::magnum::gs::Camera::draw (\nMagnum::SceneGraph::DrawableGroup3D & drawables,\nMagnum::GL::AbstractFramebuffer & framebuffer,\nMagnum::PixelFormat format,\nRobotDARTSimu * simu,\nconst DebugDrawData & debug_data,\nbool draw_debug=true\n) 
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1Camera/#function-extrinsic_matrix","title":"function extrinsic_matrix","text":"
Magnum::Matrix4 robot_dart::gui::magnum::gs::Camera::extrinsic_matrix () const\n
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1Camera/#function-far_plane","title":"function far_plane","text":"
inline Magnum::Float robot_dart::gui::magnum::gs::Camera::far_plane () const\n
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1Camera/#function-forward","title":"function forward","text":"
Camera & robot_dart::gui::magnum::gs::Camera::forward (\nMagnum::Float speed\n) 
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1Camera/#function-fov","title":"function fov","text":"
inline Magnum::Float robot_dart::gui::magnum::gs::Camera::fov () const\n
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1Camera/#function-height","title":"function height","text":"
inline Magnum::Int robot_dart::gui::magnum::gs::Camera::height () const\n
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1Camera/#function-image","title":"function image","text":"
inline Corrade::Containers::Optional< Magnum::Image2D > & robot_dart::gui::magnum::gs::Camera::image () 
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1Camera/#function-intrinsic_matrix","title":"function intrinsic_matrix","text":"
Magnum::Matrix3 robot_dart::gui::magnum::gs::Camera::intrinsic_matrix () const\n
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1Camera/#function-look_at","title":"function look_at","text":"
Camera & robot_dart::gui::magnum::gs::Camera::look_at (\nconst Magnum::Vector3 & camera,\nconst Magnum::Vector3 & center,\nconst Magnum::Vector3 & up=Magnum::Vector3::zAxis()\n) 
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1Camera/#function-move","title":"function move","text":"
Camera & robot_dart::gui::magnum::gs::Camera::move (\nconst Magnum::Vector2i & shift\n) 
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1Camera/#function-near_plane","title":"function near_plane","text":"
inline Magnum::Float robot_dart::gui::magnum::gs::Camera::near_plane () const\n
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1Camera/#function-record","title":"function record","text":"
inline void robot_dart::gui::magnum::gs::Camera::record (\nbool recording,\nbool recording_depth=false\n) 
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1Camera/#function-record_video","title":"function record_video","text":"
void robot_dart::gui::magnum::gs::Camera::record_video (\nconst std::string & video_fname,\nint fps\n) 
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1Camera/#function-recording","title":"function recording","text":"
inline bool robot_dart::gui::magnum::gs::Camera::recording () 
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1Camera/#function-recording_depth","title":"function recording_depth","text":"
inline bool robot_dart::gui::magnum::gs::Camera::recording_depth () 
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1Camera/#function-root_object","title":"function root_object","text":"
Object3D & robot_dart::gui::magnum::gs::Camera::root_object () 
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1Camera/#function-set_camera_params","title":"function set_camera_params","text":"
Camera & robot_dart::gui::magnum::gs::Camera::set_camera_params (\nMagnum::Float near_plane,\nMagnum::Float far_plane,\nMagnum::Float fov,\nMagnum::Int width,\nMagnum::Int height\n) 
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1Camera/#function-set_far_plane","title":"function set_far_plane","text":"
Camera & robot_dart::gui::magnum::gs::Camera::set_far_plane (\nMagnum::Float far_plane\n) 
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1Camera/#function-set_fov","title":"function set_fov","text":"
Camera & robot_dart::gui::magnum::gs::Camera::set_fov (\nMagnum::Float fov\n) 
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1Camera/#function-set_near_plane","title":"function set_near_plane","text":"
Camera & robot_dart::gui::magnum::gs::Camera::set_near_plane (\nMagnum::Float near_plane\n) 
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1Camera/#function-set_speed","title":"function set_speed","text":"
Camera & robot_dart::gui::magnum::gs::Camera::set_speed (\nconst Magnum::Vector2 & speed\n) 
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1Camera/#function-set_viewport","title":"function set_viewport","text":"
Camera & robot_dart::gui::magnum::gs::Camera::set_viewport (\nconst Magnum::Vector2i & size\n) 
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1Camera/#function-speed","title":"function speed","text":"
inline Magnum::Vector2 robot_dart::gui::magnum::gs::Camera::speed () const\n
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1Camera/#function-strafe","title":"function strafe","text":"
Camera & robot_dart::gui::magnum::gs::Camera::strafe (\nMagnum::Float speed\n) 
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1Camera/#function-transform_lights","title":"function transform_lights","text":"
void robot_dart::gui::magnum::gs::Camera::transform_lights (\nstd::vector< gs::Light > & lights\n) const\n
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1Camera/#function-width","title":"function width","text":"
inline Magnum::Int robot_dart::gui::magnum::gs::Camera::width () const\n
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1Camera/#function-camera_2","title":"function ~Camera","text":"
robot_dart::gui::magnum::gs::Camera::~Camera () 

The documentation for this class was generated from the following file robot_dart/gui/magnum/gs/camera.hpp

"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1CubeMap/","title":"Class robot_dart::gui::magnum::CubeMap","text":"

ClassList > robot_dart > gui > magnum > gs > CubeMap

Inherits the following classes: Magnum::GL::AbstractShaderProgram

"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1CubeMap/#public-types","title":"Public Types","text":"Type Name enum Magnum::UnsignedByte Flag typedef Magnum::Containers::EnumSet< Flag > Flags typedef Magnum::Shaders::Generic3D::Position Position typedef Magnum::Shaders::Generic3D::TextureCoordinates TextureCoordinates"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1CubeMap/#public-functions","title":"Public Functions","text":"Type Name CubeMap (Flags flags={}) CubeMap (Magnum::NoCreateT) noexcept Flags flags () const CubeMap & set_far_plane (Magnum::Float far_plane) CubeMap & set_light_index (Magnum::Int index) CubeMap & set_light_position (const Magnum::Vector3 & position) CubeMap & set_material (Material & material) CubeMap & set_shadow_matrices (Magnum::Matrix4 matrices) CubeMap & set_transformation_matrix (const Magnum::Matrix4 & matrix)"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1CubeMap/#public-types-documentation","title":"Public Types Documentation","text":""},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1CubeMap/#enum-flag","title":"enum Flag","text":"
enum robot_dart::gui::magnum::gs::CubeMap::Flag {\nDiffuseTexture = 1 << 0\n};\n
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1CubeMap/#typedef-flags","title":"typedef Flags","text":"
using robot_dart::gui::magnum::gs::CubeMap::Flags =  Magnum::Containers::EnumSet<Flag>;\n
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1CubeMap/#typedef-position","title":"typedef Position","text":"
using robot_dart::gui::magnum::gs::CubeMap::Position =  Magnum::Shaders::Generic3D::Position;\n
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1CubeMap/#typedef-texturecoordinates","title":"typedef TextureCoordinates","text":"
using robot_dart::gui::magnum::gs::CubeMap::TextureCoordinates =  Magnum::Shaders::Generic3D::TextureCoordinates;\n
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1CubeMap/#public-functions-documentation","title":"Public Functions Documentation","text":""},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1CubeMap/#function-cubemap-12","title":"function CubeMap [\u00bd]","text":"
explicit robot_dart::gui::magnum::gs::CubeMap::CubeMap (\nFlags flags={}\n) 
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1CubeMap/#function-cubemap-22","title":"function CubeMap [2/2]","text":"
explicit robot_dart::gui::magnum::gs::CubeMap::CubeMap (\nMagnum::NoCreateT\n) noexcept\n
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1CubeMap/#function-flags","title":"function flags","text":"
Flags robot_dart::gui::magnum::gs::CubeMap::flags () const\n
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1CubeMap/#function-set_far_plane","title":"function set_far_plane","text":"
CubeMap & robot_dart::gui::magnum::gs::CubeMap::set_far_plane (\nMagnum::Float far_plane\n) 
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1CubeMap/#function-set_light_index","title":"function set_light_index","text":"
CubeMap & robot_dart::gui::magnum::gs::CubeMap::set_light_index (\nMagnum::Int index\n) 
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1CubeMap/#function-set_light_position","title":"function set_light_position","text":"
CubeMap & robot_dart::gui::magnum::gs::CubeMap::set_light_position (\nconst Magnum::Vector3 & position\n) 
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1CubeMap/#function-set_material","title":"function set_material","text":"
CubeMap & robot_dart::gui::magnum::gs::CubeMap::set_material (\nMaterial & material\n) 
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1CubeMap/#function-set_shadow_matrices","title":"function set_shadow_matrices","text":"
CubeMap & robot_dart::gui::magnum::gs::CubeMap::set_shadow_matrices (\nMagnum::Matrix4 matrices\n) 
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1CubeMap/#function-set_transformation_matrix","title":"function set_transformation_matrix","text":"
CubeMap & robot_dart::gui::magnum::gs::CubeMap::set_transformation_matrix (\nconst Magnum::Matrix4 & matrix\n) 

The documentation for this class was generated from the following file robot_dart/gui/magnum/gs/cube_map.hpp

"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1CubeMapColor/","title":"Class robot_dart::gui::magnum::CubeMapColor","text":"

ClassList > robot_dart > gui > magnum > gs > CubeMapColor

Inherits the following classes: Magnum::GL::AbstractShaderProgram

"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1CubeMapColor/#public-types","title":"Public Types","text":"Type Name enum Magnum::UnsignedByte Flag typedef Magnum::Containers::EnumSet< Flag > Flags typedef Magnum::Shaders::Generic3D::Position Position typedef Magnum::Shaders::Generic3D::TextureCoordinates TextureCoordinates"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1CubeMapColor/#public-functions","title":"Public Functions","text":"Type Name CubeMapColor (Flags flags={}) CubeMapColor (Magnum::NoCreateT) noexcept CubeMapColor & bind_cube_map_texture (Magnum::GL::CubeMapTextureArray & texture) Flags flags () const CubeMapColor & set_far_plane (Magnum::Float far_plane) CubeMapColor & set_light_index (Magnum::Int index) CubeMapColor & set_light_position (const Magnum::Vector3 & position) CubeMapColor & set_material (Material & material) CubeMapColor & set_shadow_matrices (Magnum::Matrix4 matrices) CubeMapColor & set_transformation_matrix (const Magnum::Matrix4 & matrix)"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1CubeMapColor/#public-types-documentation","title":"Public Types Documentation","text":""},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1CubeMapColor/#enum-flag","title":"enum Flag","text":"
enum robot_dart::gui::magnum::gs::CubeMapColor::Flag {\nDiffuseTexture = 1 << 0\n};\n
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1CubeMapColor/#typedef-flags","title":"typedef Flags","text":"
using robot_dart::gui::magnum::gs::CubeMapColor::Flags =  Magnum::Containers::EnumSet<Flag>;\n
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1CubeMapColor/#typedef-position","title":"typedef Position","text":"
using robot_dart::gui::magnum::gs::CubeMapColor::Position =  Magnum::Shaders::Generic3D::Position;\n
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1CubeMapColor/#typedef-texturecoordinates","title":"typedef TextureCoordinates","text":"
using robot_dart::gui::magnum::gs::CubeMapColor::TextureCoordinates =  Magnum::Shaders::Generic3D::TextureCoordinates;\n
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1CubeMapColor/#public-functions-documentation","title":"Public Functions Documentation","text":""},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1CubeMapColor/#function-cubemapcolor-12","title":"function CubeMapColor [\u00bd]","text":"
explicit robot_dart::gui::magnum::gs::CubeMapColor::CubeMapColor (\nFlags flags={}\n) 
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1CubeMapColor/#function-cubemapcolor-22","title":"function CubeMapColor [2/2]","text":"
explicit robot_dart::gui::magnum::gs::CubeMapColor::CubeMapColor (\nMagnum::NoCreateT\n) noexcept\n
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1CubeMapColor/#function-bind_cube_map_texture","title":"function bind_cube_map_texture","text":"
CubeMapColor & robot_dart::gui::magnum::gs::CubeMapColor::bind_cube_map_texture (\nMagnum::GL::CubeMapTextureArray & texture\n) 
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1CubeMapColor/#function-flags","title":"function flags","text":"
Flags robot_dart::gui::magnum::gs::CubeMapColor::flags () const\n
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1CubeMapColor/#function-set_far_plane","title":"function set_far_plane","text":"
CubeMapColor & robot_dart::gui::magnum::gs::CubeMapColor::set_far_plane (\nMagnum::Float far_plane\n) 
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1CubeMapColor/#function-set_light_index","title":"function set_light_index","text":"
CubeMapColor & robot_dart::gui::magnum::gs::CubeMapColor::set_light_index (\nMagnum::Int index\n) 
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1CubeMapColor/#function-set_light_position","title":"function set_light_position","text":"
CubeMapColor & robot_dart::gui::magnum::gs::CubeMapColor::set_light_position (\nconst Magnum::Vector3 & position\n) 
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1CubeMapColor/#function-set_material","title":"function set_material","text":"
CubeMapColor & robot_dart::gui::magnum::gs::CubeMapColor::set_material (\nMaterial & material\n) 
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1CubeMapColor/#function-set_shadow_matrices","title":"function set_shadow_matrices","text":"
CubeMapColor & robot_dart::gui::magnum::gs::CubeMapColor::set_shadow_matrices (\nMagnum::Matrix4 matrices\n) 
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1CubeMapColor/#function-set_transformation_matrix","title":"function set_transformation_matrix","text":"
CubeMapColor & robot_dart::gui::magnum::gs::CubeMapColor::set_transformation_matrix (\nconst Magnum::Matrix4 & matrix\n) 

The documentation for this class was generated from the following file robot_dart/gui/magnum/gs/cube_map_color.hpp

"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1Light/","title":"Class robot_dart::gui::magnum::Light","text":"

ClassList > robot_dart > gui > magnum > gs > Light

"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1Light/#public-functions","title":"Public Functions","text":"Type Name Light () Light (const Magnum::Vector4 & position, const Material & material, const Magnum::Vector3 & spot_direction, Magnum::Float spot_exponent, Magnum::Float spot_cut_off, const Magnum::Vector4 & attenuation, bool cast_shadows=true) Magnum::Vector4 & attenuation () Magnum::Vector4 attenuation () const bool casts_shadows () const Material & material () Material material () const Magnum::Vector4 position () const Light & set_attenuation (const Magnum::Vector4 & attenuation) Light & set_casts_shadows (bool cast_shadows) Light & set_material (const Material & material) Light & set_position (const Magnum::Vector4 & position) Light & set_shadow_matrix (const Magnum::Matrix4 & shadowTransform) Light & set_spot_cut_off (Magnum::Float spot_cut_off) Light & set_spot_direction (const Magnum::Vector3 & spot_direction) Light & set_spot_exponent (Magnum::Float spot_exponent) Light & set_transformed_position (const Magnum::Vector4 & transformed_position) Light & set_transformed_spot_direction (const Magnum::Vector3 & transformed_spot_direction) Magnum::Matrix4 shadow_matrix () const Magnum::Float & spot_cut_off () Magnum::Float spot_cut_off () const Magnum::Vector3 spot_direction () const Magnum::Float & spot_exponent () Magnum::Float spot_exponent () const Magnum::Vector4 & transformed_position () Magnum::Vector4 transformed_position () const Magnum::Vector3 & transformed_spot_direction () Magnum::Vector3 transformed_spot_direction () const"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1Light/#protected-attributes","title":"Protected Attributes","text":"Type Name Magnum::Vector4 _attenuation bool _cast_shadows = = true Material _material Magnum::Vector4 _position Magnum::Matrix4 _shadow_transform = {} Magnum::Float _spot_cut_off Magnum::Vector3 _spot_direction Magnum::Float _spot_exponent Magnum::Vector4 _transformed_position Magnum::Vector3 _transformed_spot_direction"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1Light/#public-functions-documentation","title":"Public Functions Documentation","text":""},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1Light/#function-light-12","title":"function Light [\u00bd]","text":"
robot_dart::gui::magnum::gs::Light::Light () 
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1Light/#function-light-22","title":"function Light [2/2]","text":"
robot_dart::gui::magnum::gs::Light::Light (\nconst Magnum::Vector4 & position,\nconst Material & material,\nconst Magnum::Vector3 & spot_direction,\nMagnum::Float spot_exponent,\nMagnum::Float spot_cut_off,\nconst Magnum::Vector4 & attenuation,\nbool cast_shadows=true\n) 
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1Light/#function-attenuation-12","title":"function attenuation [\u00bd]","text":"
Magnum::Vector4 & robot_dart::gui::magnum::gs::Light::attenuation () 
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1Light/#function-attenuation-22","title":"function attenuation [2/2]","text":"
Magnum::Vector4 robot_dart::gui::magnum::gs::Light::attenuation () const\n
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1Light/#function-casts_shadows","title":"function casts_shadows","text":"
bool robot_dart::gui::magnum::gs::Light::casts_shadows () const\n
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1Light/#function-material-12","title":"function material [\u00bd]","text":"
Material & robot_dart::gui::magnum::gs::Light::material () 
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1Light/#function-material-22","title":"function material [2/2]","text":"
Material robot_dart::gui::magnum::gs::Light::material () const\n
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1Light/#function-position","title":"function position","text":"
Magnum::Vector4 robot_dart::gui::magnum::gs::Light::position () const\n
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1Light/#function-set_attenuation","title":"function set_attenuation","text":"
Light & robot_dart::gui::magnum::gs::Light::set_attenuation (\nconst Magnum::Vector4 & attenuation\n) 
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1Light/#function-set_casts_shadows","title":"function set_casts_shadows","text":"
Light & robot_dart::gui::magnum::gs::Light::set_casts_shadows (\nbool cast_shadows\n) 
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1Light/#function-set_material","title":"function set_material","text":"
Light & robot_dart::gui::magnum::gs::Light::set_material (\nconst Material & material\n) 
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1Light/#function-set_position","title":"function set_position","text":"
Light & robot_dart::gui::magnum::gs::Light::set_position (\nconst Magnum::Vector4 & position\n) 
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1Light/#function-set_shadow_matrix","title":"function set_shadow_matrix","text":"
Light & robot_dart::gui::magnum::gs::Light::set_shadow_matrix (\nconst Magnum::Matrix4 & shadowTransform\n) 
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1Light/#function-set_spot_cut_off","title":"function set_spot_cut_off","text":"
Light & robot_dart::gui::magnum::gs::Light::set_spot_cut_off (\nMagnum::Float spot_cut_off\n) 
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1Light/#function-set_spot_direction","title":"function set_spot_direction","text":"
Light & robot_dart::gui::magnum::gs::Light::set_spot_direction (\nconst Magnum::Vector3 & spot_direction\n) 
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1Light/#function-set_spot_exponent","title":"function set_spot_exponent","text":"
Light & robot_dart::gui::magnum::gs::Light::set_spot_exponent (\nMagnum::Float spot_exponent\n) 
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1Light/#function-set_transformed_position","title":"function set_transformed_position","text":"
Light & robot_dart::gui::magnum::gs::Light::set_transformed_position (\nconst Magnum::Vector4 & transformed_position\n) 
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1Light/#function-set_transformed_spot_direction","title":"function set_transformed_spot_direction","text":"
Light & robot_dart::gui::magnum::gs::Light::set_transformed_spot_direction (\nconst Magnum::Vector3 & transformed_spot_direction\n) 
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1Light/#function-shadow_matrix","title":"function shadow_matrix","text":"
Magnum::Matrix4 robot_dart::gui::magnum::gs::Light::shadow_matrix () const\n
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1Light/#function-spot_cut_off-12","title":"function spot_cut_off [\u00bd]","text":"
Magnum::Float & robot_dart::gui::magnum::gs::Light::spot_cut_off () 
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1Light/#function-spot_cut_off-22","title":"function spot_cut_off [2/2]","text":"
Magnum::Float robot_dart::gui::magnum::gs::Light::spot_cut_off () const\n
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1Light/#function-spot_direction","title":"function spot_direction","text":"
Magnum::Vector3 robot_dart::gui::magnum::gs::Light::spot_direction () const\n
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1Light/#function-spot_exponent-12","title":"function spot_exponent [\u00bd]","text":"
Magnum::Float & robot_dart::gui::magnum::gs::Light::spot_exponent () 
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1Light/#function-spot_exponent-22","title":"function spot_exponent [2/2]","text":"
Magnum::Float robot_dart::gui::magnum::gs::Light::spot_exponent () const\n
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1Light/#function-transformed_position-12","title":"function transformed_position [\u00bd]","text":"
Magnum::Vector4 & robot_dart::gui::magnum::gs::Light::transformed_position () 
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1Light/#function-transformed_position-22","title":"function transformed_position [2/2]","text":"
Magnum::Vector4 robot_dart::gui::magnum::gs::Light::transformed_position () const\n
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1Light/#function-transformed_spot_direction-12","title":"function transformed_spot_direction [\u00bd]","text":"
Magnum::Vector3 & robot_dart::gui::magnum::gs::Light::transformed_spot_direction () 
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1Light/#function-transformed_spot_direction-22","title":"function transformed_spot_direction [2/2]","text":"
Magnum::Vector3 robot_dart::gui::magnum::gs::Light::transformed_spot_direction () const\n
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1Light/#protected-attributes-documentation","title":"Protected Attributes Documentation","text":""},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1Light/#variable-_attenuation","title":"variable _attenuation","text":"
Magnum::Vector4 robot_dart::gui::magnum::gs::Light::_attenuation;\n
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1Light/#variable-_cast_shadows","title":"variable _cast_shadows","text":"
bool robot_dart::gui::magnum::gs::Light::_cast_shadows;\n
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1Light/#variable-_material","title":"variable _material","text":"
Material robot_dart::gui::magnum::gs::Light::_material;\n
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1Light/#variable-_position","title":"variable _position","text":"
Magnum::Vector4 robot_dart::gui::magnum::gs::Light::_position;\n
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1Light/#variable-_shadow_transform","title":"variable _shadow_transform","text":"
Magnum::Matrix4 robot_dart::gui::magnum::gs::Light::_shadow_transform;\n
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1Light/#variable-_spot_cut_off","title":"variable _spot_cut_off","text":"
Magnum::Float robot_dart::gui::magnum::gs::Light::_spot_cut_off;\n
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1Light/#variable-_spot_direction","title":"variable _spot_direction","text":"
Magnum::Vector3 robot_dart::gui::magnum::gs::Light::_spot_direction;\n
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1Light/#variable-_spot_exponent","title":"variable _spot_exponent","text":"
Magnum::Float robot_dart::gui::magnum::gs::Light::_spot_exponent;\n
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1Light/#variable-_transformed_position","title":"variable _transformed_position","text":"
Magnum::Vector4 robot_dart::gui::magnum::gs::Light::_transformed_position;\n
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1Light/#variable-_transformed_spot_direction","title":"variable _transformed_spot_direction","text":"
Magnum::Vector3 robot_dart::gui::magnum::gs::Light::_transformed_spot_direction;\n

The documentation for this class was generated from the following file robot_dart/gui/magnum/gs/light.hpp

"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1Material/","title":"Class robot_dart::gui::magnum::Material","text":"

ClassList > robot_dart > gui > magnum > gs > Material

"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1Material/#public-functions","title":"Public Functions","text":"Type Name Material () Material (const Magnum::Color4 & ambient, const Magnum::Color4 & diffuse, const Magnum::Color4 & specular, Magnum::Float shininess) Material (Magnum::GL::Texture2D * ambient_texture, Magnum::GL::Texture2D * diffuse_texture, Magnum::GL::Texture2D * specular_texture, Magnum::Float shininess) Magnum::Color4 & ambient_color () Magnum::Color4 ambient_color () const Magnum::GL::Texture2D * ambient_texture () Magnum::Color4 & diffuse_color () Magnum::Color4 diffuse_color () const Magnum::GL::Texture2D * diffuse_texture () bool has_ambient_texture () const bool has_diffuse_texture () const bool has_specular_texture () const Material & set_ambient_color (const Magnum::Color4 & ambient) Material & set_ambient_texture (Magnum::GL::Texture2D * ambient_texture) Material & set_diffuse_color (const Magnum::Color4 & diffuse) Material & set_diffuse_texture (Magnum::GL::Texture2D * diffuse_texture) Material & set_shininess (Magnum::Float shininess) Material & set_specular_color (const Magnum::Color4 & specular) Material & set_specular_texture (Magnum::GL::Texture2D * specular_texture) Magnum::Float & shininess () Magnum::Float shininess () const Magnum::Color4 & specular_color () Magnum::Color4 specular_color () const Magnum::GL::Texture2D * specular_texture ()"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1Material/#protected-attributes","title":"Protected Attributes","text":"Type Name Magnum::Color4 _ambient Magnum::GL::Texture2D * _ambient_texture = = NULL Magnum::Color4 _diffuse Magnum::GL::Texture2D * _diffuse_texture = = NULL Magnum::Float _shininess Magnum::Color4 _specular Magnum::GL::Texture2D * _specular_texture = = NULL"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1Material/#public-functions-documentation","title":"Public Functions Documentation","text":""},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1Material/#function-material-13","title":"function Material [\u2153]","text":"
robot_dart::gui::magnum::gs::Material::Material () 
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1Material/#function-material-23","title":"function Material [\u2154]","text":"
robot_dart::gui::magnum::gs::Material::Material (\nconst Magnum::Color4 & ambient,\nconst Magnum::Color4 & diffuse,\nconst Magnum::Color4 & specular,\nMagnum::Float shininess\n) 
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1Material/#function-material-33","title":"function Material [3/3]","text":"
robot_dart::gui::magnum::gs::Material::Material (\nMagnum::GL::Texture2D * ambient_texture,\nMagnum::GL::Texture2D * diffuse_texture,\nMagnum::GL::Texture2D * specular_texture,\nMagnum::Float shininess\n) 
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1Material/#function-ambient_color-12","title":"function ambient_color [\u00bd]","text":"
Magnum::Color4 & robot_dart::gui::magnum::gs::Material::ambient_color () 
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1Material/#function-ambient_color-22","title":"function ambient_color [2/2]","text":"
Magnum::Color4 robot_dart::gui::magnum::gs::Material::ambient_color () const\n
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1Material/#function-ambient_texture","title":"function ambient_texture","text":"
Magnum::GL::Texture2D * robot_dart::gui::magnum::gs::Material::ambient_texture () 
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1Material/#function-diffuse_color-12","title":"function diffuse_color [\u00bd]","text":"
Magnum::Color4 & robot_dart::gui::magnum::gs::Material::diffuse_color () 
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1Material/#function-diffuse_color-22","title":"function diffuse_color [2/2]","text":"
Magnum::Color4 robot_dart::gui::magnum::gs::Material::diffuse_color () const\n
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1Material/#function-diffuse_texture","title":"function diffuse_texture","text":"
Magnum::GL::Texture2D * robot_dart::gui::magnum::gs::Material::diffuse_texture () 
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1Material/#function-has_ambient_texture","title":"function has_ambient_texture","text":"
bool robot_dart::gui::magnum::gs::Material::has_ambient_texture () const\n
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1Material/#function-has_diffuse_texture","title":"function has_diffuse_texture","text":"
bool robot_dart::gui::magnum::gs::Material::has_diffuse_texture () const\n
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1Material/#function-has_specular_texture","title":"function has_specular_texture","text":"
bool robot_dart::gui::magnum::gs::Material::has_specular_texture () const\n
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1Material/#function-set_ambient_color","title":"function set_ambient_color","text":"
Material & robot_dart::gui::magnum::gs::Material::set_ambient_color (\nconst Magnum::Color4 & ambient\n) 
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1Material/#function-set_ambient_texture","title":"function set_ambient_texture","text":"
Material & robot_dart::gui::magnum::gs::Material::set_ambient_texture (\nMagnum::GL::Texture2D * ambient_texture\n) 
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1Material/#function-set_diffuse_color","title":"function set_diffuse_color","text":"
Material & robot_dart::gui::magnum::gs::Material::set_diffuse_color (\nconst Magnum::Color4 & diffuse\n) 
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1Material/#function-set_diffuse_texture","title":"function set_diffuse_texture","text":"
Material & robot_dart::gui::magnum::gs::Material::set_diffuse_texture (\nMagnum::GL::Texture2D * diffuse_texture\n) 
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1Material/#function-set_shininess","title":"function set_shininess","text":"
Material & robot_dart::gui::magnum::gs::Material::set_shininess (\nMagnum::Float shininess\n) 
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1Material/#function-set_specular_color","title":"function set_specular_color","text":"
Material & robot_dart::gui::magnum::gs::Material::set_specular_color (\nconst Magnum::Color4 & specular\n) 
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1Material/#function-set_specular_texture","title":"function set_specular_texture","text":"
Material & robot_dart::gui::magnum::gs::Material::set_specular_texture (\nMagnum::GL::Texture2D * specular_texture\n) 
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1Material/#function-shininess-12","title":"function shininess [\u00bd]","text":"
Magnum::Float & robot_dart::gui::magnum::gs::Material::shininess () 
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1Material/#function-shininess-22","title":"function shininess [2/2]","text":"
Magnum::Float robot_dart::gui::magnum::gs::Material::shininess () const\n
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1Material/#function-specular_color-12","title":"function specular_color [\u00bd]","text":"
Magnum::Color4 & robot_dart::gui::magnum::gs::Material::specular_color () 
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1Material/#function-specular_color-22","title":"function specular_color [2/2]","text":"
Magnum::Color4 robot_dart::gui::magnum::gs::Material::specular_color () const\n
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1Material/#function-specular_texture","title":"function specular_texture","text":"
Magnum::GL::Texture2D * robot_dart::gui::magnum::gs::Material::specular_texture () 
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1Material/#protected-attributes-documentation","title":"Protected Attributes Documentation","text":""},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1Material/#variable-_ambient","title":"variable _ambient","text":"
Magnum::Color4 robot_dart::gui::magnum::gs::Material::_ambient;\n
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1Material/#variable-_ambient_texture","title":"variable _ambient_texture","text":"
Magnum::GL::Texture2D* robot_dart::gui::magnum::gs::Material::_ambient_texture;\n
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1Material/#variable-_diffuse","title":"variable _diffuse","text":"
Magnum::Color4 robot_dart::gui::magnum::gs::Material::_diffuse;\n
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1Material/#variable-_diffuse_texture","title":"variable _diffuse_texture","text":"
Magnum::GL::Texture2D* robot_dart::gui::magnum::gs::Material::_diffuse_texture;\n
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1Material/#variable-_shininess","title":"variable _shininess","text":"
Magnum::Float robot_dart::gui::magnum::gs::Material::_shininess;\n
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1Material/#variable-_specular","title":"variable _specular","text":"
Magnum::Color4 robot_dart::gui::magnum::gs::Material::_specular;\n
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1Material/#variable-_specular_texture","title":"variable _specular_texture","text":"
Magnum::GL::Texture2D* robot_dart::gui::magnum::gs::Material::_specular_texture;\n

The documentation for this class was generated from the following file robot_dart/gui/magnum/gs/material.hpp

"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1PhongMultiLight/","title":"Class robot_dart::gui::magnum::PhongMultiLight","text":"

ClassList > robot_dart > gui > magnum > gs > PhongMultiLight

Inherits the following classes: Magnum::GL::AbstractShaderProgram

"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1PhongMultiLight/#public-types","title":"Public Types","text":"Type Name enum Magnum::UnsignedByte Flag typedef Magnum::Containers::EnumSet< Flag > Flags typedef Magnum::Shaders::Generic3D::Normal Normal typedef Magnum::Shaders::Generic3D::Position Position typedef Magnum::Shaders::Generic3D::TextureCoordinates TextureCoordinates"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1PhongMultiLight/#public-functions","title":"Public Functions","text":"Type Name PhongMultiLight (Flags flags={}, Magnum::Int max_lights=10) PhongMultiLight (Magnum::NoCreateT) noexcept PhongMultiLight & bind_cube_map_color_texture (Magnum::GL::CubeMapTextureArray & texture) PhongMultiLight & bind_cube_map_texture (Magnum::GL::CubeMapTextureArray & texture) PhongMultiLight & bind_shadow_color_texture (Magnum::GL::Texture2DArray & texture) PhongMultiLight & bind_shadow_texture (Magnum::GL::Texture2DArray & texture) Flags flags () const Magnum::Int max_lights () const PhongMultiLight & set_camera_matrix (const Magnum::Matrix4 & matrix) PhongMultiLight & set_far_plane (Magnum::Float far_plane) PhongMultiLight & set_is_shadowed (bool shadows) PhongMultiLight & set_light (Magnum::Int i, const Light & light) PhongMultiLight & set_material (Material & material) PhongMultiLight & set_normal_matrix (const Magnum::Matrix3x3 & matrix) PhongMultiLight & set_projection_matrix (const Magnum::Matrix4 & matrix) PhongMultiLight & set_specular_strength (Magnum::Float specular_strength) PhongMultiLight & set_transformation_matrix (const Magnum::Matrix4 & matrix) PhongMultiLight & set_transparent_shadows (bool shadows)"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1PhongMultiLight/#public-types-documentation","title":"Public Types Documentation","text":""},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1PhongMultiLight/#enum-flag","title":"enum Flag","text":"
enum robot_dart::gui::magnum::gs::PhongMultiLight::Flag {\nAmbientTexture = 1 << 0,\nDiffuseTexture = 1 << 1,\nSpecularTexture = 1 << 2\n};\n
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1PhongMultiLight/#typedef-flags","title":"typedef Flags","text":"
using robot_dart::gui::magnum::gs::PhongMultiLight::Flags =  Magnum::Containers::EnumSet<Flag>;\n
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1PhongMultiLight/#typedef-normal","title":"typedef Normal","text":"
using robot_dart::gui::magnum::gs::PhongMultiLight::Normal =  Magnum::Shaders::Generic3D::Normal;\n
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1PhongMultiLight/#typedef-position","title":"typedef Position","text":"
using robot_dart::gui::magnum::gs::PhongMultiLight::Position =  Magnum::Shaders::Generic3D::Position;\n
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1PhongMultiLight/#typedef-texturecoordinates","title":"typedef TextureCoordinates","text":"
using robot_dart::gui::magnum::gs::PhongMultiLight::TextureCoordinates =  Magnum::Shaders::Generic3D::TextureCoordinates;\n
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1PhongMultiLight/#public-functions-documentation","title":"Public Functions Documentation","text":""},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1PhongMultiLight/#function-phongmultilight-12","title":"function PhongMultiLight [\u00bd]","text":"
explicit robot_dart::gui::magnum::gs::PhongMultiLight::PhongMultiLight (\nFlags flags={},\nMagnum::Int max_lights=10\n) 
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1PhongMultiLight/#function-phongmultilight-22","title":"function PhongMultiLight [2/2]","text":"
explicit robot_dart::gui::magnum::gs::PhongMultiLight::PhongMultiLight (\nMagnum::NoCreateT\n) noexcept\n
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1PhongMultiLight/#function-bind_cube_map_color_texture","title":"function bind_cube_map_color_texture","text":"
PhongMultiLight & robot_dart::gui::magnum::gs::PhongMultiLight::bind_cube_map_color_texture (\nMagnum::GL::CubeMapTextureArray & texture\n) 
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1PhongMultiLight/#function-bind_cube_map_texture","title":"function bind_cube_map_texture","text":"
PhongMultiLight & robot_dart::gui::magnum::gs::PhongMultiLight::bind_cube_map_texture (\nMagnum::GL::CubeMapTextureArray & texture\n) 
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1PhongMultiLight/#function-bind_shadow_color_texture","title":"function bind_shadow_color_texture","text":"
PhongMultiLight & robot_dart::gui::magnum::gs::PhongMultiLight::bind_shadow_color_texture (\nMagnum::GL::Texture2DArray & texture\n) 
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1PhongMultiLight/#function-bind_shadow_texture","title":"function bind_shadow_texture","text":"
PhongMultiLight & robot_dart::gui::magnum::gs::PhongMultiLight::bind_shadow_texture (\nMagnum::GL::Texture2DArray & texture\n) 
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1PhongMultiLight/#function-flags","title":"function flags","text":"
Flags robot_dart::gui::magnum::gs::PhongMultiLight::flags () const\n
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1PhongMultiLight/#function-max_lights","title":"function max_lights","text":"
Magnum::Int robot_dart::gui::magnum::gs::PhongMultiLight::max_lights () const\n
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1PhongMultiLight/#function-set_camera_matrix","title":"function set_camera_matrix","text":"
PhongMultiLight & robot_dart::gui::magnum::gs::PhongMultiLight::set_camera_matrix (\nconst Magnum::Matrix4 & matrix\n) 
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1PhongMultiLight/#function-set_far_plane","title":"function set_far_plane","text":"
PhongMultiLight & robot_dart::gui::magnum::gs::PhongMultiLight::set_far_plane (\nMagnum::Float far_plane\n) 
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1PhongMultiLight/#function-set_is_shadowed","title":"function set_is_shadowed","text":"
PhongMultiLight & robot_dart::gui::magnum::gs::PhongMultiLight::set_is_shadowed (\nbool shadows\n) 
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1PhongMultiLight/#function-set_light","title":"function set_light","text":"
PhongMultiLight & robot_dart::gui::magnum::gs::PhongMultiLight::set_light (\nMagnum::Int i,\nconst Light & light\n) 
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1PhongMultiLight/#function-set_material","title":"function set_material","text":"
PhongMultiLight & robot_dart::gui::magnum::gs::PhongMultiLight::set_material (\nMaterial & material\n) 
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1PhongMultiLight/#function-set_normal_matrix","title":"function set_normal_matrix","text":"
PhongMultiLight & robot_dart::gui::magnum::gs::PhongMultiLight::set_normal_matrix (\nconst Magnum::Matrix3x3 & matrix\n) 
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1PhongMultiLight/#function-set_projection_matrix","title":"function set_projection_matrix","text":"
PhongMultiLight & robot_dart::gui::magnum::gs::PhongMultiLight::set_projection_matrix (\nconst Magnum::Matrix4 & matrix\n) 
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1PhongMultiLight/#function-set_specular_strength","title":"function set_specular_strength","text":"
PhongMultiLight & robot_dart::gui::magnum::gs::PhongMultiLight::set_specular_strength (\nMagnum::Float specular_strength\n) 
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1PhongMultiLight/#function-set_transformation_matrix","title":"function set_transformation_matrix","text":"
PhongMultiLight & robot_dart::gui::magnum::gs::PhongMultiLight::set_transformation_matrix (\nconst Magnum::Matrix4 & matrix\n) 
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1PhongMultiLight/#function-set_transparent_shadows","title":"function set_transparent_shadows","text":"
PhongMultiLight & robot_dart::gui::magnum::gs::PhongMultiLight::set_transparent_shadows (\nbool shadows\n) 

The documentation for this class was generated from the following file robot_dart/gui/magnum/gs/phong_multi_light.hpp

"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1ShadowMap/","title":"Class robot_dart::gui::magnum::ShadowMap","text":"

ClassList > robot_dart > gui > magnum > gs > ShadowMap

Inherits the following classes: Magnum::GL::AbstractShaderProgram

"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1ShadowMap/#public-types","title":"Public Types","text":"Type Name enum Magnum::UnsignedByte Flag typedef Magnum::Containers::EnumSet< Flag > Flags typedef Magnum::Shaders::Generic3D::Position Position typedef Magnum::Shaders::Generic3D::TextureCoordinates TextureCoordinates"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1ShadowMap/#public-functions","title":"Public Functions","text":"Type Name ShadowMap (Flags flags={}) ShadowMap (Magnum::NoCreateT) noexcept Flags flags () const ShadowMap & set_material (Material & material) ShadowMap & set_projection_matrix (const Magnum::Matrix4 & matrix) ShadowMap & set_transformation_matrix (const Magnum::Matrix4 & matrix)"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1ShadowMap/#public-types-documentation","title":"Public Types Documentation","text":""},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1ShadowMap/#enum-flag","title":"enum Flag","text":"
enum robot_dart::gui::magnum::gs::ShadowMap::Flag {\nDiffuseTexture = 1 << 0\n};\n
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1ShadowMap/#typedef-flags","title":"typedef Flags","text":"
using robot_dart::gui::magnum::gs::ShadowMap::Flags =  Magnum::Containers::EnumSet<Flag>;\n
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1ShadowMap/#typedef-position","title":"typedef Position","text":"
using robot_dart::gui::magnum::gs::ShadowMap::Position =  Magnum::Shaders::Generic3D::Position;\n
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1ShadowMap/#typedef-texturecoordinates","title":"typedef TextureCoordinates","text":"
using robot_dart::gui::magnum::gs::ShadowMap::TextureCoordinates =  Magnum::Shaders::Generic3D::TextureCoordinates;\n
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1ShadowMap/#public-functions-documentation","title":"Public Functions Documentation","text":""},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1ShadowMap/#function-shadowmap-12","title":"function ShadowMap [\u00bd]","text":"
explicit robot_dart::gui::magnum::gs::ShadowMap::ShadowMap (\nFlags flags={}\n) 
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1ShadowMap/#function-shadowmap-22","title":"function ShadowMap [2/2]","text":"
explicit robot_dart::gui::magnum::gs::ShadowMap::ShadowMap (\nMagnum::NoCreateT\n) noexcept\n
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1ShadowMap/#function-flags","title":"function flags","text":"
Flags robot_dart::gui::magnum::gs::ShadowMap::flags () const\n
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1ShadowMap/#function-set_material","title":"function set_material","text":"
ShadowMap & robot_dart::gui::magnum::gs::ShadowMap::set_material (\nMaterial & material\n) 
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1ShadowMap/#function-set_projection_matrix","title":"function set_projection_matrix","text":"
ShadowMap & robot_dart::gui::magnum::gs::ShadowMap::set_projection_matrix (\nconst Magnum::Matrix4 & matrix\n) 
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1ShadowMap/#function-set_transformation_matrix","title":"function set_transformation_matrix","text":"
ShadowMap & robot_dart::gui::magnum::gs::ShadowMap::set_transformation_matrix (\nconst Magnum::Matrix4 & matrix\n) 

The documentation for this class was generated from the following file robot_dart/gui/magnum/gs/shadow_map.hpp

"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1ShadowMapColor/","title":"Class robot_dart::gui::magnum::ShadowMapColor","text":"

ClassList > robot_dart > gui > magnum > gs > ShadowMapColor

Inherits the following classes: Magnum::GL::AbstractShaderProgram

"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1ShadowMapColor/#public-types","title":"Public Types","text":"Type Name enum Magnum::UnsignedByte Flag typedef Magnum::Containers::EnumSet< Flag > Flags typedef Magnum::Shaders::Generic3D::Position Position typedef Magnum::Shaders::Generic3D::TextureCoordinates TextureCoordinates"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1ShadowMapColor/#public-functions","title":"Public Functions","text":"Type Name ShadowMapColor (Flags flags={}) ShadowMapColor (Magnum::NoCreateT) noexcept Flags flags () const ShadowMapColor & set_material (Material & material) ShadowMapColor & set_projection_matrix (const Magnum::Matrix4 & matrix) ShadowMapColor & set_transformation_matrix (const Magnum::Matrix4 & matrix)"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1ShadowMapColor/#public-types-documentation","title":"Public Types Documentation","text":""},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1ShadowMapColor/#enum-flag","title":"enum Flag","text":"
enum robot_dart::gui::magnum::gs::ShadowMapColor::Flag {\nDiffuseTexture = 1 << 0\n};\n
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1ShadowMapColor/#typedef-flags","title":"typedef Flags","text":"
using robot_dart::gui::magnum::gs::ShadowMapColor::Flags =  Magnum::Containers::EnumSet<Flag>;\n
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1ShadowMapColor/#typedef-position","title":"typedef Position","text":"
using robot_dart::gui::magnum::gs::ShadowMapColor::Position =  Magnum::Shaders::Generic3D::Position;\n
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1ShadowMapColor/#typedef-texturecoordinates","title":"typedef TextureCoordinates","text":"
using robot_dart::gui::magnum::gs::ShadowMapColor::TextureCoordinates =  Magnum::Shaders::Generic3D::TextureCoordinates;\n
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1ShadowMapColor/#public-functions-documentation","title":"Public Functions Documentation","text":""},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1ShadowMapColor/#function-shadowmapcolor-12","title":"function ShadowMapColor [\u00bd]","text":"
explicit robot_dart::gui::magnum::gs::ShadowMapColor::ShadowMapColor (\nFlags flags={}\n) 
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1ShadowMapColor/#function-shadowmapcolor-22","title":"function ShadowMapColor [2/2]","text":"
explicit robot_dart::gui::magnum::gs::ShadowMapColor::ShadowMapColor (\nMagnum::NoCreateT\n) noexcept\n
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1ShadowMapColor/#function-flags","title":"function flags","text":"
Flags robot_dart::gui::magnum::gs::ShadowMapColor::flags () const\n
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1ShadowMapColor/#function-set_material","title":"function set_material","text":"
ShadowMapColor & robot_dart::gui::magnum::gs::ShadowMapColor::set_material (\nMaterial & material\n) 
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1ShadowMapColor/#function-set_projection_matrix","title":"function set_projection_matrix","text":"
ShadowMapColor & robot_dart::gui::magnum::gs::ShadowMapColor::set_projection_matrix (\nconst Magnum::Matrix4 & matrix\n) 
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1gs_1_1ShadowMapColor/#function-set_transformation_matrix","title":"function set_transformation_matrix","text":"
ShadowMapColor & robot_dart::gui::magnum::gs::ShadowMapColor::set_transformation_matrix (\nconst Magnum::Matrix4 & matrix\n) 

The documentation for this class was generated from the following file robot_dart/gui/magnum/gs/shadow_map_color.hpp

"},{"location":"api/namespacerobot__dart_1_1gui_1_1magnum_1_1sensor/","title":"Namespace robot_dart::gui::magnum::sensor","text":"

Namespace List > robot_dart > gui > magnum > sensor

"},{"location":"api/namespacerobot__dart_1_1gui_1_1magnum_1_1sensor/#classes","title":"Classes","text":"Type Name class Camera

The documentation for this class was generated from the following file robot_dart/gui/magnum/sensor/camera.cpp

"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1sensor_1_1Camera/","title":"Class robot_dart::gui::magnum::sensor::Camera","text":"

ClassList > robot_dart > gui > magnum > sensor > Camera

Inherits the following classes: robot_dart::sensor::Sensor

"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1sensor_1_1Camera/#public-functions","title":"Public Functions","text":"Type Name Camera (BaseApplication * app, size_t width, size_t height, size_t freq=30, bool draw_debug=false) virtual void attach_to_body (dart::dynamics::BodyNode * body, const Eigen::Isometry3d & tf=Eigen::Isometry3d::Identity()) override virtual void attach_to_joint (dart::dynamics::Joint *, const Eigen::Isometry3d &) override virtual void calculate (double) override gs::Camera & camera () const gs::Camera & camera () const Eigen::Matrix4d camera_extrinsic_matrix () const Eigen::Matrix3d camera_intrinsic_matrix () const DepthImage depth_array () GrayscaleImage depth_image () void draw_debug (bool draw=true) bool drawing_debug () const Image image () virtual void init () override void look_at (const Eigen::Vector3d & camera_pos, const Eigen::Vector3d & look_at=Eigen::Vector3d(0, 0, 0), const Eigen::Vector3d & up=Eigen::Vector3d(0, 0, 1)) Magnum::Image2D * magnum_depth_image () Magnum::Image2D * magnum_image () GrayscaleImage raw_depth_image () void record_video (const std::string & video_fname) virtual std::string type () override const ~Camera ()"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1sensor_1_1Camera/#public-functions-inherited-from-robot_dartsensorsensor","title":"Public Functions inherited from robot_dart::sensor::Sensor","text":"

See robot_dart::sensor::Sensor

Type Name Sensor (size_t freq=40) void activate (bool enable=true) bool active () const virtual void attach_to_body (dart::dynamics::BodyNode * body, const Eigen::Isometry3d & tf=Eigen::Isometry3d::Identity()) void attach_to_body (const std::shared_ptr< Robot > & robot, const std::string & body_name, const Eigen::Isometry3d & tf=Eigen::Isometry3d::Identity()) virtual void attach_to_joint (dart::dynamics::Joint * joint, const Eigen::Isometry3d & tf=Eigen::Isometry3d::Identity()) void attach_to_joint (const std::shared_ptr< Robot > & robot, const std::string & joint_name, const Eigen::Isometry3d & tf=Eigen::Isometry3d::Identity()) const std::string & attached_to () const virtual void calculate (double) = 0 void detach () size_t frequency () const virtual void init () = 0 const Eigen::Isometry3d & pose () const void refresh (double t) void set_frequency (size_t freq) void set_pose (const Eigen::Isometry3d & tf) void set_simu (RobotDARTSimu * simu) const RobotDARTSimu * simu () const virtual std::string type () const = 0 virtual ~Sensor ()"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1sensor_1_1Camera/#protected-attributes","title":"Protected Attributes","text":"Type Name std::unique_ptr< gs::Camera > _camera Magnum::GL::Renderbuffer _color Magnum::GL::Renderbuffer _depth bool _draw_debug Magnum::PixelFormat _format Magnum::GL::Framebuffer _framebuffer = {Magnum::NoCreate} size_t _height BaseApplication * _magnum_app size_t _width"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1sensor_1_1Camera/#protected-attributes-inherited-from-robot_dartsensorsensor","title":"Protected Attributes inherited from robot_dart::sensor::Sensor","text":"

See robot_dart::sensor::Sensor

Type Name bool _active Eigen::Isometry3d _attached_tf bool _attached_to_body = = false bool _attached_to_joint = = false bool _attaching_to_body = = false bool _attaching_to_joint = = false dart::dynamics::BodyNode * _body_attached size_t _frequency dart::dynamics::Joint * _joint_attached RobotDARTSimu * _simu = = nullptr Eigen::Isometry3d _world_pose"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1sensor_1_1Camera/#public-functions-documentation","title":"Public Functions Documentation","text":""},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1sensor_1_1Camera/#function-camera","title":"function Camera","text":"
robot_dart::gui::magnum::sensor::Camera::Camera (\nBaseApplication * app,\nsize_t width,\nsize_t height,\nsize_t freq=30,\nbool draw_debug=false\n) 
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1sensor_1_1Camera/#function-attach_to_body","title":"function attach_to_body","text":"
virtual void robot_dart::gui::magnum::sensor::Camera::attach_to_body (\ndart::dynamics::BodyNode * body,\nconst Eigen::Isometry3d & tf=Eigen::Isometry3d::Identity()\n) override\n

Implements robot_dart::sensor::Sensor::attach_to_body

"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1sensor_1_1Camera/#function-attach_to_joint","title":"function attach_to_joint","text":"
inline virtual void robot_dart::gui::magnum::sensor::Camera::attach_to_joint (\ndart::dynamics::Joint *,\nconst Eigen::Isometry3d &\n) override\n

Implements robot_dart::sensor::Sensor::attach_to_joint

"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1sensor_1_1Camera/#function-calculate","title":"function calculate","text":"
virtual void robot_dart::gui::magnum::sensor::Camera::calculate (\ndouble\n) override\n

Implements robot_dart::sensor::Sensor::calculate

"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1sensor_1_1Camera/#function-camera-12","title":"function camera [\u00bd]","text":"
inline gs::Camera & robot_dart::gui::magnum::sensor::Camera::camera () 
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1sensor_1_1Camera/#function-camera-22","title":"function camera [2/2]","text":"
inline const gs::Camera & robot_dart::gui::magnum::sensor::Camera::camera () const\n
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1sensor_1_1Camera/#function-camera_extrinsic_matrix","title":"function camera_extrinsic_matrix","text":"
Eigen::Matrix4d robot_dart::gui::magnum::sensor::Camera::camera_extrinsic_matrix () const\n
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1sensor_1_1Camera/#function-camera_intrinsic_matrix","title":"function camera_intrinsic_matrix","text":"
Eigen::Matrix3d robot_dart::gui::magnum::sensor::Camera::camera_intrinsic_matrix () const\n
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1sensor_1_1Camera/#function-depth_array","title":"function depth_array","text":"
DepthImage robot_dart::gui::magnum::sensor::Camera::depth_array () 
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1sensor_1_1Camera/#function-depth_image","title":"function depth_image","text":"
GrayscaleImage robot_dart::gui::magnum::sensor::Camera::depth_image () 
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1sensor_1_1Camera/#function-draw_debug","title":"function draw_debug","text":"
inline void robot_dart::gui::magnum::sensor::Camera::draw_debug (\nbool draw=true\n) 
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1sensor_1_1Camera/#function-drawing_debug","title":"function drawing_debug","text":"
inline bool robot_dart::gui::magnum::sensor::Camera::drawing_debug () const\n
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1sensor_1_1Camera/#function-image","title":"function image","text":"
inline Image robot_dart::gui::magnum::sensor::Camera::image () 
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1sensor_1_1Camera/#function-init","title":"function init","text":"
virtual void robot_dart::gui::magnum::sensor::Camera::init () override\n

Implements robot_dart::sensor::Sensor::init

"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1sensor_1_1Camera/#function-look_at","title":"function look_at","text":"
void robot_dart::gui::magnum::sensor::Camera::look_at (\nconst Eigen::Vector3d & camera_pos,\nconst Eigen::Vector3d & look_at=Eigen::Vector3d(0, 0, 0),\nconst Eigen::Vector3d & up=Eigen::Vector3d(0, 0, 1)\n) 
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1sensor_1_1Camera/#function-magnum_depth_image","title":"function magnum_depth_image","text":"
inline Magnum::Image2D * robot_dart::gui::magnum::sensor::Camera::magnum_depth_image () 
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1sensor_1_1Camera/#function-magnum_image","title":"function magnum_image","text":"
inline Magnum::Image2D * robot_dart::gui::magnum::sensor::Camera::magnum_image () 
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1sensor_1_1Camera/#function-raw_depth_image","title":"function raw_depth_image","text":"
GrayscaleImage robot_dart::gui::magnum::sensor::Camera::raw_depth_image () 
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1sensor_1_1Camera/#function-record_video","title":"function record_video","text":"
inline void robot_dart::gui::magnum::sensor::Camera::record_video (\nconst std::string & video_fname\n) 
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1sensor_1_1Camera/#function-type","title":"function type","text":"
virtual std::string robot_dart::gui::magnum::sensor::Camera::type () override const\n

Implements robot_dart::sensor::Sensor::type

"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1sensor_1_1Camera/#function-camera_1","title":"function ~Camera","text":"
inline robot_dart::gui::magnum::sensor::Camera::~Camera () 
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1sensor_1_1Camera/#protected-attributes-documentation","title":"Protected Attributes Documentation","text":""},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1sensor_1_1Camera/#variable-_camera","title":"variable _camera","text":"
std::unique_ptr<gs::Camera> robot_dart::gui::magnum::sensor::Camera::_camera;\n
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1sensor_1_1Camera/#variable-_color","title":"variable _color","text":"
Magnum::GL::Renderbuffer robot_dart::gui::magnum::sensor::Camera::_color;\n
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1sensor_1_1Camera/#variable-_depth","title":"variable _depth","text":"
Magnum::GL::Renderbuffer robot_dart::gui::magnum::sensor::Camera::_depth;\n
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1sensor_1_1Camera/#variable-_draw_debug","title":"variable _draw_debug","text":"
bool robot_dart::gui::magnum::sensor::Camera::_draw_debug;\n
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1sensor_1_1Camera/#variable-_format","title":"variable _format","text":"
Magnum::PixelFormat robot_dart::gui::magnum::sensor::Camera::_format;\n
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1sensor_1_1Camera/#variable-_framebuffer","title":"variable _framebuffer","text":"
Magnum::GL::Framebuffer robot_dart::gui::magnum::sensor::Camera::_framebuffer;\n
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1sensor_1_1Camera/#variable-_height","title":"variable _height","text":"
size_t robot_dart::gui::magnum::sensor::Camera::_height;\n
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1sensor_1_1Camera/#variable-_magnum_app","title":"variable _magnum_app","text":"
BaseApplication* robot_dart::gui::magnum::sensor::Camera::_magnum_app;\n
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1sensor_1_1Camera/#variable-_width","title":"variable _width","text":"
size_t robot_dart::gui::magnum::sensor::Camera::_width;\n

The documentation for this class was generated from the following file robot_dart/gui/magnum/sensor/camera.hpp

"},{"location":"api/namespacerobot__dart_1_1robots/","title":"Namespace robot_dart::robots","text":"

Namespace List > robot_dart > robots

"},{"location":"api/namespacerobot__dart_1_1robots/#classes","title":"Classes","text":"Type Name class A1 class Arm class Franka class Hexapod class ICub class Iiwa class Pendulum class Talos datasheet: https://pal-robotics.com/wp-content/uploads/2019/07/Datasheet_TALOS.pdf __ class TalosFastCollision class TalosLight class Tiago datasheet: https://pal-robotics.com/wp-content/uploads/2021/07/Datasheet-complete_TIAGo-2021.pdf __ class Ur3e class Ur3eHand class Vx300

The documentation for this class was generated from the following file robot_dart/robots/a1.cpp

"},{"location":"api/classrobot__dart_1_1robots_1_1A1/","title":"Class robot_dart::robots::A1","text":"

ClassList > robot_dart > robots > A1

Inherits the following classes: robot_dart::Robot

"},{"location":"api/classrobot__dart_1_1robots_1_1A1/#public-functions","title":"Public Functions","text":"Type Name A1 (size_t frequency=1000, const std::string & urdf=\"unitree_a1/a1.urdf\", const std::vector< std::pair< std::string, std::string > > & packages=('a1\\_description', 'unitree\\_a1/a1\\_description')) const sensor::IMU & imu () const virtual void reset () override"},{"location":"api/classrobot__dart_1_1robots_1_1A1/#public-functions-inherited-from-robot_dartrobot","title":"Public Functions inherited from robot_dart::Robot","text":"

See robot_dart::Robot

Type Name Robot (const std::string & model_file, const std::vector< std::pair< std::string, std::string > > & packages, const std::string & robot_name=\"robot\", bool is_urdf_string=false, bool cast_shadows=true) Robot (const std::string & model_file, const std::string & robot_name=\"robot\", bool is_urdf_string=false, bool cast_shadows=true) Robot (dart::dynamics::SkeletonPtr skeleton, const std::string & robot_name=\"robot\", bool cast_shadows=true) Eigen::VectorXd acceleration_lower_limits (const std::vector< std::string > & dof_names={}) const Eigen::VectorXd acceleration_upper_limits (const std::vector< std::string > & dof_names={}) const Eigen::VectorXd accelerations (const std::vector< std::string > & dof_names={}) const std::vector< std::shared_ptr< control::RobotControl > > active_controllers () const std::string actuator_type (const std::string & joint_name) const std::vector< std::string > actuator_types (const std::vector< std::string > & joint_names={}) const void add_body_mass (const std::string & body_name, double mass) void add_body_mass (size_t body_index, double mass) void add_controller (const std::shared_ptr< control::RobotControl > & controller, double weight=1.0) void add_external_force (const std::string & body_name, const Eigen::Vector3d & force, const Eigen::Vector3d & offset=Eigen::Vector3d::Zero(), bool force_local=false, bool offset_local=true) void add_external_force (size_t body_index, const Eigen::Vector3d & force, const Eigen::Vector3d & offset=Eigen::Vector3d::Zero(), bool force_local=false, bool offset_local=true) void add_external_torque (const std::string & body_name, const Eigen::Vector3d & torque, bool local=false) void add_external_torque (size_t body_index, const Eigen::Vector3d & torque, bool local=false) bool adjacent_colliding () const Eigen::MatrixXd aug_mass_matrix (const std::vector< std::string > & dof_names={}) const Eigen::Isometry3d base_pose () const Eigen::Vector6d base_pose_vec () const Eigen::Vector6d body_acceleration (const std::string & body_name) const Eigen::Vector6d body_acceleration (size_t body_index) const size_t body_index (const std::string & body_name) const double body_mass (const std::string & body_name) const double body_mass (size_t body_index) const std::string body_name (size_t body_index) const std::vector< std::string > body_names () const dart::dynamics::BodyNode * body_node (const std::string & body_name) dart::dynamics::BodyNode * body_node (size_t body_index) Eigen::Isometry3d body_pose (const std::string & body_name) const Eigen::Isometry3d body_pose (size_t body_index) const Eigen::Vector6d body_pose_vec (const std::string & body_name) const Eigen::Vector6d body_pose_vec (size_t body_index) const Eigen::Vector6d body_velocity (const std::string & body_name) const Eigen::Vector6d body_velocity (size_t body_index) const bool cast_shadows () const void clear_controllers () void clear_external_forces () void clear_internal_forces () std::shared_ptr< Robot > clone () const std::shared_ptr< Robot > clone_ghost (const std::string & ghost_name=\"ghost\", const Eigen::Vector4d & ghost_color={0.3, 0.3, 0.3, 0.7}) const Eigen::Vector3d com () const Eigen::Vector6d com_acceleration () const Eigen::MatrixXd com_jacobian (const std::vector< std::string > & dof_names={}) const Eigen::MatrixXd com_jacobian_deriv (const std::vector< std::string > & dof_names={}) const Eigen::Vector6d com_velocity () const Eigen::VectorXd commands (const std::vector< std::string > & dof_names={}) const Eigen::VectorXd constraint_forces (const std::vector< std::string > & dof_names={}) const std::shared_ptr< control::RobotControl > controller (size_t index) const std::vector< std::shared_ptr< control::RobotControl > > controllers () const Eigen::VectorXd coriolis_forces (const std::vector< std::string > & dof_names={}) const Eigen::VectorXd coriolis_gravity_forces (const std::vector< std::string > & dof_names={}) const std::vector< double > coulomb_coeffs (const std::vector< std::string > & dof_names={}) const std::vector< double > damping_coeffs (const std::vector< std::string > & dof_names={}) const dart::dynamics::DegreeOfFreedom * dof (const std::string & dof_name) dart::dynamics::DegreeOfFreedom * dof (size_t dof_index) size_t dof_index (const std::string & dof_name) const const std::unordered_map< std::string, size_t > & dof_map () const std::string dof_name (size_t dof_index) const std::vector< std::string > dof_names (bool filter_mimics=false, bool filter_locked=false, bool filter_passive=false) const const std::vector< std::pair< dart::dynamics::BodyNode *, double > > & drawing_axes () const Eigen::Vector6d external_forces (const std::string & body_name) const Eigen::Vector6d external_forces (size_t body_index) const void fix_to_world () bool fixed () const Eigen::VectorXd force_lower_limits (const std::vector< std::string > & dof_names={}) const void force_position_bounds () std::pair< Eigen::Vector6d, Eigen::Vector6d > force_torque (size_t joint_index) const Eigen::VectorXd force_upper_limits (const std::vector< std::string > & dof_names={}) const Eigen::VectorXd forces (const std::vector< std::string > & dof_names={}) const bool free () const void free_from_world (const Eigen::Vector6d & pose=Eigen::Vector6d::Zero()) double friction_coeff (const std::string & body_name) double friction_coeff (size_t body_index) Eigen::Vector3d friction_dir (const std::string & body_name) Eigen::Vector3d friction_dir (size_t body_index) bool ghost () const Eigen::VectorXd gravity_forces (const std::vector< std::string > & dof_names={}) const Eigen::MatrixXd inv_aug_mass_matrix (const std::vector< std::string > & dof_names={}) const Eigen::MatrixXd inv_mass_matrix (const std::vector< std::string > & dof_names={}) const Eigen::MatrixXd jacobian (const std::string & body_name, const std::vector< std::string > & dof_names={}) const Eigen::MatrixXd jacobian_deriv (const std::string & body_name, const std::vector< std::string > & dof_names={}) const dart::dynamics::Joint * joint (const std::string & joint_name) dart::dynamics::Joint * joint (size_t joint_index) size_t joint_index (const std::string & joint_name) const const std::unordered_map< std::string, size_t > & joint_map () const std::string joint_name (size_t joint_index) const std::vector< std::string > joint_names () const std::vector< std::string > locked_dof_names () const Eigen::MatrixXd mass_matrix (const std::vector< std::string > & dof_names={}) const std::vector< std::string > mimic_dof_names () const const std::string & model_filename () const const std::vector< std::pair< std::string, std::string > > & model_packages () const const std::string & name () const size_t num_bodies () const size_t num_controllers () const size_t num_dofs () const size_t num_joints () const std::vector< std::string > passive_dof_names () const std::vector< bool > position_enforced (const std::vector< std::string > & dof_names={}) const Eigen::VectorXd position_lower_limits (const std::vector< std::string > & dof_names={}) const Eigen::VectorXd position_upper_limits (const std::vector< std::string > & dof_names={}) const Eigen::VectorXd positions (const std::vector< std::string > & dof_names={}) const void reinit_controllers () void remove_all_drawing_axis () void remove_controller (const std::shared_ptr< control::RobotControl > & controller) void remove_controller (size_t index) virtual void reset () void reset_commands () double restitution_coeff (const std::string & body_name) double restitution_coeff (size_t body_index) double secondary_friction_coeff (const std::string & body_name) double secondary_friction_coeff (size_t body_index) bool self_colliding () const void set_acceleration_lower_limits (const Eigen::VectorXd & accelerations, const std::vector< std::string > & dof_names={}) void set_acceleration_upper_limits (const Eigen::VectorXd & accelerations, const std::vector< std::string > & dof_names={}) void set_accelerations (const Eigen::VectorXd & accelerations, const std::vector< std::string > & dof_names={}) void set_actuator_type (const std::string & type, const std::string & joint_name, bool override_mimic=false, bool override_base=false) void set_actuator_types (const std::string & type, const std::vector< std::string > & joint_names={}, bool override_mimic=false, bool override_base=false) void set_base_pose (const Eigen::Isometry3d & tf) void set_base_pose (const Eigen::Vector6d & pose) set base pose: pose is a 6D vector (first 3D orientation in angle-axis and last 3D translation) void set_body_mass (const std::string & body_name, double mass) void set_body_mass (size_t body_index, double mass) void set_body_name (size_t body_index, const std::string & body_name) void set_cast_shadows (bool cast_shadows=true) void set_color_mode (const std::string & color_mode) void set_color_mode (const std::string & color_mode, const std::string & body_name) void set_commands (const Eigen::VectorXd & commands, const std::vector< std::string > & dof_names={}) void set_coulomb_coeffs (const std::vector< double > & cfrictions, const std::vector< std::string > & dof_names={}) void set_coulomb_coeffs (double cfriction, const std::vector< std::string > & dof_names={}) void set_damping_coeffs (const std::vector< double > & damps, const std::vector< std::string > & dof_names={}) void set_damping_coeffs (double damp, const std::vector< std::string > & dof_names={}) void set_draw_axis (const std::string & body_name, double size=0.25) void set_external_force (const std::string & body_name, const Eigen::Vector3d & force, const Eigen::Vector3d & offset=Eigen::Vector3d::Zero(), bool force_local=false, bool offset_local=true) void set_external_force (size_t body_index, const Eigen::Vector3d & force, const Eigen::Vector3d & offset=Eigen::Vector3d::Zero(), bool force_local=false, bool offset_local=true) void set_external_torque (const std::string & body_name, const Eigen::Vector3d & torque, bool local=false) void set_external_torque (size_t body_index, const Eigen::Vector3d & torque, bool local=false) void set_force_lower_limits (const Eigen::VectorXd & forces, const std::vector< std::string > & dof_names={}) void set_force_upper_limits (const Eigen::VectorXd & forces, const std::vector< std::string > & dof_names={}) void set_forces (const Eigen::VectorXd & forces, const std::vector< std::string > & dof_names={}) void set_friction_coeff (const std::string & body_name, double value) void set_friction_coeff (size_t body_index, double value) void set_friction_coeffs (double value) void set_friction_dir (const std::string & body_name, const Eigen::Vector3d & direction) void set_friction_dir (size_t body_index, const Eigen::Vector3d & direction) void set_ghost (bool ghost=true) void set_joint_name (size_t joint_index, const std::string & joint_name) void set_mimic (const std::string & joint_name, const std::string & mimic_joint_name, double multiplier=1., double offset=0.) void set_position_enforced (const std::vector< bool > & enforced, const std::vector< std::string > & dof_names={}) void set_position_enforced (bool enforced, const std::vector< std::string > & dof_names={}) void set_position_lower_limits (const Eigen::VectorXd & positions, const std::vector< std::string > & dof_names={}) void set_position_upper_limits (const Eigen::VectorXd & positions, const std::vector< std::string > & dof_names={}) void set_positions (const Eigen::VectorXd & positions, const std::vector< std::string > & dof_names={}) void set_restitution_coeff (const std::string & body_name, double value) void set_restitution_coeff (size_t body_index, double value) void set_restitution_coeffs (double value) void set_secondary_friction_coeff (const std::string & body_name, double value) void set_secondary_friction_coeff (size_t body_index, double value) void set_secondary_friction_coeffs (double value) void set_self_collision (bool enable_self_collisions=true, bool enable_adjacent_collisions=false) void set_spring_stiffnesses (const std::vector< double > & stiffnesses, const std::vector< std::string > & dof_names={}) void set_spring_stiffnesses (double stiffness, const std::vector< std::string > & dof_names={}) void set_velocities (const Eigen::VectorXd & velocities, const std::vector< std::string > & dof_names={}) void set_velocity_lower_limits (const Eigen::VectorXd & velocities, const std::vector< std::string > & dof_names={}) void set_velocity_upper_limits (const Eigen::VectorXd & velocities, const std::vector< std::string > & dof_names={}) dart::dynamics::SkeletonPtr skeleton () std::vector< double > spring_stiffnesses (const std::vector< std::string > & dof_names={}) const void update (double t) void update_joint_dof_maps () Eigen::VectorXd vec_dof (const Eigen::VectorXd & vec, const std::vector< std::string > & dof_names) const Eigen::VectorXd velocities (const std::vector< std::string > & dof_names={}) const Eigen::VectorXd velocity_lower_limits (const std::vector< std::string > & dof_names={}) const Eigen::VectorXd velocity_upper_limits (const std::vector< std::string > & dof_names={}) const virtual ~Robot ()"},{"location":"api/classrobot__dart_1_1robots_1_1A1/#public-static-functions-inherited-from-robot_dartrobot","title":"Public Static Functions inherited from robot_dart::Robot","text":"

See robot_dart::Robot

Type Name std::shared_ptr< Robot > create_box (const Eigen::Vector3d & dims, const Eigen::Isometry3d & tf, const std::string & type=\"free\", double mass=1.0, const Eigen::Vector4d & color=dart::Color::Red(1.0), const std::string & box_name=\"box\") std::shared_ptr< Robot > create_box (const Eigen::Vector3d & dims, const Eigen::Vector6d & pose=Eigen::Vector6d::Zero(), const std::string & type=\"free\", double mass=1.0, const Eigen::Vector4d & color=dart::Color::Red(1.0), const std::string & box_name=\"box\") std::shared_ptr< Robot > create_ellipsoid (const Eigen::Vector3d & dims, const Eigen::Isometry3d & tf, const std::string & type=\"free\", double mass=1.0, const Eigen::Vector4d & color=dart::Color::Red(1.0), const std::string & ellipsoid_name=\"ellipsoid\") std::shared_ptr< Robot > create_ellipsoid (const Eigen::Vector3d & dims, const Eigen::Vector6d & pose=Eigen::Vector6d::Zero(), const std::string & type=\"free\", double mass=1.0, const Eigen::Vector4d & color=dart::Color::Red(1.0), const std::string & ellipsoid_name=\"ellipsoid\")"},{"location":"api/classrobot__dart_1_1robots_1_1A1/#protected-attributes","title":"Protected Attributes","text":"Type Name std::shared_ptr< sensor::IMU > _imu"},{"location":"api/classrobot__dart_1_1robots_1_1A1/#protected-attributes-inherited-from-robot_dartrobot","title":"Protected Attributes inherited from robot_dart::Robot","text":"

See robot_dart::Robot

Type Name std::vector< std::pair< dart::dynamics::BodyNode *, double > > _axis_shapes bool _cast_shadows std::vector< std::shared_ptr< control::RobotControl > > _controllers std::unordered_map< std::string, size_t > _dof_map bool _is_ghost std::unordered_map< std::string, size_t > _joint_map std::string _model_filename std::vector< std::pair< std::string, std::string > > _packages std::string _robot_name dart::dynamics::SkeletonPtr _skeleton"},{"location":"api/classrobot__dart_1_1robots_1_1A1/#protected-functions-inherited-from-robot_dartrobot","title":"Protected Functions inherited from robot_dart::Robot","text":"

See robot_dart::Robot

Type Name dart::dynamics::Joint::ActuatorType _actuator_type (size_t joint_index) const std::vector< dart::dynamics::Joint::ActuatorType > _actuator_types () const std::string _get_path (const std::string & filename) const Eigen::MatrixXd _jacobian (const Eigen::MatrixXd & full_jacobian, const std::vector< std::string > & dof_names) const dart::dynamics::SkeletonPtr _load_model (const std::string & filename, const std::vector< std::pair< std::string, std::string > > & packages=std::vector< std::pair< std::string, std::string > >(), bool is_urdf_string=false) Eigen::MatrixXd _mass_matrix (const Eigen::MatrixXd & full_mass_matrix, const std::vector< std::string > & dof_names) const virtual void _post_addition (RobotDARTSimu *) Function called by RobotDARTSimu object when adding the robot to the world. virtual void _post_removal (RobotDARTSimu *) Function called by RobotDARTSimu object when removing the robot to the world. void _set_actuator_type (size_t joint_index, dart::dynamics::Joint::ActuatorType type, bool override_mimic=false, bool override_base=false) void _set_actuator_types (const std::vector< dart::dynamics::Joint::ActuatorType > & types, bool override_mimic=false, bool override_base=false) void _set_actuator_types (dart::dynamics::Joint::ActuatorType type, bool override_mimic=false, bool override_base=false) void _set_color_mode (dart::dynamics::MeshShape::ColorMode color_mode, dart::dynamics::SkeletonPtr skel) void _set_color_mode (dart::dynamics::MeshShape::ColorMode color_mode, dart::dynamics::ShapeNode * sn)"},{"location":"api/classrobot__dart_1_1robots_1_1A1/#public-functions-documentation","title":"Public Functions Documentation","text":""},{"location":"api/classrobot__dart_1_1robots_1_1A1/#function-a1","title":"function A1","text":"
robot_dart::robots::A1::A1 (\nsize_t frequency=1000,\nconst std::string & urdf=\"unitree_a1/a1.urdf\",\nconst std::vector< std::pair< std::string, std::string > > & packages=('a1_description', 'unitree_a1/a1_description')\n) 
"},{"location":"api/classrobot__dart_1_1robots_1_1A1/#function-imu","title":"function imu","text":"
inline const sensor::IMU & robot_dart::robots::A1::imu () const\n
"},{"location":"api/classrobot__dart_1_1robots_1_1A1/#function-reset","title":"function reset","text":"
virtual void robot_dart::robots::A1::reset () override\n

Implements robot_dart::Robot::reset

"},{"location":"api/classrobot__dart_1_1robots_1_1A1/#protected-attributes-documentation","title":"Protected Attributes Documentation","text":""},{"location":"api/classrobot__dart_1_1robots_1_1A1/#variable-_imu","title":"variable _imu","text":"
std::shared_ptr<sensor::IMU> robot_dart::robots::A1::_imu;\n

The documentation for this class was generated from the following file robot_dart/robots/a1.hpp

"},{"location":"api/classrobot__dart_1_1robots_1_1Arm/","title":"Class robot_dart::robots::Arm","text":"

ClassList > robot_dart > robots > Arm

Inherits the following classes: robot_dart::Robot

"},{"location":"api/classrobot__dart_1_1robots_1_1Arm/#public-functions","title":"Public Functions","text":"Type Name Arm (const std::string & urdf=\"arm.urdf\")"},{"location":"api/classrobot__dart_1_1robots_1_1Arm/#public-functions-inherited-from-robot_dartrobot","title":"Public Functions inherited from robot_dart::Robot","text":"

See robot_dart::Robot

Type Name Robot (const std::string & model_file, const std::vector< std::pair< std::string, std::string > > & packages, const std::string & robot_name=\"robot\", bool is_urdf_string=false, bool cast_shadows=true) Robot (const std::string & model_file, const std::string & robot_name=\"robot\", bool is_urdf_string=false, bool cast_shadows=true) Robot (dart::dynamics::SkeletonPtr skeleton, const std::string & robot_name=\"robot\", bool cast_shadows=true) Eigen::VectorXd acceleration_lower_limits (const std::vector< std::string > & dof_names={}) const Eigen::VectorXd acceleration_upper_limits (const std::vector< std::string > & dof_names={}) const Eigen::VectorXd accelerations (const std::vector< std::string > & dof_names={}) const std::vector< std::shared_ptr< control::RobotControl > > active_controllers () const std::string actuator_type (const std::string & joint_name) const std::vector< std::string > actuator_types (const std::vector< std::string > & joint_names={}) const void add_body_mass (const std::string & body_name, double mass) void add_body_mass (size_t body_index, double mass) void add_controller (const std::shared_ptr< control::RobotControl > & controller, double weight=1.0) void add_external_force (const std::string & body_name, const Eigen::Vector3d & force, const Eigen::Vector3d & offset=Eigen::Vector3d::Zero(), bool force_local=false, bool offset_local=true) void add_external_force (size_t body_index, const Eigen::Vector3d & force, const Eigen::Vector3d & offset=Eigen::Vector3d::Zero(), bool force_local=false, bool offset_local=true) void add_external_torque (const std::string & body_name, const Eigen::Vector3d & torque, bool local=false) void add_external_torque (size_t body_index, const Eigen::Vector3d & torque, bool local=false) bool adjacent_colliding () const Eigen::MatrixXd aug_mass_matrix (const std::vector< std::string > & dof_names={}) const Eigen::Isometry3d base_pose () const Eigen::Vector6d base_pose_vec () const Eigen::Vector6d body_acceleration (const std::string & body_name) const Eigen::Vector6d body_acceleration (size_t body_index) const size_t body_index (const std::string & body_name) const double body_mass (const std::string & body_name) const double body_mass (size_t body_index) const std::string body_name (size_t body_index) const std::vector< std::string > body_names () const dart::dynamics::BodyNode * body_node (const std::string & body_name) dart::dynamics::BodyNode * body_node (size_t body_index) Eigen::Isometry3d body_pose (const std::string & body_name) const Eigen::Isometry3d body_pose (size_t body_index) const Eigen::Vector6d body_pose_vec (const std::string & body_name) const Eigen::Vector6d body_pose_vec (size_t body_index) const Eigen::Vector6d body_velocity (const std::string & body_name) const Eigen::Vector6d body_velocity (size_t body_index) const bool cast_shadows () const void clear_controllers () void clear_external_forces () void clear_internal_forces () std::shared_ptr< Robot > clone () const std::shared_ptr< Robot > clone_ghost (const std::string & ghost_name=\"ghost\", const Eigen::Vector4d & ghost_color={0.3, 0.3, 0.3, 0.7}) const Eigen::Vector3d com () const Eigen::Vector6d com_acceleration () const Eigen::MatrixXd com_jacobian (const std::vector< std::string > & dof_names={}) const Eigen::MatrixXd com_jacobian_deriv (const std::vector< std::string > & dof_names={}) const Eigen::Vector6d com_velocity () const Eigen::VectorXd commands (const std::vector< std::string > & dof_names={}) const Eigen::VectorXd constraint_forces (const std::vector< std::string > & dof_names={}) const std::shared_ptr< control::RobotControl > controller (size_t index) const std::vector< std::shared_ptr< control::RobotControl > > controllers () const Eigen::VectorXd coriolis_forces (const std::vector< std::string > & dof_names={}) const Eigen::VectorXd coriolis_gravity_forces (const std::vector< std::string > & dof_names={}) const std::vector< double > coulomb_coeffs (const std::vector< std::string > & dof_names={}) const std::vector< double > damping_coeffs (const std::vector< std::string > & dof_names={}) const dart::dynamics::DegreeOfFreedom * dof (const std::string & dof_name) dart::dynamics::DegreeOfFreedom * dof (size_t dof_index) size_t dof_index (const std::string & dof_name) const const std::unordered_map< std::string, size_t > & dof_map () const std::string dof_name (size_t dof_index) const std::vector< std::string > dof_names (bool filter_mimics=false, bool filter_locked=false, bool filter_passive=false) const const std::vector< std::pair< dart::dynamics::BodyNode *, double > > & drawing_axes () const Eigen::Vector6d external_forces (const std::string & body_name) const Eigen::Vector6d external_forces (size_t body_index) const void fix_to_world () bool fixed () const Eigen::VectorXd force_lower_limits (const std::vector< std::string > & dof_names={}) const void force_position_bounds () std::pair< Eigen::Vector6d, Eigen::Vector6d > force_torque (size_t joint_index) const Eigen::VectorXd force_upper_limits (const std::vector< std::string > & dof_names={}) const Eigen::VectorXd forces (const std::vector< std::string > & dof_names={}) const bool free () const void free_from_world (const Eigen::Vector6d & pose=Eigen::Vector6d::Zero()) double friction_coeff (const std::string & body_name) double friction_coeff (size_t body_index) Eigen::Vector3d friction_dir (const std::string & body_name) Eigen::Vector3d friction_dir (size_t body_index) bool ghost () const Eigen::VectorXd gravity_forces (const std::vector< std::string > & dof_names={}) const Eigen::MatrixXd inv_aug_mass_matrix (const std::vector< std::string > & dof_names={}) const Eigen::MatrixXd inv_mass_matrix (const std::vector< std::string > & dof_names={}) const Eigen::MatrixXd jacobian (const std::string & body_name, const std::vector< std::string > & dof_names={}) const Eigen::MatrixXd jacobian_deriv (const std::string & body_name, const std::vector< std::string > & dof_names={}) const dart::dynamics::Joint * joint (const std::string & joint_name) dart::dynamics::Joint * joint (size_t joint_index) size_t joint_index (const std::string & joint_name) const const std::unordered_map< std::string, size_t > & joint_map () const std::string joint_name (size_t joint_index) const std::vector< std::string > joint_names () const std::vector< std::string > locked_dof_names () const Eigen::MatrixXd mass_matrix (const std::vector< std::string > & dof_names={}) const std::vector< std::string > mimic_dof_names () const const std::string & model_filename () const const std::vector< std::pair< std::string, std::string > > & model_packages () const const std::string & name () const size_t num_bodies () const size_t num_controllers () const size_t num_dofs () const size_t num_joints () const std::vector< std::string > passive_dof_names () const std::vector< bool > position_enforced (const std::vector< std::string > & dof_names={}) const Eigen::VectorXd position_lower_limits (const std::vector< std::string > & dof_names={}) const Eigen::VectorXd position_upper_limits (const std::vector< std::string > & dof_names={}) const Eigen::VectorXd positions (const std::vector< std::string > & dof_names={}) const void reinit_controllers () void remove_all_drawing_axis () void remove_controller (const std::shared_ptr< control::RobotControl > & controller) void remove_controller (size_t index) virtual void reset () void reset_commands () double restitution_coeff (const std::string & body_name) double restitution_coeff (size_t body_index) double secondary_friction_coeff (const std::string & body_name) double secondary_friction_coeff (size_t body_index) bool self_colliding () const void set_acceleration_lower_limits (const Eigen::VectorXd & accelerations, const std::vector< std::string > & dof_names={}) void set_acceleration_upper_limits (const Eigen::VectorXd & accelerations, const std::vector< std::string > & dof_names={}) void set_accelerations (const Eigen::VectorXd & accelerations, const std::vector< std::string > & dof_names={}) void set_actuator_type (const std::string & type, const std::string & joint_name, bool override_mimic=false, bool override_base=false) void set_actuator_types (const std::string & type, const std::vector< std::string > & joint_names={}, bool override_mimic=false, bool override_base=false) void set_base_pose (const Eigen::Isometry3d & tf) void set_base_pose (const Eigen::Vector6d & pose) set base pose: pose is a 6D vector (first 3D orientation in angle-axis and last 3D translation) void set_body_mass (const std::string & body_name, double mass) void set_body_mass (size_t body_index, double mass) void set_body_name (size_t body_index, const std::string & body_name) void set_cast_shadows (bool cast_shadows=true) void set_color_mode (const std::string & color_mode) void set_color_mode (const std::string & color_mode, const std::string & body_name) void set_commands (const Eigen::VectorXd & commands, const std::vector< std::string > & dof_names={}) void set_coulomb_coeffs (const std::vector< double > & cfrictions, const std::vector< std::string > & dof_names={}) void set_coulomb_coeffs (double cfriction, const std::vector< std::string > & dof_names={}) void set_damping_coeffs (const std::vector< double > & damps, const std::vector< std::string > & dof_names={}) void set_damping_coeffs (double damp, const std::vector< std::string > & dof_names={}) void set_draw_axis (const std::string & body_name, double size=0.25) void set_external_force (const std::string & body_name, const Eigen::Vector3d & force, const Eigen::Vector3d & offset=Eigen::Vector3d::Zero(), bool force_local=false, bool offset_local=true) void set_external_force (size_t body_index, const Eigen::Vector3d & force, const Eigen::Vector3d & offset=Eigen::Vector3d::Zero(), bool force_local=false, bool offset_local=true) void set_external_torque (const std::string & body_name, const Eigen::Vector3d & torque, bool local=false) void set_external_torque (size_t body_index, const Eigen::Vector3d & torque, bool local=false) void set_force_lower_limits (const Eigen::VectorXd & forces, const std::vector< std::string > & dof_names={}) void set_force_upper_limits (const Eigen::VectorXd & forces, const std::vector< std::string > & dof_names={}) void set_forces (const Eigen::VectorXd & forces, const std::vector< std::string > & dof_names={}) void set_friction_coeff (const std::string & body_name, double value) void set_friction_coeff (size_t body_index, double value) void set_friction_coeffs (double value) void set_friction_dir (const std::string & body_name, const Eigen::Vector3d & direction) void set_friction_dir (size_t body_index, const Eigen::Vector3d & direction) void set_ghost (bool ghost=true) void set_joint_name (size_t joint_index, const std::string & joint_name) void set_mimic (const std::string & joint_name, const std::string & mimic_joint_name, double multiplier=1., double offset=0.) void set_position_enforced (const std::vector< bool > & enforced, const std::vector< std::string > & dof_names={}) void set_position_enforced (bool enforced, const std::vector< std::string > & dof_names={}) void set_position_lower_limits (const Eigen::VectorXd & positions, const std::vector< std::string > & dof_names={}) void set_position_upper_limits (const Eigen::VectorXd & positions, const std::vector< std::string > & dof_names={}) void set_positions (const Eigen::VectorXd & positions, const std::vector< std::string > & dof_names={}) void set_restitution_coeff (const std::string & body_name, double value) void set_restitution_coeff (size_t body_index, double value) void set_restitution_coeffs (double value) void set_secondary_friction_coeff (const std::string & body_name, double value) void set_secondary_friction_coeff (size_t body_index, double value) void set_secondary_friction_coeffs (double value) void set_self_collision (bool enable_self_collisions=true, bool enable_adjacent_collisions=false) void set_spring_stiffnesses (const std::vector< double > & stiffnesses, const std::vector< std::string > & dof_names={}) void set_spring_stiffnesses (double stiffness, const std::vector< std::string > & dof_names={}) void set_velocities (const Eigen::VectorXd & velocities, const std::vector< std::string > & dof_names={}) void set_velocity_lower_limits (const Eigen::VectorXd & velocities, const std::vector< std::string > & dof_names={}) void set_velocity_upper_limits (const Eigen::VectorXd & velocities, const std::vector< std::string > & dof_names={}) dart::dynamics::SkeletonPtr skeleton () std::vector< double > spring_stiffnesses (const std::vector< std::string > & dof_names={}) const void update (double t) void update_joint_dof_maps () Eigen::VectorXd vec_dof (const Eigen::VectorXd & vec, const std::vector< std::string > & dof_names) const Eigen::VectorXd velocities (const std::vector< std::string > & dof_names={}) const Eigen::VectorXd velocity_lower_limits (const std::vector< std::string > & dof_names={}) const Eigen::VectorXd velocity_upper_limits (const std::vector< std::string > & dof_names={}) const virtual ~Robot ()"},{"location":"api/classrobot__dart_1_1robots_1_1Arm/#public-static-functions-inherited-from-robot_dartrobot","title":"Public Static Functions inherited from robot_dart::Robot","text":"

See robot_dart::Robot

Type Name std::shared_ptr< Robot > create_box (const Eigen::Vector3d & dims, const Eigen::Isometry3d & tf, const std::string & type=\"free\", double mass=1.0, const Eigen::Vector4d & color=dart::Color::Red(1.0), const std::string & box_name=\"box\") std::shared_ptr< Robot > create_box (const Eigen::Vector3d & dims, const Eigen::Vector6d & pose=Eigen::Vector6d::Zero(), const std::string & type=\"free\", double mass=1.0, const Eigen::Vector4d & color=dart::Color::Red(1.0), const std::string & box_name=\"box\") std::shared_ptr< Robot > create_ellipsoid (const Eigen::Vector3d & dims, const Eigen::Isometry3d & tf, const std::string & type=\"free\", double mass=1.0, const Eigen::Vector4d & color=dart::Color::Red(1.0), const std::string & ellipsoid_name=\"ellipsoid\") std::shared_ptr< Robot > create_ellipsoid (const Eigen::Vector3d & dims, const Eigen::Vector6d & pose=Eigen::Vector6d::Zero(), const std::string & type=\"free\", double mass=1.0, const Eigen::Vector4d & color=dart::Color::Red(1.0), const std::string & ellipsoid_name=\"ellipsoid\")"},{"location":"api/classrobot__dart_1_1robots_1_1Arm/#protected-attributes-inherited-from-robot_dartrobot","title":"Protected Attributes inherited from robot_dart::Robot","text":"

See robot_dart::Robot

Type Name std::vector< std::pair< dart::dynamics::BodyNode *, double > > _axis_shapes bool _cast_shadows std::vector< std::shared_ptr< control::RobotControl > > _controllers std::unordered_map< std::string, size_t > _dof_map bool _is_ghost std::unordered_map< std::string, size_t > _joint_map std::string _model_filename std::vector< std::pair< std::string, std::string > > _packages std::string _robot_name dart::dynamics::SkeletonPtr _skeleton"},{"location":"api/classrobot__dart_1_1robots_1_1Arm/#protected-functions-inherited-from-robot_dartrobot","title":"Protected Functions inherited from robot_dart::Robot","text":"

See robot_dart::Robot

Type Name dart::dynamics::Joint::ActuatorType _actuator_type (size_t joint_index) const std::vector< dart::dynamics::Joint::ActuatorType > _actuator_types () const std::string _get_path (const std::string & filename) const Eigen::MatrixXd _jacobian (const Eigen::MatrixXd & full_jacobian, const std::vector< std::string > & dof_names) const dart::dynamics::SkeletonPtr _load_model (const std::string & filename, const std::vector< std::pair< std::string, std::string > > & packages=std::vector< std::pair< std::string, std::string > >(), bool is_urdf_string=false) Eigen::MatrixXd _mass_matrix (const Eigen::MatrixXd & full_mass_matrix, const std::vector< std::string > & dof_names) const virtual void _post_addition (RobotDARTSimu *) Function called by RobotDARTSimu object when adding the robot to the world. virtual void _post_removal (RobotDARTSimu *) Function called by RobotDARTSimu object when removing the robot to the world. void _set_actuator_type (size_t joint_index, dart::dynamics::Joint::ActuatorType type, bool override_mimic=false, bool override_base=false) void _set_actuator_types (const std::vector< dart::dynamics::Joint::ActuatorType > & types, bool override_mimic=false, bool override_base=false) void _set_actuator_types (dart::dynamics::Joint::ActuatorType type, bool override_mimic=false, bool override_base=false) void _set_color_mode (dart::dynamics::MeshShape::ColorMode color_mode, dart::dynamics::SkeletonPtr skel) void _set_color_mode (dart::dynamics::MeshShape::ColorMode color_mode, dart::dynamics::ShapeNode * sn)"},{"location":"api/classrobot__dart_1_1robots_1_1Arm/#public-functions-documentation","title":"Public Functions Documentation","text":""},{"location":"api/classrobot__dart_1_1robots_1_1Arm/#function-arm","title":"function Arm","text":"
inline robot_dart::robots::Arm::Arm (\nconst std::string & urdf=\"arm.urdf\"\n) 

The documentation for this class was generated from the following file robot_dart/robots/arm.hpp

"},{"location":"api/classrobot__dart_1_1robots_1_1Franka/","title":"Class robot_dart::robots::Franka","text":"

ClassList > robot_dart > robots > Franka

Inherits the following classes: robot_dart::Robot

"},{"location":"api/classrobot__dart_1_1robots_1_1Franka/#public-functions","title":"Public Functions","text":"Type Name Franka (size_t frequency=1000, const std::string & urdf=\"franka/franka.urdf\", const std::vector< std::pair< std::string, std::string > > & packages=('franka\\_description', 'franka/franka\\_description')) const sensor::ForceTorque & ft_wrist () const"},{"location":"api/classrobot__dart_1_1robots_1_1Franka/#public-functions-inherited-from-robot_dartrobot","title":"Public Functions inherited from robot_dart::Robot","text":"

See robot_dart::Robot

Type Name Robot (const std::string & model_file, const std::vector< std::pair< std::string, std::string > > & packages, const std::string & robot_name=\"robot\", bool is_urdf_string=false, bool cast_shadows=true) Robot (const std::string & model_file, const std::string & robot_name=\"robot\", bool is_urdf_string=false, bool cast_shadows=true) Robot (dart::dynamics::SkeletonPtr skeleton, const std::string & robot_name=\"robot\", bool cast_shadows=true) Eigen::VectorXd acceleration_lower_limits (const std::vector< std::string > & dof_names={}) const Eigen::VectorXd acceleration_upper_limits (const std::vector< std::string > & dof_names={}) const Eigen::VectorXd accelerations (const std::vector< std::string > & dof_names={}) const std::vector< std::shared_ptr< control::RobotControl > > active_controllers () const std::string actuator_type (const std::string & joint_name) const std::vector< std::string > actuator_types (const std::vector< std::string > & joint_names={}) const void add_body_mass (const std::string & body_name, double mass) void add_body_mass (size_t body_index, double mass) void add_controller (const std::shared_ptr< control::RobotControl > & controller, double weight=1.0) void add_external_force (const std::string & body_name, const Eigen::Vector3d & force, const Eigen::Vector3d & offset=Eigen::Vector3d::Zero(), bool force_local=false, bool offset_local=true) void add_external_force (size_t body_index, const Eigen::Vector3d & force, const Eigen::Vector3d & offset=Eigen::Vector3d::Zero(), bool force_local=false, bool offset_local=true) void add_external_torque (const std::string & body_name, const Eigen::Vector3d & torque, bool local=false) void add_external_torque (size_t body_index, const Eigen::Vector3d & torque, bool local=false) bool adjacent_colliding () const Eigen::MatrixXd aug_mass_matrix (const std::vector< std::string > & dof_names={}) const Eigen::Isometry3d base_pose () const Eigen::Vector6d base_pose_vec () const Eigen::Vector6d body_acceleration (const std::string & body_name) const Eigen::Vector6d body_acceleration (size_t body_index) const size_t body_index (const std::string & body_name) const double body_mass (const std::string & body_name) const double body_mass (size_t body_index) const std::string body_name (size_t body_index) const std::vector< std::string > body_names () const dart::dynamics::BodyNode * body_node (const std::string & body_name) dart::dynamics::BodyNode * body_node (size_t body_index) Eigen::Isometry3d body_pose (const std::string & body_name) const Eigen::Isometry3d body_pose (size_t body_index) const Eigen::Vector6d body_pose_vec (const std::string & body_name) const Eigen::Vector6d body_pose_vec (size_t body_index) const Eigen::Vector6d body_velocity (const std::string & body_name) const Eigen::Vector6d body_velocity (size_t body_index) const bool cast_shadows () const void clear_controllers () void clear_external_forces () void clear_internal_forces () std::shared_ptr< Robot > clone () const std::shared_ptr< Robot > clone_ghost (const std::string & ghost_name=\"ghost\", const Eigen::Vector4d & ghost_color={0.3, 0.3, 0.3, 0.7}) const Eigen::Vector3d com () const Eigen::Vector6d com_acceleration () const Eigen::MatrixXd com_jacobian (const std::vector< std::string > & dof_names={}) const Eigen::MatrixXd com_jacobian_deriv (const std::vector< std::string > & dof_names={}) const Eigen::Vector6d com_velocity () const Eigen::VectorXd commands (const std::vector< std::string > & dof_names={}) const Eigen::VectorXd constraint_forces (const std::vector< std::string > & dof_names={}) const std::shared_ptr< control::RobotControl > controller (size_t index) const std::vector< std::shared_ptr< control::RobotControl > > controllers () const Eigen::VectorXd coriolis_forces (const std::vector< std::string > & dof_names={}) const Eigen::VectorXd coriolis_gravity_forces (const std::vector< std::string > & dof_names={}) const std::vector< double > coulomb_coeffs (const std::vector< std::string > & dof_names={}) const std::vector< double > damping_coeffs (const std::vector< std::string > & dof_names={}) const dart::dynamics::DegreeOfFreedom * dof (const std::string & dof_name) dart::dynamics::DegreeOfFreedom * dof (size_t dof_index) size_t dof_index (const std::string & dof_name) const const std::unordered_map< std::string, size_t > & dof_map () const std::string dof_name (size_t dof_index) const std::vector< std::string > dof_names (bool filter_mimics=false, bool filter_locked=false, bool filter_passive=false) const const std::vector< std::pair< dart::dynamics::BodyNode *, double > > & drawing_axes () const Eigen::Vector6d external_forces (const std::string & body_name) const Eigen::Vector6d external_forces (size_t body_index) const void fix_to_world () bool fixed () const Eigen::VectorXd force_lower_limits (const std::vector< std::string > & dof_names={}) const void force_position_bounds () std::pair< Eigen::Vector6d, Eigen::Vector6d > force_torque (size_t joint_index) const Eigen::VectorXd force_upper_limits (const std::vector< std::string > & dof_names={}) const Eigen::VectorXd forces (const std::vector< std::string > & dof_names={}) const bool free () const void free_from_world (const Eigen::Vector6d & pose=Eigen::Vector6d::Zero()) double friction_coeff (const std::string & body_name) double friction_coeff (size_t body_index) Eigen::Vector3d friction_dir (const std::string & body_name) Eigen::Vector3d friction_dir (size_t body_index) bool ghost () const Eigen::VectorXd gravity_forces (const std::vector< std::string > & dof_names={}) const Eigen::MatrixXd inv_aug_mass_matrix (const std::vector< std::string > & dof_names={}) const Eigen::MatrixXd inv_mass_matrix (const std::vector< std::string > & dof_names={}) const Eigen::MatrixXd jacobian (const std::string & body_name, const std::vector< std::string > & dof_names={}) const Eigen::MatrixXd jacobian_deriv (const std::string & body_name, const std::vector< std::string > & dof_names={}) const dart::dynamics::Joint * joint (const std::string & joint_name) dart::dynamics::Joint * joint (size_t joint_index) size_t joint_index (const std::string & joint_name) const const std::unordered_map< std::string, size_t > & joint_map () const std::string joint_name (size_t joint_index) const std::vector< std::string > joint_names () const std::vector< std::string > locked_dof_names () const Eigen::MatrixXd mass_matrix (const std::vector< std::string > & dof_names={}) const std::vector< std::string > mimic_dof_names () const const std::string & model_filename () const const std::vector< std::pair< std::string, std::string > > & model_packages () const const std::string & name () const size_t num_bodies () const size_t num_controllers () const size_t num_dofs () const size_t num_joints () const std::vector< std::string > passive_dof_names () const std::vector< bool > position_enforced (const std::vector< std::string > & dof_names={}) const Eigen::VectorXd position_lower_limits (const std::vector< std::string > & dof_names={}) const Eigen::VectorXd position_upper_limits (const std::vector< std::string > & dof_names={}) const Eigen::VectorXd positions (const std::vector< std::string > & dof_names={}) const void reinit_controllers () void remove_all_drawing_axis () void remove_controller (const std::shared_ptr< control::RobotControl > & controller) void remove_controller (size_t index) virtual void reset () void reset_commands () double restitution_coeff (const std::string & body_name) double restitution_coeff (size_t body_index) double secondary_friction_coeff (const std::string & body_name) double secondary_friction_coeff (size_t body_index) bool self_colliding () const void set_acceleration_lower_limits (const Eigen::VectorXd & accelerations, const std::vector< std::string > & dof_names={}) void set_acceleration_upper_limits (const Eigen::VectorXd & accelerations, const std::vector< std::string > & dof_names={}) void set_accelerations (const Eigen::VectorXd & accelerations, const std::vector< std::string > & dof_names={}) void set_actuator_type (const std::string & type, const std::string & joint_name, bool override_mimic=false, bool override_base=false) void set_actuator_types (const std::string & type, const std::vector< std::string > & joint_names={}, bool override_mimic=false, bool override_base=false) void set_base_pose (const Eigen::Isometry3d & tf) void set_base_pose (const Eigen::Vector6d & pose) set base pose: pose is a 6D vector (first 3D orientation in angle-axis and last 3D translation) void set_body_mass (const std::string & body_name, double mass) void set_body_mass (size_t body_index, double mass) void set_body_name (size_t body_index, const std::string & body_name) void set_cast_shadows (bool cast_shadows=true) void set_color_mode (const std::string & color_mode) void set_color_mode (const std::string & color_mode, const std::string & body_name) void set_commands (const Eigen::VectorXd & commands, const std::vector< std::string > & dof_names={}) void set_coulomb_coeffs (const std::vector< double > & cfrictions, const std::vector< std::string > & dof_names={}) void set_coulomb_coeffs (double cfriction, const std::vector< std::string > & dof_names={}) void set_damping_coeffs (const std::vector< double > & damps, const std::vector< std::string > & dof_names={}) void set_damping_coeffs (double damp, const std::vector< std::string > & dof_names={}) void set_draw_axis (const std::string & body_name, double size=0.25) void set_external_force (const std::string & body_name, const Eigen::Vector3d & force, const Eigen::Vector3d & offset=Eigen::Vector3d::Zero(), bool force_local=false, bool offset_local=true) void set_external_force (size_t body_index, const Eigen::Vector3d & force, const Eigen::Vector3d & offset=Eigen::Vector3d::Zero(), bool force_local=false, bool offset_local=true) void set_external_torque (const std::string & body_name, const Eigen::Vector3d & torque, bool local=false) void set_external_torque (size_t body_index, const Eigen::Vector3d & torque, bool local=false) void set_force_lower_limits (const Eigen::VectorXd & forces, const std::vector< std::string > & dof_names={}) void set_force_upper_limits (const Eigen::VectorXd & forces, const std::vector< std::string > & dof_names={}) void set_forces (const Eigen::VectorXd & forces, const std::vector< std::string > & dof_names={}) void set_friction_coeff (const std::string & body_name, double value) void set_friction_coeff (size_t body_index, double value) void set_friction_coeffs (double value) void set_friction_dir (const std::string & body_name, const Eigen::Vector3d & direction) void set_friction_dir (size_t body_index, const Eigen::Vector3d & direction) void set_ghost (bool ghost=true) void set_joint_name (size_t joint_index, const std::string & joint_name) void set_mimic (const std::string & joint_name, const std::string & mimic_joint_name, double multiplier=1., double offset=0.) void set_position_enforced (const std::vector< bool > & enforced, const std::vector< std::string > & dof_names={}) void set_position_enforced (bool enforced, const std::vector< std::string > & dof_names={}) void set_position_lower_limits (const Eigen::VectorXd & positions, const std::vector< std::string > & dof_names={}) void set_position_upper_limits (const Eigen::VectorXd & positions, const std::vector< std::string > & dof_names={}) void set_positions (const Eigen::VectorXd & positions, const std::vector< std::string > & dof_names={}) void set_restitution_coeff (const std::string & body_name, double value) void set_restitution_coeff (size_t body_index, double value) void set_restitution_coeffs (double value) void set_secondary_friction_coeff (const std::string & body_name, double value) void set_secondary_friction_coeff (size_t body_index, double value) void set_secondary_friction_coeffs (double value) void set_self_collision (bool enable_self_collisions=true, bool enable_adjacent_collisions=false) void set_spring_stiffnesses (const std::vector< double > & stiffnesses, const std::vector< std::string > & dof_names={}) void set_spring_stiffnesses (double stiffness, const std::vector< std::string > & dof_names={}) void set_velocities (const Eigen::VectorXd & velocities, const std::vector< std::string > & dof_names={}) void set_velocity_lower_limits (const Eigen::VectorXd & velocities, const std::vector< std::string > & dof_names={}) void set_velocity_upper_limits (const Eigen::VectorXd & velocities, const std::vector< std::string > & dof_names={}) dart::dynamics::SkeletonPtr skeleton () std::vector< double > spring_stiffnesses (const std::vector< std::string > & dof_names={}) const void update (double t) void update_joint_dof_maps () Eigen::VectorXd vec_dof (const Eigen::VectorXd & vec, const std::vector< std::string > & dof_names) const Eigen::VectorXd velocities (const std::vector< std::string > & dof_names={}) const Eigen::VectorXd velocity_lower_limits (const std::vector< std::string > & dof_names={}) const Eigen::VectorXd velocity_upper_limits (const std::vector< std::string > & dof_names={}) const virtual ~Robot ()"},{"location":"api/classrobot__dart_1_1robots_1_1Franka/#public-static-functions-inherited-from-robot_dartrobot","title":"Public Static Functions inherited from robot_dart::Robot","text":"

See robot_dart::Robot

Type Name std::shared_ptr< Robot > create_box (const Eigen::Vector3d & dims, const Eigen::Isometry3d & tf, const std::string & type=\"free\", double mass=1.0, const Eigen::Vector4d & color=dart::Color::Red(1.0), const std::string & box_name=\"box\") std::shared_ptr< Robot > create_box (const Eigen::Vector3d & dims, const Eigen::Vector6d & pose=Eigen::Vector6d::Zero(), const std::string & type=\"free\", double mass=1.0, const Eigen::Vector4d & color=dart::Color::Red(1.0), const std::string & box_name=\"box\") std::shared_ptr< Robot > create_ellipsoid (const Eigen::Vector3d & dims, const Eigen::Isometry3d & tf, const std::string & type=\"free\", double mass=1.0, const Eigen::Vector4d & color=dart::Color::Red(1.0), const std::string & ellipsoid_name=\"ellipsoid\") std::shared_ptr< Robot > create_ellipsoid (const Eigen::Vector3d & dims, const Eigen::Vector6d & pose=Eigen::Vector6d::Zero(), const std::string & type=\"free\", double mass=1.0, const Eigen::Vector4d & color=dart::Color::Red(1.0), const std::string & ellipsoid_name=\"ellipsoid\")"},{"location":"api/classrobot__dart_1_1robots_1_1Franka/#protected-attributes","title":"Protected Attributes","text":"Type Name std::shared_ptr< sensor::ForceTorque > _ft_wrist"},{"location":"api/classrobot__dart_1_1robots_1_1Franka/#protected-attributes-inherited-from-robot_dartrobot","title":"Protected Attributes inherited from robot_dart::Robot","text":"

See robot_dart::Robot

Type Name std::vector< std::pair< dart::dynamics::BodyNode *, double > > _axis_shapes bool _cast_shadows std::vector< std::shared_ptr< control::RobotControl > > _controllers std::unordered_map< std::string, size_t > _dof_map bool _is_ghost std::unordered_map< std::string, size_t > _joint_map std::string _model_filename std::vector< std::pair< std::string, std::string > > _packages std::string _robot_name dart::dynamics::SkeletonPtr _skeleton"},{"location":"api/classrobot__dart_1_1robots_1_1Franka/#protected-functions","title":"Protected Functions","text":"Type Name virtual void _post_addition (RobotDARTSimu *) overrideFunction called by RobotDARTSimu object when adding the robot to the world. virtual void _post_removal (RobotDARTSimu *) overrideFunction called by RobotDARTSimu object when removing the robot to the world."},{"location":"api/classrobot__dart_1_1robots_1_1Franka/#protected-functions-inherited-from-robot_dartrobot","title":"Protected Functions inherited from robot_dart::Robot","text":"

See robot_dart::Robot

Type Name dart::dynamics::Joint::ActuatorType _actuator_type (size_t joint_index) const std::vector< dart::dynamics::Joint::ActuatorType > _actuator_types () const std::string _get_path (const std::string & filename) const Eigen::MatrixXd _jacobian (const Eigen::MatrixXd & full_jacobian, const std::vector< std::string > & dof_names) const dart::dynamics::SkeletonPtr _load_model (const std::string & filename, const std::vector< std::pair< std::string, std::string > > & packages=std::vector< std::pair< std::string, std::string > >(), bool is_urdf_string=false) Eigen::MatrixXd _mass_matrix (const Eigen::MatrixXd & full_mass_matrix, const std::vector< std::string > & dof_names) const virtual void _post_addition (RobotDARTSimu *) Function called by RobotDARTSimu object when adding the robot to the world. virtual void _post_removal (RobotDARTSimu *) Function called by RobotDARTSimu object when removing the robot to the world. void _set_actuator_type (size_t joint_index, dart::dynamics::Joint::ActuatorType type, bool override_mimic=false, bool override_base=false) void _set_actuator_types (const std::vector< dart::dynamics::Joint::ActuatorType > & types, bool override_mimic=false, bool override_base=false) void _set_actuator_types (dart::dynamics::Joint::ActuatorType type, bool override_mimic=false, bool override_base=false) void _set_color_mode (dart::dynamics::MeshShape::ColorMode color_mode, dart::dynamics::SkeletonPtr skel) void _set_color_mode (dart::dynamics::MeshShape::ColorMode color_mode, dart::dynamics::ShapeNode * sn)"},{"location":"api/classrobot__dart_1_1robots_1_1Franka/#public-functions-documentation","title":"Public Functions Documentation","text":""},{"location":"api/classrobot__dart_1_1robots_1_1Franka/#function-franka","title":"function Franka","text":"
robot_dart::robots::Franka::Franka (\nsize_t frequency=1000,\nconst std::string & urdf=\"franka/franka.urdf\",\nconst std::vector< std::pair< std::string, std::string > > & packages=('franka_description', 'franka/franka_description')\n) 
"},{"location":"api/classrobot__dart_1_1robots_1_1Franka/#function-ft_wrist","title":"function ft_wrist","text":"
inline const sensor::ForceTorque & robot_dart::robots::Franka::ft_wrist () const\n
"},{"location":"api/classrobot__dart_1_1robots_1_1Franka/#protected-attributes-documentation","title":"Protected Attributes Documentation","text":""},{"location":"api/classrobot__dart_1_1robots_1_1Franka/#variable-_ft_wrist","title":"variable _ft_wrist","text":"
std::shared_ptr<sensor::ForceTorque> robot_dart::robots::Franka::_ft_wrist;\n
"},{"location":"api/classrobot__dart_1_1robots_1_1Franka/#protected-functions-documentation","title":"Protected Functions Documentation","text":""},{"location":"api/classrobot__dart_1_1robots_1_1Franka/#function-_post_addition","title":"function _post_addition","text":"
virtual void robot_dart::robots::Franka::_post_addition (\nRobotDARTSimu *\n) override\n

Implements robot_dart::Robot::_post_addition

"},{"location":"api/classrobot__dart_1_1robots_1_1Franka/#function-_post_removal","title":"function _post_removal","text":"
virtual void robot_dart::robots::Franka::_post_removal (\nRobotDARTSimu *\n) override\n

Implements robot_dart::Robot::_post_removal

The documentation for this class was generated from the following file robot_dart/robots/franka.hpp

"},{"location":"api/classrobot__dart_1_1robots_1_1Hexapod/","title":"Class robot_dart::robots::Hexapod","text":"

ClassList > robot_dart > robots > Hexapod

Inherits the following classes: robot_dart::Robot

"},{"location":"api/classrobot__dart_1_1robots_1_1Hexapod/#public-functions","title":"Public Functions","text":"Type Name Hexapod (const std::string & urdf=\"pexod.urdf\") virtual void reset () override"},{"location":"api/classrobot__dart_1_1robots_1_1Hexapod/#public-functions-inherited-from-robot_dartrobot","title":"Public Functions inherited from robot_dart::Robot","text":"

See robot_dart::Robot

Type Name Robot (const std::string & model_file, const std::vector< std::pair< std::string, std::string > > & packages, const std::string & robot_name=\"robot\", bool is_urdf_string=false, bool cast_shadows=true) Robot (const std::string & model_file, const std::string & robot_name=\"robot\", bool is_urdf_string=false, bool cast_shadows=true) Robot (dart::dynamics::SkeletonPtr skeleton, const std::string & robot_name=\"robot\", bool cast_shadows=true) Eigen::VectorXd acceleration_lower_limits (const std::vector< std::string > & dof_names={}) const Eigen::VectorXd acceleration_upper_limits (const std::vector< std::string > & dof_names={}) const Eigen::VectorXd accelerations (const std::vector< std::string > & dof_names={}) const std::vector< std::shared_ptr< control::RobotControl > > active_controllers () const std::string actuator_type (const std::string & joint_name) const std::vector< std::string > actuator_types (const std::vector< std::string > & joint_names={}) const void add_body_mass (const std::string & body_name, double mass) void add_body_mass (size_t body_index, double mass) void add_controller (const std::shared_ptr< control::RobotControl > & controller, double weight=1.0) void add_external_force (const std::string & body_name, const Eigen::Vector3d & force, const Eigen::Vector3d & offset=Eigen::Vector3d::Zero(), bool force_local=false, bool offset_local=true) void add_external_force (size_t body_index, const Eigen::Vector3d & force, const Eigen::Vector3d & offset=Eigen::Vector3d::Zero(), bool force_local=false, bool offset_local=true) void add_external_torque (const std::string & body_name, const Eigen::Vector3d & torque, bool local=false) void add_external_torque (size_t body_index, const Eigen::Vector3d & torque, bool local=false) bool adjacent_colliding () const Eigen::MatrixXd aug_mass_matrix (const std::vector< std::string > & dof_names={}) const Eigen::Isometry3d base_pose () const Eigen::Vector6d base_pose_vec () const Eigen::Vector6d body_acceleration (const std::string & body_name) const Eigen::Vector6d body_acceleration (size_t body_index) const size_t body_index (const std::string & body_name) const double body_mass (const std::string & body_name) const double body_mass (size_t body_index) const std::string body_name (size_t body_index) const std::vector< std::string > body_names () const dart::dynamics::BodyNode * body_node (const std::string & body_name) dart::dynamics::BodyNode * body_node (size_t body_index) Eigen::Isometry3d body_pose (const std::string & body_name) const Eigen::Isometry3d body_pose (size_t body_index) const Eigen::Vector6d body_pose_vec (const std::string & body_name) const Eigen::Vector6d body_pose_vec (size_t body_index) const Eigen::Vector6d body_velocity (const std::string & body_name) const Eigen::Vector6d body_velocity (size_t body_index) const bool cast_shadows () const void clear_controllers () void clear_external_forces () void clear_internal_forces () std::shared_ptr< Robot > clone () const std::shared_ptr< Robot > clone_ghost (const std::string & ghost_name=\"ghost\", const Eigen::Vector4d & ghost_color={0.3, 0.3, 0.3, 0.7}) const Eigen::Vector3d com () const Eigen::Vector6d com_acceleration () const Eigen::MatrixXd com_jacobian (const std::vector< std::string > & dof_names={}) const Eigen::MatrixXd com_jacobian_deriv (const std::vector< std::string > & dof_names={}) const Eigen::Vector6d com_velocity () const Eigen::VectorXd commands (const std::vector< std::string > & dof_names={}) const Eigen::VectorXd constraint_forces (const std::vector< std::string > & dof_names={}) const std::shared_ptr< control::RobotControl > controller (size_t index) const std::vector< std::shared_ptr< control::RobotControl > > controllers () const Eigen::VectorXd coriolis_forces (const std::vector< std::string > & dof_names={}) const Eigen::VectorXd coriolis_gravity_forces (const std::vector< std::string > & dof_names={}) const std::vector< double > coulomb_coeffs (const std::vector< std::string > & dof_names={}) const std::vector< double > damping_coeffs (const std::vector< std::string > & dof_names={}) const dart::dynamics::DegreeOfFreedom * dof (const std::string & dof_name) dart::dynamics::DegreeOfFreedom * dof (size_t dof_index) size_t dof_index (const std::string & dof_name) const const std::unordered_map< std::string, size_t > & dof_map () const std::string dof_name (size_t dof_index) const std::vector< std::string > dof_names (bool filter_mimics=false, bool filter_locked=false, bool filter_passive=false) const const std::vector< std::pair< dart::dynamics::BodyNode *, double > > & drawing_axes () const Eigen::Vector6d external_forces (const std::string & body_name) const Eigen::Vector6d external_forces (size_t body_index) const void fix_to_world () bool fixed () const Eigen::VectorXd force_lower_limits (const std::vector< std::string > & dof_names={}) const void force_position_bounds () std::pair< Eigen::Vector6d, Eigen::Vector6d > force_torque (size_t joint_index) const Eigen::VectorXd force_upper_limits (const std::vector< std::string > & dof_names={}) const Eigen::VectorXd forces (const std::vector< std::string > & dof_names={}) const bool free () const void free_from_world (const Eigen::Vector6d & pose=Eigen::Vector6d::Zero()) double friction_coeff (const std::string & body_name) double friction_coeff (size_t body_index) Eigen::Vector3d friction_dir (const std::string & body_name) Eigen::Vector3d friction_dir (size_t body_index) bool ghost () const Eigen::VectorXd gravity_forces (const std::vector< std::string > & dof_names={}) const Eigen::MatrixXd inv_aug_mass_matrix (const std::vector< std::string > & dof_names={}) const Eigen::MatrixXd inv_mass_matrix (const std::vector< std::string > & dof_names={}) const Eigen::MatrixXd jacobian (const std::string & body_name, const std::vector< std::string > & dof_names={}) const Eigen::MatrixXd jacobian_deriv (const std::string & body_name, const std::vector< std::string > & dof_names={}) const dart::dynamics::Joint * joint (const std::string & joint_name) dart::dynamics::Joint * joint (size_t joint_index) size_t joint_index (const std::string & joint_name) const const std::unordered_map< std::string, size_t > & joint_map () const std::string joint_name (size_t joint_index) const std::vector< std::string > joint_names () const std::vector< std::string > locked_dof_names () const Eigen::MatrixXd mass_matrix (const std::vector< std::string > & dof_names={}) const std::vector< std::string > mimic_dof_names () const const std::string & model_filename () const const std::vector< std::pair< std::string, std::string > > & model_packages () const const std::string & name () const size_t num_bodies () const size_t num_controllers () const size_t num_dofs () const size_t num_joints () const std::vector< std::string > passive_dof_names () const std::vector< bool > position_enforced (const std::vector< std::string > & dof_names={}) const Eigen::VectorXd position_lower_limits (const std::vector< std::string > & dof_names={}) const Eigen::VectorXd position_upper_limits (const std::vector< std::string > & dof_names={}) const Eigen::VectorXd positions (const std::vector< std::string > & dof_names={}) const void reinit_controllers () void remove_all_drawing_axis () void remove_controller (const std::shared_ptr< control::RobotControl > & controller) void remove_controller (size_t index) virtual void reset () void reset_commands () double restitution_coeff (const std::string & body_name) double restitution_coeff (size_t body_index) double secondary_friction_coeff (const std::string & body_name) double secondary_friction_coeff (size_t body_index) bool self_colliding () const void set_acceleration_lower_limits (const Eigen::VectorXd & accelerations, const std::vector< std::string > & dof_names={}) void set_acceleration_upper_limits (const Eigen::VectorXd & accelerations, const std::vector< std::string > & dof_names={}) void set_accelerations (const Eigen::VectorXd & accelerations, const std::vector< std::string > & dof_names={}) void set_actuator_type (const std::string & type, const std::string & joint_name, bool override_mimic=false, bool override_base=false) void set_actuator_types (const std::string & type, const std::vector< std::string > & joint_names={}, bool override_mimic=false, bool override_base=false) void set_base_pose (const Eigen::Isometry3d & tf) void set_base_pose (const Eigen::Vector6d & pose) set base pose: pose is a 6D vector (first 3D orientation in angle-axis and last 3D translation) void set_body_mass (const std::string & body_name, double mass) void set_body_mass (size_t body_index, double mass) void set_body_name (size_t body_index, const std::string & body_name) void set_cast_shadows (bool cast_shadows=true) void set_color_mode (const std::string & color_mode) void set_color_mode (const std::string & color_mode, const std::string & body_name) void set_commands (const Eigen::VectorXd & commands, const std::vector< std::string > & dof_names={}) void set_coulomb_coeffs (const std::vector< double > & cfrictions, const std::vector< std::string > & dof_names={}) void set_coulomb_coeffs (double cfriction, const std::vector< std::string > & dof_names={}) void set_damping_coeffs (const std::vector< double > & damps, const std::vector< std::string > & dof_names={}) void set_damping_coeffs (double damp, const std::vector< std::string > & dof_names={}) void set_draw_axis (const std::string & body_name, double size=0.25) void set_external_force (const std::string & body_name, const Eigen::Vector3d & force, const Eigen::Vector3d & offset=Eigen::Vector3d::Zero(), bool force_local=false, bool offset_local=true) void set_external_force (size_t body_index, const Eigen::Vector3d & force, const Eigen::Vector3d & offset=Eigen::Vector3d::Zero(), bool force_local=false, bool offset_local=true) void set_external_torque (const std::string & body_name, const Eigen::Vector3d & torque, bool local=false) void set_external_torque (size_t body_index, const Eigen::Vector3d & torque, bool local=false) void set_force_lower_limits (const Eigen::VectorXd & forces, const std::vector< std::string > & dof_names={}) void set_force_upper_limits (const Eigen::VectorXd & forces, const std::vector< std::string > & dof_names={}) void set_forces (const Eigen::VectorXd & forces, const std::vector< std::string > & dof_names={}) void set_friction_coeff (const std::string & body_name, double value) void set_friction_coeff (size_t body_index, double value) void set_friction_coeffs (double value) void set_friction_dir (const std::string & body_name, const Eigen::Vector3d & direction) void set_friction_dir (size_t body_index, const Eigen::Vector3d & direction) void set_ghost (bool ghost=true) void set_joint_name (size_t joint_index, const std::string & joint_name) void set_mimic (const std::string & joint_name, const std::string & mimic_joint_name, double multiplier=1., double offset=0.) void set_position_enforced (const std::vector< bool > & enforced, const std::vector< std::string > & dof_names={}) void set_position_enforced (bool enforced, const std::vector< std::string > & dof_names={}) void set_position_lower_limits (const Eigen::VectorXd & positions, const std::vector< std::string > & dof_names={}) void set_position_upper_limits (const Eigen::VectorXd & positions, const std::vector< std::string > & dof_names={}) void set_positions (const Eigen::VectorXd & positions, const std::vector< std::string > & dof_names={}) void set_restitution_coeff (const std::string & body_name, double value) void set_restitution_coeff (size_t body_index, double value) void set_restitution_coeffs (double value) void set_secondary_friction_coeff (const std::string & body_name, double value) void set_secondary_friction_coeff (size_t body_index, double value) void set_secondary_friction_coeffs (double value) void set_self_collision (bool enable_self_collisions=true, bool enable_adjacent_collisions=false) void set_spring_stiffnesses (const std::vector< double > & stiffnesses, const std::vector< std::string > & dof_names={}) void set_spring_stiffnesses (double stiffness, const std::vector< std::string > & dof_names={}) void set_velocities (const Eigen::VectorXd & velocities, const std::vector< std::string > & dof_names={}) void set_velocity_lower_limits (const Eigen::VectorXd & velocities, const std::vector< std::string > & dof_names={}) void set_velocity_upper_limits (const Eigen::VectorXd & velocities, const std::vector< std::string > & dof_names={}) dart::dynamics::SkeletonPtr skeleton () std::vector< double > spring_stiffnesses (const std::vector< std::string > & dof_names={}) const void update (double t) void update_joint_dof_maps () Eigen::VectorXd vec_dof (const Eigen::VectorXd & vec, const std::vector< std::string > & dof_names) const Eigen::VectorXd velocities (const std::vector< std::string > & dof_names={}) const Eigen::VectorXd velocity_lower_limits (const std::vector< std::string > & dof_names={}) const Eigen::VectorXd velocity_upper_limits (const std::vector< std::string > & dof_names={}) const virtual ~Robot ()"},{"location":"api/classrobot__dart_1_1robots_1_1Hexapod/#public-static-functions-inherited-from-robot_dartrobot","title":"Public Static Functions inherited from robot_dart::Robot","text":"

See robot_dart::Robot

Type Name std::shared_ptr< Robot > create_box (const Eigen::Vector3d & dims, const Eigen::Isometry3d & tf, const std::string & type=\"free\", double mass=1.0, const Eigen::Vector4d & color=dart::Color::Red(1.0), const std::string & box_name=\"box\") std::shared_ptr< Robot > create_box (const Eigen::Vector3d & dims, const Eigen::Vector6d & pose=Eigen::Vector6d::Zero(), const std::string & type=\"free\", double mass=1.0, const Eigen::Vector4d & color=dart::Color::Red(1.0), const std::string & box_name=\"box\") std::shared_ptr< Robot > create_ellipsoid (const Eigen::Vector3d & dims, const Eigen::Isometry3d & tf, const std::string & type=\"free\", double mass=1.0, const Eigen::Vector4d & color=dart::Color::Red(1.0), const std::string & ellipsoid_name=\"ellipsoid\") std::shared_ptr< Robot > create_ellipsoid (const Eigen::Vector3d & dims, const Eigen::Vector6d & pose=Eigen::Vector6d::Zero(), const std::string & type=\"free\", double mass=1.0, const Eigen::Vector4d & color=dart::Color::Red(1.0), const std::string & ellipsoid_name=\"ellipsoid\")"},{"location":"api/classrobot__dart_1_1robots_1_1Hexapod/#protected-attributes-inherited-from-robot_dartrobot","title":"Protected Attributes inherited from robot_dart::Robot","text":"

See robot_dart::Robot

Type Name std::vector< std::pair< dart::dynamics::BodyNode *, double > > _axis_shapes bool _cast_shadows std::vector< std::shared_ptr< control::RobotControl > > _controllers std::unordered_map< std::string, size_t > _dof_map bool _is_ghost std::unordered_map< std::string, size_t > _joint_map std::string _model_filename std::vector< std::pair< std::string, std::string > > _packages std::string _robot_name dart::dynamics::SkeletonPtr _skeleton"},{"location":"api/classrobot__dart_1_1robots_1_1Hexapod/#protected-functions-inherited-from-robot_dartrobot","title":"Protected Functions inherited from robot_dart::Robot","text":"

See robot_dart::Robot

Type Name dart::dynamics::Joint::ActuatorType _actuator_type (size_t joint_index) const std::vector< dart::dynamics::Joint::ActuatorType > _actuator_types () const std::string _get_path (const std::string & filename) const Eigen::MatrixXd _jacobian (const Eigen::MatrixXd & full_jacobian, const std::vector< std::string > & dof_names) const dart::dynamics::SkeletonPtr _load_model (const std::string & filename, const std::vector< std::pair< std::string, std::string > > & packages=std::vector< std::pair< std::string, std::string > >(), bool is_urdf_string=false) Eigen::MatrixXd _mass_matrix (const Eigen::MatrixXd & full_mass_matrix, const std::vector< std::string > & dof_names) const virtual void _post_addition (RobotDARTSimu *) Function called by RobotDARTSimu object when adding the robot to the world. virtual void _post_removal (RobotDARTSimu *) Function called by RobotDARTSimu object when removing the robot to the world. void _set_actuator_type (size_t joint_index, dart::dynamics::Joint::ActuatorType type, bool override_mimic=false, bool override_base=false) void _set_actuator_types (const std::vector< dart::dynamics::Joint::ActuatorType > & types, bool override_mimic=false, bool override_base=false) void _set_actuator_types (dart::dynamics::Joint::ActuatorType type, bool override_mimic=false, bool override_base=false) void _set_color_mode (dart::dynamics::MeshShape::ColorMode color_mode, dart::dynamics::SkeletonPtr skel) void _set_color_mode (dart::dynamics::MeshShape::ColorMode color_mode, dart::dynamics::ShapeNode * sn)"},{"location":"api/classrobot__dart_1_1robots_1_1Hexapod/#public-functions-documentation","title":"Public Functions Documentation","text":""},{"location":"api/classrobot__dart_1_1robots_1_1Hexapod/#function-hexapod","title":"function Hexapod","text":"
inline robot_dart::robots::Hexapod::Hexapod (\nconst std::string & urdf=\"pexod.urdf\"\n) 
"},{"location":"api/classrobot__dart_1_1robots_1_1Hexapod/#function-reset","title":"function reset","text":"
inline virtual void robot_dart::robots::Hexapod::reset () override\n

Implements robot_dart::Robot::reset

The documentation for this class was generated from the following file robot_dart/robots/hexapod.hpp

"},{"location":"api/classrobot__dart_1_1robots_1_1ICub/","title":"Class robot_dart::robots::ICub","text":"

ClassList > robot_dart > robots > ICub

Inherits the following classes: robot_dart::Robot

"},{"location":"api/classrobot__dart_1_1robots_1_1ICub/#public-functions","title":"Public Functions","text":"Type Name ICub (size_t frequency=1000, const std::string & urdf=\"icub/icub.urdf\", const std::vector< std::pair< std::string, std::string > > & packages=('icub\\_description', 'icub/icub\\_description')) const sensor::ForceTorque & ft_foot_left () const const sensor::ForceTorque & ft_foot_right () const const sensor::IMU & imu () const virtual void reset () override"},{"location":"api/classrobot__dart_1_1robots_1_1ICub/#public-functions-inherited-from-robot_dartrobot","title":"Public Functions inherited from robot_dart::Robot","text":"

See robot_dart::Robot

Type Name Robot (const std::string & model_file, const std::vector< std::pair< std::string, std::string > > & packages, const std::string & robot_name=\"robot\", bool is_urdf_string=false, bool cast_shadows=true) Robot (const std::string & model_file, const std::string & robot_name=\"robot\", bool is_urdf_string=false, bool cast_shadows=true) Robot (dart::dynamics::SkeletonPtr skeleton, const std::string & robot_name=\"robot\", bool cast_shadows=true) Eigen::VectorXd acceleration_lower_limits (const std::vector< std::string > & dof_names={}) const Eigen::VectorXd acceleration_upper_limits (const std::vector< std::string > & dof_names={}) const Eigen::VectorXd accelerations (const std::vector< std::string > & dof_names={}) const std::vector< std::shared_ptr< control::RobotControl > > active_controllers () const std::string actuator_type (const std::string & joint_name) const std::vector< std::string > actuator_types (const std::vector< std::string > & joint_names={}) const void add_body_mass (const std::string & body_name, double mass) void add_body_mass (size_t body_index, double mass) void add_controller (const std::shared_ptr< control::RobotControl > & controller, double weight=1.0) void add_external_force (const std::string & body_name, const Eigen::Vector3d & force, const Eigen::Vector3d & offset=Eigen::Vector3d::Zero(), bool force_local=false, bool offset_local=true) void add_external_force (size_t body_index, const Eigen::Vector3d & force, const Eigen::Vector3d & offset=Eigen::Vector3d::Zero(), bool force_local=false, bool offset_local=true) void add_external_torque (const std::string & body_name, const Eigen::Vector3d & torque, bool local=false) void add_external_torque (size_t body_index, const Eigen::Vector3d & torque, bool local=false) bool adjacent_colliding () const Eigen::MatrixXd aug_mass_matrix (const std::vector< std::string > & dof_names={}) const Eigen::Isometry3d base_pose () const Eigen::Vector6d base_pose_vec () const Eigen::Vector6d body_acceleration (const std::string & body_name) const Eigen::Vector6d body_acceleration (size_t body_index) const size_t body_index (const std::string & body_name) const double body_mass (const std::string & body_name) const double body_mass (size_t body_index) const std::string body_name (size_t body_index) const std::vector< std::string > body_names () const dart::dynamics::BodyNode * body_node (const std::string & body_name) dart::dynamics::BodyNode * body_node (size_t body_index) Eigen::Isometry3d body_pose (const std::string & body_name) const Eigen::Isometry3d body_pose (size_t body_index) const Eigen::Vector6d body_pose_vec (const std::string & body_name) const Eigen::Vector6d body_pose_vec (size_t body_index) const Eigen::Vector6d body_velocity (const std::string & body_name) const Eigen::Vector6d body_velocity (size_t body_index) const bool cast_shadows () const void clear_controllers () void clear_external_forces () void clear_internal_forces () std::shared_ptr< Robot > clone () const std::shared_ptr< Robot > clone_ghost (const std::string & ghost_name=\"ghost\", const Eigen::Vector4d & ghost_color={0.3, 0.3, 0.3, 0.7}) const Eigen::Vector3d com () const Eigen::Vector6d com_acceleration () const Eigen::MatrixXd com_jacobian (const std::vector< std::string > & dof_names={}) const Eigen::MatrixXd com_jacobian_deriv (const std::vector< std::string > & dof_names={}) const Eigen::Vector6d com_velocity () const Eigen::VectorXd commands (const std::vector< std::string > & dof_names={}) const Eigen::VectorXd constraint_forces (const std::vector< std::string > & dof_names={}) const std::shared_ptr< control::RobotControl > controller (size_t index) const std::vector< std::shared_ptr< control::RobotControl > > controllers () const Eigen::VectorXd coriolis_forces (const std::vector< std::string > & dof_names={}) const Eigen::VectorXd coriolis_gravity_forces (const std::vector< std::string > & dof_names={}) const std::vector< double > coulomb_coeffs (const std::vector< std::string > & dof_names={}) const std::vector< double > damping_coeffs (const std::vector< std::string > & dof_names={}) const dart::dynamics::DegreeOfFreedom * dof (const std::string & dof_name) dart::dynamics::DegreeOfFreedom * dof (size_t dof_index) size_t dof_index (const std::string & dof_name) const const std::unordered_map< std::string, size_t > & dof_map () const std::string dof_name (size_t dof_index) const std::vector< std::string > dof_names (bool filter_mimics=false, bool filter_locked=false, bool filter_passive=false) const const std::vector< std::pair< dart::dynamics::BodyNode *, double > > & drawing_axes () const Eigen::Vector6d external_forces (const std::string & body_name) const Eigen::Vector6d external_forces (size_t body_index) const void fix_to_world () bool fixed () const Eigen::VectorXd force_lower_limits (const std::vector< std::string > & dof_names={}) const void force_position_bounds () std::pair< Eigen::Vector6d, Eigen::Vector6d > force_torque (size_t joint_index) const Eigen::VectorXd force_upper_limits (const std::vector< std::string > & dof_names={}) const Eigen::VectorXd forces (const std::vector< std::string > & dof_names={}) const bool free () const void free_from_world (const Eigen::Vector6d & pose=Eigen::Vector6d::Zero()) double friction_coeff (const std::string & body_name) double friction_coeff (size_t body_index) Eigen::Vector3d friction_dir (const std::string & body_name) Eigen::Vector3d friction_dir (size_t body_index) bool ghost () const Eigen::VectorXd gravity_forces (const std::vector< std::string > & dof_names={}) const Eigen::MatrixXd inv_aug_mass_matrix (const std::vector< std::string > & dof_names={}) const Eigen::MatrixXd inv_mass_matrix (const std::vector< std::string > & dof_names={}) const Eigen::MatrixXd jacobian (const std::string & body_name, const std::vector< std::string > & dof_names={}) const Eigen::MatrixXd jacobian_deriv (const std::string & body_name, const std::vector< std::string > & dof_names={}) const dart::dynamics::Joint * joint (const std::string & joint_name) dart::dynamics::Joint * joint (size_t joint_index) size_t joint_index (const std::string & joint_name) const const std::unordered_map< std::string, size_t > & joint_map () const std::string joint_name (size_t joint_index) const std::vector< std::string > joint_names () const std::vector< std::string > locked_dof_names () const Eigen::MatrixXd mass_matrix (const std::vector< std::string > & dof_names={}) const std::vector< std::string > mimic_dof_names () const const std::string & model_filename () const const std::vector< std::pair< std::string, std::string > > & model_packages () const const std::string & name () const size_t num_bodies () const size_t num_controllers () const size_t num_dofs () const size_t num_joints () const std::vector< std::string > passive_dof_names () const std::vector< bool > position_enforced (const std::vector< std::string > & dof_names={}) const Eigen::VectorXd position_lower_limits (const std::vector< std::string > & dof_names={}) const Eigen::VectorXd position_upper_limits (const std::vector< std::string > & dof_names={}) const Eigen::VectorXd positions (const std::vector< std::string > & dof_names={}) const void reinit_controllers () void remove_all_drawing_axis () void remove_controller (const std::shared_ptr< control::RobotControl > & controller) void remove_controller (size_t index) virtual void reset () void reset_commands () double restitution_coeff (const std::string & body_name) double restitution_coeff (size_t body_index) double secondary_friction_coeff (const std::string & body_name) double secondary_friction_coeff (size_t body_index) bool self_colliding () const void set_acceleration_lower_limits (const Eigen::VectorXd & accelerations, const std::vector< std::string > & dof_names={}) void set_acceleration_upper_limits (const Eigen::VectorXd & accelerations, const std::vector< std::string > & dof_names={}) void set_accelerations (const Eigen::VectorXd & accelerations, const std::vector< std::string > & dof_names={}) void set_actuator_type (const std::string & type, const std::string & joint_name, bool override_mimic=false, bool override_base=false) void set_actuator_types (const std::string & type, const std::vector< std::string > & joint_names={}, bool override_mimic=false, bool override_base=false) void set_base_pose (const Eigen::Isometry3d & tf) void set_base_pose (const Eigen::Vector6d & pose) set base pose: pose is a 6D vector (first 3D orientation in angle-axis and last 3D translation) void set_body_mass (const std::string & body_name, double mass) void set_body_mass (size_t body_index, double mass) void set_body_name (size_t body_index, const std::string & body_name) void set_cast_shadows (bool cast_shadows=true) void set_color_mode (const std::string & color_mode) void set_color_mode (const std::string & color_mode, const std::string & body_name) void set_commands (const Eigen::VectorXd & commands, const std::vector< std::string > & dof_names={}) void set_coulomb_coeffs (const std::vector< double > & cfrictions, const std::vector< std::string > & dof_names={}) void set_coulomb_coeffs (double cfriction, const std::vector< std::string > & dof_names={}) void set_damping_coeffs (const std::vector< double > & damps, const std::vector< std::string > & dof_names={}) void set_damping_coeffs (double damp, const std::vector< std::string > & dof_names={}) void set_draw_axis (const std::string & body_name, double size=0.25) void set_external_force (const std::string & body_name, const Eigen::Vector3d & force, const Eigen::Vector3d & offset=Eigen::Vector3d::Zero(), bool force_local=false, bool offset_local=true) void set_external_force (size_t body_index, const Eigen::Vector3d & force, const Eigen::Vector3d & offset=Eigen::Vector3d::Zero(), bool force_local=false, bool offset_local=true) void set_external_torque (const std::string & body_name, const Eigen::Vector3d & torque, bool local=false) void set_external_torque (size_t body_index, const Eigen::Vector3d & torque, bool local=false) void set_force_lower_limits (const Eigen::VectorXd & forces, const std::vector< std::string > & dof_names={}) void set_force_upper_limits (const Eigen::VectorXd & forces, const std::vector< std::string > & dof_names={}) void set_forces (const Eigen::VectorXd & forces, const std::vector< std::string > & dof_names={}) void set_friction_coeff (const std::string & body_name, double value) void set_friction_coeff (size_t body_index, double value) void set_friction_coeffs (double value) void set_friction_dir (const std::string & body_name, const Eigen::Vector3d & direction) void set_friction_dir (size_t body_index, const Eigen::Vector3d & direction) void set_ghost (bool ghost=true) void set_joint_name (size_t joint_index, const std::string & joint_name) void set_mimic (const std::string & joint_name, const std::string & mimic_joint_name, double multiplier=1., double offset=0.) void set_position_enforced (const std::vector< bool > & enforced, const std::vector< std::string > & dof_names={}) void set_position_enforced (bool enforced, const std::vector< std::string > & dof_names={}) void set_position_lower_limits (const Eigen::VectorXd & positions, const std::vector< std::string > & dof_names={}) void set_position_upper_limits (const Eigen::VectorXd & positions, const std::vector< std::string > & dof_names={}) void set_positions (const Eigen::VectorXd & positions, const std::vector< std::string > & dof_names={}) void set_restitution_coeff (const std::string & body_name, double value) void set_restitution_coeff (size_t body_index, double value) void set_restitution_coeffs (double value) void set_secondary_friction_coeff (const std::string & body_name, double value) void set_secondary_friction_coeff (size_t body_index, double value) void set_secondary_friction_coeffs (double value) void set_self_collision (bool enable_self_collisions=true, bool enable_adjacent_collisions=false) void set_spring_stiffnesses (const std::vector< double > & stiffnesses, const std::vector< std::string > & dof_names={}) void set_spring_stiffnesses (double stiffness, const std::vector< std::string > & dof_names={}) void set_velocities (const Eigen::VectorXd & velocities, const std::vector< std::string > & dof_names={}) void set_velocity_lower_limits (const Eigen::VectorXd & velocities, const std::vector< std::string > & dof_names={}) void set_velocity_upper_limits (const Eigen::VectorXd & velocities, const std::vector< std::string > & dof_names={}) dart::dynamics::SkeletonPtr skeleton () std::vector< double > spring_stiffnesses (const std::vector< std::string > & dof_names={}) const void update (double t) void update_joint_dof_maps () Eigen::VectorXd vec_dof (const Eigen::VectorXd & vec, const std::vector< std::string > & dof_names) const Eigen::VectorXd velocities (const std::vector< std::string > & dof_names={}) const Eigen::VectorXd velocity_lower_limits (const std::vector< std::string > & dof_names={}) const Eigen::VectorXd velocity_upper_limits (const std::vector< std::string > & dof_names={}) const virtual ~Robot ()"},{"location":"api/classrobot__dart_1_1robots_1_1ICub/#public-static-functions-inherited-from-robot_dartrobot","title":"Public Static Functions inherited from robot_dart::Robot","text":"

See robot_dart::Robot

Type Name std::shared_ptr< Robot > create_box (const Eigen::Vector3d & dims, const Eigen::Isometry3d & tf, const std::string & type=\"free\", double mass=1.0, const Eigen::Vector4d & color=dart::Color::Red(1.0), const std::string & box_name=\"box\") std::shared_ptr< Robot > create_box (const Eigen::Vector3d & dims, const Eigen::Vector6d & pose=Eigen::Vector6d::Zero(), const std::string & type=\"free\", double mass=1.0, const Eigen::Vector4d & color=dart::Color::Red(1.0), const std::string & box_name=\"box\") std::shared_ptr< Robot > create_ellipsoid (const Eigen::Vector3d & dims, const Eigen::Isometry3d & tf, const std::string & type=\"free\", double mass=1.0, const Eigen::Vector4d & color=dart::Color::Red(1.0), const std::string & ellipsoid_name=\"ellipsoid\") std::shared_ptr< Robot > create_ellipsoid (const Eigen::Vector3d & dims, const Eigen::Vector6d & pose=Eigen::Vector6d::Zero(), const std::string & type=\"free\", double mass=1.0, const Eigen::Vector4d & color=dart::Color::Red(1.0), const std::string & ellipsoid_name=\"ellipsoid\")"},{"location":"api/classrobot__dart_1_1robots_1_1ICub/#protected-attributes","title":"Protected Attributes","text":"Type Name std::shared_ptr< sensor::ForceTorque > _ft_foot_left std::shared_ptr< sensor::ForceTorque > _ft_foot_right std::shared_ptr< sensor::IMU > _imu"},{"location":"api/classrobot__dart_1_1robots_1_1ICub/#protected-attributes-inherited-from-robot_dartrobot","title":"Protected Attributes inherited from robot_dart::Robot","text":"

See robot_dart::Robot

Type Name std::vector< std::pair< dart::dynamics::BodyNode *, double > > _axis_shapes bool _cast_shadows std::vector< std::shared_ptr< control::RobotControl > > _controllers std::unordered_map< std::string, size_t > _dof_map bool _is_ghost std::unordered_map< std::string, size_t > _joint_map std::string _model_filename std::vector< std::pair< std::string, std::string > > _packages std::string _robot_name dart::dynamics::SkeletonPtr _skeleton"},{"location":"api/classrobot__dart_1_1robots_1_1ICub/#protected-functions","title":"Protected Functions","text":"Type Name virtual void _post_addition (RobotDARTSimu *) overrideFunction called by RobotDARTSimu object when adding the robot to the world. virtual void _post_removal (RobotDARTSimu *) overrideFunction called by RobotDARTSimu object when removing the robot to the world."},{"location":"api/classrobot__dart_1_1robots_1_1ICub/#protected-functions-inherited-from-robot_dartrobot","title":"Protected Functions inherited from robot_dart::Robot","text":"

See robot_dart::Robot

Type Name dart::dynamics::Joint::ActuatorType _actuator_type (size_t joint_index) const std::vector< dart::dynamics::Joint::ActuatorType > _actuator_types () const std::string _get_path (const std::string & filename) const Eigen::MatrixXd _jacobian (const Eigen::MatrixXd & full_jacobian, const std::vector< std::string > & dof_names) const dart::dynamics::SkeletonPtr _load_model (const std::string & filename, const std::vector< std::pair< std::string, std::string > > & packages=std::vector< std::pair< std::string, std::string > >(), bool is_urdf_string=false) Eigen::MatrixXd _mass_matrix (const Eigen::MatrixXd & full_mass_matrix, const std::vector< std::string > & dof_names) const virtual void _post_addition (RobotDARTSimu *) Function called by RobotDARTSimu object when adding the robot to the world. virtual void _post_removal (RobotDARTSimu *) Function called by RobotDARTSimu object when removing the robot to the world. void _set_actuator_type (size_t joint_index, dart::dynamics::Joint::ActuatorType type, bool override_mimic=false, bool override_base=false) void _set_actuator_types (const std::vector< dart::dynamics::Joint::ActuatorType > & types, bool override_mimic=false, bool override_base=false) void _set_actuator_types (dart::dynamics::Joint::ActuatorType type, bool override_mimic=false, bool override_base=false) void _set_color_mode (dart::dynamics::MeshShape::ColorMode color_mode, dart::dynamics::SkeletonPtr skel) void _set_color_mode (dart::dynamics::MeshShape::ColorMode color_mode, dart::dynamics::ShapeNode * sn)"},{"location":"api/classrobot__dart_1_1robots_1_1ICub/#public-functions-documentation","title":"Public Functions Documentation","text":""},{"location":"api/classrobot__dart_1_1robots_1_1ICub/#function-icub","title":"function ICub","text":"
robot_dart::robots::ICub::ICub (\nsize_t frequency=1000,\nconst std::string & urdf=\"icub/icub.urdf\",\nconst std::vector< std::pair< std::string, std::string > > & packages=('icub_description', 'icub/icub_description')\n) 
"},{"location":"api/classrobot__dart_1_1robots_1_1ICub/#function-ft_foot_left","title":"function ft_foot_left","text":"
inline const sensor::ForceTorque & robot_dart::robots::ICub::ft_foot_left () const\n
"},{"location":"api/classrobot__dart_1_1robots_1_1ICub/#function-ft_foot_right","title":"function ft_foot_right","text":"
inline const sensor::ForceTorque & robot_dart::robots::ICub::ft_foot_right () const\n
"},{"location":"api/classrobot__dart_1_1robots_1_1ICub/#function-imu","title":"function imu","text":"
inline const sensor::IMU & robot_dart::robots::ICub::imu () const\n
"},{"location":"api/classrobot__dart_1_1robots_1_1ICub/#function-reset","title":"function reset","text":"
virtual void robot_dart::robots::ICub::reset () override\n

Implements robot_dart::Robot::reset

"},{"location":"api/classrobot__dart_1_1robots_1_1ICub/#protected-attributes-documentation","title":"Protected Attributes Documentation","text":""},{"location":"api/classrobot__dart_1_1robots_1_1ICub/#variable-_ft_foot_left","title":"variable _ft_foot_left","text":"
std::shared_ptr<sensor::ForceTorque> robot_dart::robots::ICub::_ft_foot_left;\n
"},{"location":"api/classrobot__dart_1_1robots_1_1ICub/#variable-_ft_foot_right","title":"variable _ft_foot_right","text":"
std::shared_ptr<sensor::ForceTorque> robot_dart::robots::ICub::_ft_foot_right;\n
"},{"location":"api/classrobot__dart_1_1robots_1_1ICub/#variable-_imu","title":"variable _imu","text":"
std::shared_ptr<sensor::IMU> robot_dart::robots::ICub::_imu;\n
"},{"location":"api/classrobot__dart_1_1robots_1_1ICub/#protected-functions-documentation","title":"Protected Functions Documentation","text":""},{"location":"api/classrobot__dart_1_1robots_1_1ICub/#function-_post_addition","title":"function _post_addition","text":"
virtual void robot_dart::robots::ICub::_post_addition (\nRobotDARTSimu *\n) override\n

Implements robot_dart::Robot::_post_addition

"},{"location":"api/classrobot__dart_1_1robots_1_1ICub/#function-_post_removal","title":"function _post_removal","text":"
virtual void robot_dart::robots::ICub::_post_removal (\nRobotDARTSimu *\n) override\n

Implements robot_dart::Robot::_post_removal

The documentation for this class was generated from the following file robot_dart/robots/icub.hpp

"},{"location":"api/classrobot__dart_1_1robots_1_1Iiwa/","title":"Class robot_dart::robots::Iiwa","text":"

ClassList > robot_dart > robots > Iiwa

Inherits the following classes: robot_dart::Robot

"},{"location":"api/classrobot__dart_1_1robots_1_1Iiwa/#public-functions","title":"Public Functions","text":"Type Name Iiwa (size_t frequency=1000, const std::string & urdf=\"iiwa/iiwa.urdf\", const std::vector< std::pair< std::string, std::string > > & packages=('iiwa\\_description', 'iiwa/iiwa\\_description')) const sensor::ForceTorque & ft_wrist () const"},{"location":"api/classrobot__dart_1_1robots_1_1Iiwa/#public-functions-inherited-from-robot_dartrobot","title":"Public Functions inherited from robot_dart::Robot","text":"

See robot_dart::Robot

Type Name Robot (const std::string & model_file, const std::vector< std::pair< std::string, std::string > > & packages, const std::string & robot_name=\"robot\", bool is_urdf_string=false, bool cast_shadows=true) Robot (const std::string & model_file, const std::string & robot_name=\"robot\", bool is_urdf_string=false, bool cast_shadows=true) Robot (dart::dynamics::SkeletonPtr skeleton, const std::string & robot_name=\"robot\", bool cast_shadows=true) Eigen::VectorXd acceleration_lower_limits (const std::vector< std::string > & dof_names={}) const Eigen::VectorXd acceleration_upper_limits (const std::vector< std::string > & dof_names={}) const Eigen::VectorXd accelerations (const std::vector< std::string > & dof_names={}) const std::vector< std::shared_ptr< control::RobotControl > > active_controllers () const std::string actuator_type (const std::string & joint_name) const std::vector< std::string > actuator_types (const std::vector< std::string > & joint_names={}) const void add_body_mass (const std::string & body_name, double mass) void add_body_mass (size_t body_index, double mass) void add_controller (const std::shared_ptr< control::RobotControl > & controller, double weight=1.0) void add_external_force (const std::string & body_name, const Eigen::Vector3d & force, const Eigen::Vector3d & offset=Eigen::Vector3d::Zero(), bool force_local=false, bool offset_local=true) void add_external_force (size_t body_index, const Eigen::Vector3d & force, const Eigen::Vector3d & offset=Eigen::Vector3d::Zero(), bool force_local=false, bool offset_local=true) void add_external_torque (const std::string & body_name, const Eigen::Vector3d & torque, bool local=false) void add_external_torque (size_t body_index, const Eigen::Vector3d & torque, bool local=false) bool adjacent_colliding () const Eigen::MatrixXd aug_mass_matrix (const std::vector< std::string > & dof_names={}) const Eigen::Isometry3d base_pose () const Eigen::Vector6d base_pose_vec () const Eigen::Vector6d body_acceleration (const std::string & body_name) const Eigen::Vector6d body_acceleration (size_t body_index) const size_t body_index (const std::string & body_name) const double body_mass (const std::string & body_name) const double body_mass (size_t body_index) const std::string body_name (size_t body_index) const std::vector< std::string > body_names () const dart::dynamics::BodyNode * body_node (const std::string & body_name) dart::dynamics::BodyNode * body_node (size_t body_index) Eigen::Isometry3d body_pose (const std::string & body_name) const Eigen::Isometry3d body_pose (size_t body_index) const Eigen::Vector6d body_pose_vec (const std::string & body_name) const Eigen::Vector6d body_pose_vec (size_t body_index) const Eigen::Vector6d body_velocity (const std::string & body_name) const Eigen::Vector6d body_velocity (size_t body_index) const bool cast_shadows () const void clear_controllers () void clear_external_forces () void clear_internal_forces () std::shared_ptr< Robot > clone () const std::shared_ptr< Robot > clone_ghost (const std::string & ghost_name=\"ghost\", const Eigen::Vector4d & ghost_color={0.3, 0.3, 0.3, 0.7}) const Eigen::Vector3d com () const Eigen::Vector6d com_acceleration () const Eigen::MatrixXd com_jacobian (const std::vector< std::string > & dof_names={}) const Eigen::MatrixXd com_jacobian_deriv (const std::vector< std::string > & dof_names={}) const Eigen::Vector6d com_velocity () const Eigen::VectorXd commands (const std::vector< std::string > & dof_names={}) const Eigen::VectorXd constraint_forces (const std::vector< std::string > & dof_names={}) const std::shared_ptr< control::RobotControl > controller (size_t index) const std::vector< std::shared_ptr< control::RobotControl > > controllers () const Eigen::VectorXd coriolis_forces (const std::vector< std::string > & dof_names={}) const Eigen::VectorXd coriolis_gravity_forces (const std::vector< std::string > & dof_names={}) const std::vector< double > coulomb_coeffs (const std::vector< std::string > & dof_names={}) const std::vector< double > damping_coeffs (const std::vector< std::string > & dof_names={}) const dart::dynamics::DegreeOfFreedom * dof (const std::string & dof_name) dart::dynamics::DegreeOfFreedom * dof (size_t dof_index) size_t dof_index (const std::string & dof_name) const const std::unordered_map< std::string, size_t > & dof_map () const std::string dof_name (size_t dof_index) const std::vector< std::string > dof_names (bool filter_mimics=false, bool filter_locked=false, bool filter_passive=false) const const std::vector< std::pair< dart::dynamics::BodyNode *, double > > & drawing_axes () const Eigen::Vector6d external_forces (const std::string & body_name) const Eigen::Vector6d external_forces (size_t body_index) const void fix_to_world () bool fixed () const Eigen::VectorXd force_lower_limits (const std::vector< std::string > & dof_names={}) const void force_position_bounds () std::pair< Eigen::Vector6d, Eigen::Vector6d > force_torque (size_t joint_index) const Eigen::VectorXd force_upper_limits (const std::vector< std::string > & dof_names={}) const Eigen::VectorXd forces (const std::vector< std::string > & dof_names={}) const bool free () const void free_from_world (const Eigen::Vector6d & pose=Eigen::Vector6d::Zero()) double friction_coeff (const std::string & body_name) double friction_coeff (size_t body_index) Eigen::Vector3d friction_dir (const std::string & body_name) Eigen::Vector3d friction_dir (size_t body_index) bool ghost () const Eigen::VectorXd gravity_forces (const std::vector< std::string > & dof_names={}) const Eigen::MatrixXd inv_aug_mass_matrix (const std::vector< std::string > & dof_names={}) const Eigen::MatrixXd inv_mass_matrix (const std::vector< std::string > & dof_names={}) const Eigen::MatrixXd jacobian (const std::string & body_name, const std::vector< std::string > & dof_names={}) const Eigen::MatrixXd jacobian_deriv (const std::string & body_name, const std::vector< std::string > & dof_names={}) const dart::dynamics::Joint * joint (const std::string & joint_name) dart::dynamics::Joint * joint (size_t joint_index) size_t joint_index (const std::string & joint_name) const const std::unordered_map< std::string, size_t > & joint_map () const std::string joint_name (size_t joint_index) const std::vector< std::string > joint_names () const std::vector< std::string > locked_dof_names () const Eigen::MatrixXd mass_matrix (const std::vector< std::string > & dof_names={}) const std::vector< std::string > mimic_dof_names () const const std::string & model_filename () const const std::vector< std::pair< std::string, std::string > > & model_packages () const const std::string & name () const size_t num_bodies () const size_t num_controllers () const size_t num_dofs () const size_t num_joints () const std::vector< std::string > passive_dof_names () const std::vector< bool > position_enforced (const std::vector< std::string > & dof_names={}) const Eigen::VectorXd position_lower_limits (const std::vector< std::string > & dof_names={}) const Eigen::VectorXd position_upper_limits (const std::vector< std::string > & dof_names={}) const Eigen::VectorXd positions (const std::vector< std::string > & dof_names={}) const void reinit_controllers () void remove_all_drawing_axis () void remove_controller (const std::shared_ptr< control::RobotControl > & controller) void remove_controller (size_t index) virtual void reset () void reset_commands () double restitution_coeff (const std::string & body_name) double restitution_coeff (size_t body_index) double secondary_friction_coeff (const std::string & body_name) double secondary_friction_coeff (size_t body_index) bool self_colliding () const void set_acceleration_lower_limits (const Eigen::VectorXd & accelerations, const std::vector< std::string > & dof_names={}) void set_acceleration_upper_limits (const Eigen::VectorXd & accelerations, const std::vector< std::string > & dof_names={}) void set_accelerations (const Eigen::VectorXd & accelerations, const std::vector< std::string > & dof_names={}) void set_actuator_type (const std::string & type, const std::string & joint_name, bool override_mimic=false, bool override_base=false) void set_actuator_types (const std::string & type, const std::vector< std::string > & joint_names={}, bool override_mimic=false, bool override_base=false) void set_base_pose (const Eigen::Isometry3d & tf) void set_base_pose (const Eigen::Vector6d & pose) set base pose: pose is a 6D vector (first 3D orientation in angle-axis and last 3D translation) void set_body_mass (const std::string & body_name, double mass) void set_body_mass (size_t body_index, double mass) void set_body_name (size_t body_index, const std::string & body_name) void set_cast_shadows (bool cast_shadows=true) void set_color_mode (const std::string & color_mode) void set_color_mode (const std::string & color_mode, const std::string & body_name) void set_commands (const Eigen::VectorXd & commands, const std::vector< std::string > & dof_names={}) void set_coulomb_coeffs (const std::vector< double > & cfrictions, const std::vector< std::string > & dof_names={}) void set_coulomb_coeffs (double cfriction, const std::vector< std::string > & dof_names={}) void set_damping_coeffs (const std::vector< double > & damps, const std::vector< std::string > & dof_names={}) void set_damping_coeffs (double damp, const std::vector< std::string > & dof_names={}) void set_draw_axis (const std::string & body_name, double size=0.25) void set_external_force (const std::string & body_name, const Eigen::Vector3d & force, const Eigen::Vector3d & offset=Eigen::Vector3d::Zero(), bool force_local=false, bool offset_local=true) void set_external_force (size_t body_index, const Eigen::Vector3d & force, const Eigen::Vector3d & offset=Eigen::Vector3d::Zero(), bool force_local=false, bool offset_local=true) void set_external_torque (const std::string & body_name, const Eigen::Vector3d & torque, bool local=false) void set_external_torque (size_t body_index, const Eigen::Vector3d & torque, bool local=false) void set_force_lower_limits (const Eigen::VectorXd & forces, const std::vector< std::string > & dof_names={}) void set_force_upper_limits (const Eigen::VectorXd & forces, const std::vector< std::string > & dof_names={}) void set_forces (const Eigen::VectorXd & forces, const std::vector< std::string > & dof_names={}) void set_friction_coeff (const std::string & body_name, double value) void set_friction_coeff (size_t body_index, double value) void set_friction_coeffs (double value) void set_friction_dir (const std::string & body_name, const Eigen::Vector3d & direction) void set_friction_dir (size_t body_index, const Eigen::Vector3d & direction) void set_ghost (bool ghost=true) void set_joint_name (size_t joint_index, const std::string & joint_name) void set_mimic (const std::string & joint_name, const std::string & mimic_joint_name, double multiplier=1., double offset=0.) void set_position_enforced (const std::vector< bool > & enforced, const std::vector< std::string > & dof_names={}) void set_position_enforced (bool enforced, const std::vector< std::string > & dof_names={}) void set_position_lower_limits (const Eigen::VectorXd & positions, const std::vector< std::string > & dof_names={}) void set_position_upper_limits (const Eigen::VectorXd & positions, const std::vector< std::string > & dof_names={}) void set_positions (const Eigen::VectorXd & positions, const std::vector< std::string > & dof_names={}) void set_restitution_coeff (const std::string & body_name, double value) void set_restitution_coeff (size_t body_index, double value) void set_restitution_coeffs (double value) void set_secondary_friction_coeff (const std::string & body_name, double value) void set_secondary_friction_coeff (size_t body_index, double value) void set_secondary_friction_coeffs (double value) void set_self_collision (bool enable_self_collisions=true, bool enable_adjacent_collisions=false) void set_spring_stiffnesses (const std::vector< double > & stiffnesses, const std::vector< std::string > & dof_names={}) void set_spring_stiffnesses (double stiffness, const std::vector< std::string > & dof_names={}) void set_velocities (const Eigen::VectorXd & velocities, const std::vector< std::string > & dof_names={}) void set_velocity_lower_limits (const Eigen::VectorXd & velocities, const std::vector< std::string > & dof_names={}) void set_velocity_upper_limits (const Eigen::VectorXd & velocities, const std::vector< std::string > & dof_names={}) dart::dynamics::SkeletonPtr skeleton () std::vector< double > spring_stiffnesses (const std::vector< std::string > & dof_names={}) const void update (double t) void update_joint_dof_maps () Eigen::VectorXd vec_dof (const Eigen::VectorXd & vec, const std::vector< std::string > & dof_names) const Eigen::VectorXd velocities (const std::vector< std::string > & dof_names={}) const Eigen::VectorXd velocity_lower_limits (const std::vector< std::string > & dof_names={}) const Eigen::VectorXd velocity_upper_limits (const std::vector< std::string > & dof_names={}) const virtual ~Robot ()"},{"location":"api/classrobot__dart_1_1robots_1_1Iiwa/#public-static-functions-inherited-from-robot_dartrobot","title":"Public Static Functions inherited from robot_dart::Robot","text":"

See robot_dart::Robot

Type Name std::shared_ptr< Robot > create_box (const Eigen::Vector3d & dims, const Eigen::Isometry3d & tf, const std::string & type=\"free\", double mass=1.0, const Eigen::Vector4d & color=dart::Color::Red(1.0), const std::string & box_name=\"box\") std::shared_ptr< Robot > create_box (const Eigen::Vector3d & dims, const Eigen::Vector6d & pose=Eigen::Vector6d::Zero(), const std::string & type=\"free\", double mass=1.0, const Eigen::Vector4d & color=dart::Color::Red(1.0), const std::string & box_name=\"box\") std::shared_ptr< Robot > create_ellipsoid (const Eigen::Vector3d & dims, const Eigen::Isometry3d & tf, const std::string & type=\"free\", double mass=1.0, const Eigen::Vector4d & color=dart::Color::Red(1.0), const std::string & ellipsoid_name=\"ellipsoid\") std::shared_ptr< Robot > create_ellipsoid (const Eigen::Vector3d & dims, const Eigen::Vector6d & pose=Eigen::Vector6d::Zero(), const std::string & type=\"free\", double mass=1.0, const Eigen::Vector4d & color=dart::Color::Red(1.0), const std::string & ellipsoid_name=\"ellipsoid\")"},{"location":"api/classrobot__dart_1_1robots_1_1Iiwa/#protected-attributes","title":"Protected Attributes","text":"Type Name std::shared_ptr< sensor::ForceTorque > _ft_wrist"},{"location":"api/classrobot__dart_1_1robots_1_1Iiwa/#protected-attributes-inherited-from-robot_dartrobot","title":"Protected Attributes inherited from robot_dart::Robot","text":"

See robot_dart::Robot

Type Name std::vector< std::pair< dart::dynamics::BodyNode *, double > > _axis_shapes bool _cast_shadows std::vector< std::shared_ptr< control::RobotControl > > _controllers std::unordered_map< std::string, size_t > _dof_map bool _is_ghost std::unordered_map< std::string, size_t > _joint_map std::string _model_filename std::vector< std::pair< std::string, std::string > > _packages std::string _robot_name dart::dynamics::SkeletonPtr _skeleton"},{"location":"api/classrobot__dart_1_1robots_1_1Iiwa/#protected-functions","title":"Protected Functions","text":"Type Name virtual void _post_addition (RobotDARTSimu *) overrideFunction called by RobotDARTSimu object when adding the robot to the world. virtual void _post_removal (RobotDARTSimu *) overrideFunction called by RobotDARTSimu object when removing the robot to the world."},{"location":"api/classrobot__dart_1_1robots_1_1Iiwa/#protected-functions-inherited-from-robot_dartrobot","title":"Protected Functions inherited from robot_dart::Robot","text":"

See robot_dart::Robot

Type Name dart::dynamics::Joint::ActuatorType _actuator_type (size_t joint_index) const std::vector< dart::dynamics::Joint::ActuatorType > _actuator_types () const std::string _get_path (const std::string & filename) const Eigen::MatrixXd _jacobian (const Eigen::MatrixXd & full_jacobian, const std::vector< std::string > & dof_names) const dart::dynamics::SkeletonPtr _load_model (const std::string & filename, const std::vector< std::pair< std::string, std::string > > & packages=std::vector< std::pair< std::string, std::string > >(), bool is_urdf_string=false) Eigen::MatrixXd _mass_matrix (const Eigen::MatrixXd & full_mass_matrix, const std::vector< std::string > & dof_names) const virtual void _post_addition (RobotDARTSimu *) Function called by RobotDARTSimu object when adding the robot to the world. virtual void _post_removal (RobotDARTSimu *) Function called by RobotDARTSimu object when removing the robot to the world. void _set_actuator_type (size_t joint_index, dart::dynamics::Joint::ActuatorType type, bool override_mimic=false, bool override_base=false) void _set_actuator_types (const std::vector< dart::dynamics::Joint::ActuatorType > & types, bool override_mimic=false, bool override_base=false) void _set_actuator_types (dart::dynamics::Joint::ActuatorType type, bool override_mimic=false, bool override_base=false) void _set_color_mode (dart::dynamics::MeshShape::ColorMode color_mode, dart::dynamics::SkeletonPtr skel) void _set_color_mode (dart::dynamics::MeshShape::ColorMode color_mode, dart::dynamics::ShapeNode * sn)"},{"location":"api/classrobot__dart_1_1robots_1_1Iiwa/#public-functions-documentation","title":"Public Functions Documentation","text":""},{"location":"api/classrobot__dart_1_1robots_1_1Iiwa/#function-iiwa","title":"function Iiwa","text":"
robot_dart::robots::Iiwa::Iiwa (\nsize_t frequency=1000,\nconst std::string & urdf=\"iiwa/iiwa.urdf\",\nconst std::vector< std::pair< std::string, std::string > > & packages=('iiwa_description', 'iiwa/iiwa_description')\n) 
"},{"location":"api/classrobot__dart_1_1robots_1_1Iiwa/#function-ft_wrist","title":"function ft_wrist","text":"
inline const sensor::ForceTorque & robot_dart::robots::Iiwa::ft_wrist () const\n
"},{"location":"api/classrobot__dart_1_1robots_1_1Iiwa/#protected-attributes-documentation","title":"Protected Attributes Documentation","text":""},{"location":"api/classrobot__dart_1_1robots_1_1Iiwa/#variable-_ft_wrist","title":"variable _ft_wrist","text":"
std::shared_ptr<sensor::ForceTorque> robot_dart::robots::Iiwa::_ft_wrist;\n
"},{"location":"api/classrobot__dart_1_1robots_1_1Iiwa/#protected-functions-documentation","title":"Protected Functions Documentation","text":""},{"location":"api/classrobot__dart_1_1robots_1_1Iiwa/#function-_post_addition","title":"function _post_addition","text":"
virtual void robot_dart::robots::Iiwa::_post_addition (\nRobotDARTSimu *\n) override\n

Implements robot_dart::Robot::_post_addition

"},{"location":"api/classrobot__dart_1_1robots_1_1Iiwa/#function-_post_removal","title":"function _post_removal","text":"
virtual void robot_dart::robots::Iiwa::_post_removal (\nRobotDARTSimu *\n) override\n

Implements robot_dart::Robot::_post_removal

The documentation for this class was generated from the following file robot_dart/robots/iiwa.hpp

"},{"location":"api/classrobot__dart_1_1robots_1_1Pendulum/","title":"Class robot_dart::robots::Pendulum","text":"

ClassList > robot_dart > robots > Pendulum

Inherits the following classes: robot_dart::Robot

"},{"location":"api/classrobot__dart_1_1robots_1_1Pendulum/#public-functions","title":"Public Functions","text":"Type Name Pendulum (const std::string & urdf=\"pendulum.urdf\")"},{"location":"api/classrobot__dart_1_1robots_1_1Pendulum/#public-functions-inherited-from-robot_dartrobot","title":"Public Functions inherited from robot_dart::Robot","text":"

See robot_dart::Robot

Type Name Robot (const std::string & model_file, const std::vector< std::pair< std::string, std::string > > & packages, const std::string & robot_name=\"robot\", bool is_urdf_string=false, bool cast_shadows=true) Robot (const std::string & model_file, const std::string & robot_name=\"robot\", bool is_urdf_string=false, bool cast_shadows=true) Robot (dart::dynamics::SkeletonPtr skeleton, const std::string & robot_name=\"robot\", bool cast_shadows=true) Eigen::VectorXd acceleration_lower_limits (const std::vector< std::string > & dof_names={}) const Eigen::VectorXd acceleration_upper_limits (const std::vector< std::string > & dof_names={}) const Eigen::VectorXd accelerations (const std::vector< std::string > & dof_names={}) const std::vector< std::shared_ptr< control::RobotControl > > active_controllers () const std::string actuator_type (const std::string & joint_name) const std::vector< std::string > actuator_types (const std::vector< std::string > & joint_names={}) const void add_body_mass (const std::string & body_name, double mass) void add_body_mass (size_t body_index, double mass) void add_controller (const std::shared_ptr< control::RobotControl > & controller, double weight=1.0) void add_external_force (const std::string & body_name, const Eigen::Vector3d & force, const Eigen::Vector3d & offset=Eigen::Vector3d::Zero(), bool force_local=false, bool offset_local=true) void add_external_force (size_t body_index, const Eigen::Vector3d & force, const Eigen::Vector3d & offset=Eigen::Vector3d::Zero(), bool force_local=false, bool offset_local=true) void add_external_torque (const std::string & body_name, const Eigen::Vector3d & torque, bool local=false) void add_external_torque (size_t body_index, const Eigen::Vector3d & torque, bool local=false) bool adjacent_colliding () const Eigen::MatrixXd aug_mass_matrix (const std::vector< std::string > & dof_names={}) const Eigen::Isometry3d base_pose () const Eigen::Vector6d base_pose_vec () const Eigen::Vector6d body_acceleration (const std::string & body_name) const Eigen::Vector6d body_acceleration (size_t body_index) const size_t body_index (const std::string & body_name) const double body_mass (const std::string & body_name) const double body_mass (size_t body_index) const std::string body_name (size_t body_index) const std::vector< std::string > body_names () const dart::dynamics::BodyNode * body_node (const std::string & body_name) dart::dynamics::BodyNode * body_node (size_t body_index) Eigen::Isometry3d body_pose (const std::string & body_name) const Eigen::Isometry3d body_pose (size_t body_index) const Eigen::Vector6d body_pose_vec (const std::string & body_name) const Eigen::Vector6d body_pose_vec (size_t body_index) const Eigen::Vector6d body_velocity (const std::string & body_name) const Eigen::Vector6d body_velocity (size_t body_index) const bool cast_shadows () const void clear_controllers () void clear_external_forces () void clear_internal_forces () std::shared_ptr< Robot > clone () const std::shared_ptr< Robot > clone_ghost (const std::string & ghost_name=\"ghost\", const Eigen::Vector4d & ghost_color={0.3, 0.3, 0.3, 0.7}) const Eigen::Vector3d com () const Eigen::Vector6d com_acceleration () const Eigen::MatrixXd com_jacobian (const std::vector< std::string > & dof_names={}) const Eigen::MatrixXd com_jacobian_deriv (const std::vector< std::string > & dof_names={}) const Eigen::Vector6d com_velocity () const Eigen::VectorXd commands (const std::vector< std::string > & dof_names={}) const Eigen::VectorXd constraint_forces (const std::vector< std::string > & dof_names={}) const std::shared_ptr< control::RobotControl > controller (size_t index) const std::vector< std::shared_ptr< control::RobotControl > > controllers () const Eigen::VectorXd coriolis_forces (const std::vector< std::string > & dof_names={}) const Eigen::VectorXd coriolis_gravity_forces (const std::vector< std::string > & dof_names={}) const std::vector< double > coulomb_coeffs (const std::vector< std::string > & dof_names={}) const std::vector< double > damping_coeffs (const std::vector< std::string > & dof_names={}) const dart::dynamics::DegreeOfFreedom * dof (const std::string & dof_name) dart::dynamics::DegreeOfFreedom * dof (size_t dof_index) size_t dof_index (const std::string & dof_name) const const std::unordered_map< std::string, size_t > & dof_map () const std::string dof_name (size_t dof_index) const std::vector< std::string > dof_names (bool filter_mimics=false, bool filter_locked=false, bool filter_passive=false) const const std::vector< std::pair< dart::dynamics::BodyNode *, double > > & drawing_axes () const Eigen::Vector6d external_forces (const std::string & body_name) const Eigen::Vector6d external_forces (size_t body_index) const void fix_to_world () bool fixed () const Eigen::VectorXd force_lower_limits (const std::vector< std::string > & dof_names={}) const void force_position_bounds () std::pair< Eigen::Vector6d, Eigen::Vector6d > force_torque (size_t joint_index) const Eigen::VectorXd force_upper_limits (const std::vector< std::string > & dof_names={}) const Eigen::VectorXd forces (const std::vector< std::string > & dof_names={}) const bool free () const void free_from_world (const Eigen::Vector6d & pose=Eigen::Vector6d::Zero()) double friction_coeff (const std::string & body_name) double friction_coeff (size_t body_index) Eigen::Vector3d friction_dir (const std::string & body_name) Eigen::Vector3d friction_dir (size_t body_index) bool ghost () const Eigen::VectorXd gravity_forces (const std::vector< std::string > & dof_names={}) const Eigen::MatrixXd inv_aug_mass_matrix (const std::vector< std::string > & dof_names={}) const Eigen::MatrixXd inv_mass_matrix (const std::vector< std::string > & dof_names={}) const Eigen::MatrixXd jacobian (const std::string & body_name, const std::vector< std::string > & dof_names={}) const Eigen::MatrixXd jacobian_deriv (const std::string & body_name, const std::vector< std::string > & dof_names={}) const dart::dynamics::Joint * joint (const std::string & joint_name) dart::dynamics::Joint * joint (size_t joint_index) size_t joint_index (const std::string & joint_name) const const std::unordered_map< std::string, size_t > & joint_map () const std::string joint_name (size_t joint_index) const std::vector< std::string > joint_names () const std::vector< std::string > locked_dof_names () const Eigen::MatrixXd mass_matrix (const std::vector< std::string > & dof_names={}) const std::vector< std::string > mimic_dof_names () const const std::string & model_filename () const const std::vector< std::pair< std::string, std::string > > & model_packages () const const std::string & name () const size_t num_bodies () const size_t num_controllers () const size_t num_dofs () const size_t num_joints () const std::vector< std::string > passive_dof_names () const std::vector< bool > position_enforced (const std::vector< std::string > & dof_names={}) const Eigen::VectorXd position_lower_limits (const std::vector< std::string > & dof_names={}) const Eigen::VectorXd position_upper_limits (const std::vector< std::string > & dof_names={}) const Eigen::VectorXd positions (const std::vector< std::string > & dof_names={}) const void reinit_controllers () void remove_all_drawing_axis () void remove_controller (const std::shared_ptr< control::RobotControl > & controller) void remove_controller (size_t index) virtual void reset () void reset_commands () double restitution_coeff (const std::string & body_name) double restitution_coeff (size_t body_index) double secondary_friction_coeff (const std::string & body_name) double secondary_friction_coeff (size_t body_index) bool self_colliding () const void set_acceleration_lower_limits (const Eigen::VectorXd & accelerations, const std::vector< std::string > & dof_names={}) void set_acceleration_upper_limits (const Eigen::VectorXd & accelerations, const std::vector< std::string > & dof_names={}) void set_accelerations (const Eigen::VectorXd & accelerations, const std::vector< std::string > & dof_names={}) void set_actuator_type (const std::string & type, const std::string & joint_name, bool override_mimic=false, bool override_base=false) void set_actuator_types (const std::string & type, const std::vector< std::string > & joint_names={}, bool override_mimic=false, bool override_base=false) void set_base_pose (const Eigen::Isometry3d & tf) void set_base_pose (const Eigen::Vector6d & pose) set base pose: pose is a 6D vector (first 3D orientation in angle-axis and last 3D translation) void set_body_mass (const std::string & body_name, double mass) void set_body_mass (size_t body_index, double mass) void set_body_name (size_t body_index, const std::string & body_name) void set_cast_shadows (bool cast_shadows=true) void set_color_mode (const std::string & color_mode) void set_color_mode (const std::string & color_mode, const std::string & body_name) void set_commands (const Eigen::VectorXd & commands, const std::vector< std::string > & dof_names={}) void set_coulomb_coeffs (const std::vector< double > & cfrictions, const std::vector< std::string > & dof_names={}) void set_coulomb_coeffs (double cfriction, const std::vector< std::string > & dof_names={}) void set_damping_coeffs (const std::vector< double > & damps, const std::vector< std::string > & dof_names={}) void set_damping_coeffs (double damp, const std::vector< std::string > & dof_names={}) void set_draw_axis (const std::string & body_name, double size=0.25) void set_external_force (const std::string & body_name, const Eigen::Vector3d & force, const Eigen::Vector3d & offset=Eigen::Vector3d::Zero(), bool force_local=false, bool offset_local=true) void set_external_force (size_t body_index, const Eigen::Vector3d & force, const Eigen::Vector3d & offset=Eigen::Vector3d::Zero(), bool force_local=false, bool offset_local=true) void set_external_torque (const std::string & body_name, const Eigen::Vector3d & torque, bool local=false) void set_external_torque (size_t body_index, const Eigen::Vector3d & torque, bool local=false) void set_force_lower_limits (const Eigen::VectorXd & forces, const std::vector< std::string > & dof_names={}) void set_force_upper_limits (const Eigen::VectorXd & forces, const std::vector< std::string > & dof_names={}) void set_forces (const Eigen::VectorXd & forces, const std::vector< std::string > & dof_names={}) void set_friction_coeff (const std::string & body_name, double value) void set_friction_coeff (size_t body_index, double value) void set_friction_coeffs (double value) void set_friction_dir (const std::string & body_name, const Eigen::Vector3d & direction) void set_friction_dir (size_t body_index, const Eigen::Vector3d & direction) void set_ghost (bool ghost=true) void set_joint_name (size_t joint_index, const std::string & joint_name) void set_mimic (const std::string & joint_name, const std::string & mimic_joint_name, double multiplier=1., double offset=0.) void set_position_enforced (const std::vector< bool > & enforced, const std::vector< std::string > & dof_names={}) void set_position_enforced (bool enforced, const std::vector< std::string > & dof_names={}) void set_position_lower_limits (const Eigen::VectorXd & positions, const std::vector< std::string > & dof_names={}) void set_position_upper_limits (const Eigen::VectorXd & positions, const std::vector< std::string > & dof_names={}) void set_positions (const Eigen::VectorXd & positions, const std::vector< std::string > & dof_names={}) void set_restitution_coeff (const std::string & body_name, double value) void set_restitution_coeff (size_t body_index, double value) void set_restitution_coeffs (double value) void set_secondary_friction_coeff (const std::string & body_name, double value) void set_secondary_friction_coeff (size_t body_index, double value) void set_secondary_friction_coeffs (double value) void set_self_collision (bool enable_self_collisions=true, bool enable_adjacent_collisions=false) void set_spring_stiffnesses (const std::vector< double > & stiffnesses, const std::vector< std::string > & dof_names={}) void set_spring_stiffnesses (double stiffness, const std::vector< std::string > & dof_names={}) void set_velocities (const Eigen::VectorXd & velocities, const std::vector< std::string > & dof_names={}) void set_velocity_lower_limits (const Eigen::VectorXd & velocities, const std::vector< std::string > & dof_names={}) void set_velocity_upper_limits (const Eigen::VectorXd & velocities, const std::vector< std::string > & dof_names={}) dart::dynamics::SkeletonPtr skeleton () std::vector< double > spring_stiffnesses (const std::vector< std::string > & dof_names={}) const void update (double t) void update_joint_dof_maps () Eigen::VectorXd vec_dof (const Eigen::VectorXd & vec, const std::vector< std::string > & dof_names) const Eigen::VectorXd velocities (const std::vector< std::string > & dof_names={}) const Eigen::VectorXd velocity_lower_limits (const std::vector< std::string > & dof_names={}) const Eigen::VectorXd velocity_upper_limits (const std::vector< std::string > & dof_names={}) const virtual ~Robot ()"},{"location":"api/classrobot__dart_1_1robots_1_1Pendulum/#public-static-functions-inherited-from-robot_dartrobot","title":"Public Static Functions inherited from robot_dart::Robot","text":"

See robot_dart::Robot

Type Name std::shared_ptr< Robot > create_box (const Eigen::Vector3d & dims, const Eigen::Isometry3d & tf, const std::string & type=\"free\", double mass=1.0, const Eigen::Vector4d & color=dart::Color::Red(1.0), const std::string & box_name=\"box\") std::shared_ptr< Robot > create_box (const Eigen::Vector3d & dims, const Eigen::Vector6d & pose=Eigen::Vector6d::Zero(), const std::string & type=\"free\", double mass=1.0, const Eigen::Vector4d & color=dart::Color::Red(1.0), const std::string & box_name=\"box\") std::shared_ptr< Robot > create_ellipsoid (const Eigen::Vector3d & dims, const Eigen::Isometry3d & tf, const std::string & type=\"free\", double mass=1.0, const Eigen::Vector4d & color=dart::Color::Red(1.0), const std::string & ellipsoid_name=\"ellipsoid\") std::shared_ptr< Robot > create_ellipsoid (const Eigen::Vector3d & dims, const Eigen::Vector6d & pose=Eigen::Vector6d::Zero(), const std::string & type=\"free\", double mass=1.0, const Eigen::Vector4d & color=dart::Color::Red(1.0), const std::string & ellipsoid_name=\"ellipsoid\")"},{"location":"api/classrobot__dart_1_1robots_1_1Pendulum/#protected-attributes-inherited-from-robot_dartrobot","title":"Protected Attributes inherited from robot_dart::Robot","text":"

See robot_dart::Robot

Type Name std::vector< std::pair< dart::dynamics::BodyNode *, double > > _axis_shapes bool _cast_shadows std::vector< std::shared_ptr< control::RobotControl > > _controllers std::unordered_map< std::string, size_t > _dof_map bool _is_ghost std::unordered_map< std::string, size_t > _joint_map std::string _model_filename std::vector< std::pair< std::string, std::string > > _packages std::string _robot_name dart::dynamics::SkeletonPtr _skeleton"},{"location":"api/classrobot__dart_1_1robots_1_1Pendulum/#protected-functions-inherited-from-robot_dartrobot","title":"Protected Functions inherited from robot_dart::Robot","text":"

See robot_dart::Robot

Type Name dart::dynamics::Joint::ActuatorType _actuator_type (size_t joint_index) const std::vector< dart::dynamics::Joint::ActuatorType > _actuator_types () const std::string _get_path (const std::string & filename) const Eigen::MatrixXd _jacobian (const Eigen::MatrixXd & full_jacobian, const std::vector< std::string > & dof_names) const dart::dynamics::SkeletonPtr _load_model (const std::string & filename, const std::vector< std::pair< std::string, std::string > > & packages=std::vector< std::pair< std::string, std::string > >(), bool is_urdf_string=false) Eigen::MatrixXd _mass_matrix (const Eigen::MatrixXd & full_mass_matrix, const std::vector< std::string > & dof_names) const virtual void _post_addition (RobotDARTSimu *) Function called by RobotDARTSimu object when adding the robot to the world. virtual void _post_removal (RobotDARTSimu *) Function called by RobotDARTSimu object when removing the robot to the world. void _set_actuator_type (size_t joint_index, dart::dynamics::Joint::ActuatorType type, bool override_mimic=false, bool override_base=false) void _set_actuator_types (const std::vector< dart::dynamics::Joint::ActuatorType > & types, bool override_mimic=false, bool override_base=false) void _set_actuator_types (dart::dynamics::Joint::ActuatorType type, bool override_mimic=false, bool override_base=false) void _set_color_mode (dart::dynamics::MeshShape::ColorMode color_mode, dart::dynamics::SkeletonPtr skel) void _set_color_mode (dart::dynamics::MeshShape::ColorMode color_mode, dart::dynamics::ShapeNode * sn)"},{"location":"api/classrobot__dart_1_1robots_1_1Pendulum/#public-functions-documentation","title":"Public Functions Documentation","text":""},{"location":"api/classrobot__dart_1_1robots_1_1Pendulum/#function-pendulum","title":"function Pendulum","text":"
inline robot_dart::robots::Pendulum::Pendulum (\nconst std::string & urdf=\"pendulum.urdf\"\n) 

The documentation for this class was generated from the following file robot_dart/robots/pendulum.hpp

"},{"location":"api/classrobot__dart_1_1robots_1_1Talos/","title":"Class robot_dart::robots::Talos","text":"

ClassList > robot_dart > robots > Talos

datasheet: https://pal-robotics.com/wp-content/uploads/2019/07/Datasheet_TALOS.pdf __

Inherits the following classes: robot_dart::Robot

Inherited by the following classes: robot_dart::robots::TalosFastCollision, robot_dart::robots::TalosLight

"},{"location":"api/classrobot__dart_1_1robots_1_1Talos/#public-types","title":"Public Types","text":"Type Name typedef std::unordered_map< std::string, std::shared_ptr< sensor::Torque > > torque_map_t"},{"location":"api/classrobot__dart_1_1robots_1_1Talos/#public-functions","title":"Public Functions","text":"Type Name Talos (size_t frequency=1000, const std::string & urdf=\"talos/talos.urdf\", const std::vector< std::pair< std::string, std::string > > & packages=('talos\\_description', 'talos/talos\\_description')) const sensor::ForceTorque & ft_foot_left () const const sensor::ForceTorque & ft_foot_right () const const sensor::ForceTorque & ft_wrist_left () const const sensor::ForceTorque & ft_wrist_right () const const sensor::IMU & imu () const virtual void reset () override const torque_map_t & torques () const"},{"location":"api/classrobot__dart_1_1robots_1_1Talos/#public-functions-inherited-from-robot_dartrobot","title":"Public Functions inherited from robot_dart::Robot","text":"

See robot_dart::Robot

Type Name Robot (const std::string & model_file, const std::vector< std::pair< std::string, std::string > > & packages, const std::string & robot_name=\"robot\", bool is_urdf_string=false, bool cast_shadows=true) Robot (const std::string & model_file, const std::string & robot_name=\"robot\", bool is_urdf_string=false, bool cast_shadows=true) Robot (dart::dynamics::SkeletonPtr skeleton, const std::string & robot_name=\"robot\", bool cast_shadows=true) Eigen::VectorXd acceleration_lower_limits (const std::vector< std::string > & dof_names={}) const Eigen::VectorXd acceleration_upper_limits (const std::vector< std::string > & dof_names={}) const Eigen::VectorXd accelerations (const std::vector< std::string > & dof_names={}) const std::vector< std::shared_ptr< control::RobotControl > > active_controllers () const std::string actuator_type (const std::string & joint_name) const std::vector< std::string > actuator_types (const std::vector< std::string > & joint_names={}) const void add_body_mass (const std::string & body_name, double mass) void add_body_mass (size_t body_index, double mass) void add_controller (const std::shared_ptr< control::RobotControl > & controller, double weight=1.0) void add_external_force (const std::string & body_name, const Eigen::Vector3d & force, const Eigen::Vector3d & offset=Eigen::Vector3d::Zero(), bool force_local=false, bool offset_local=true) void add_external_force (size_t body_index, const Eigen::Vector3d & force, const Eigen::Vector3d & offset=Eigen::Vector3d::Zero(), bool force_local=false, bool offset_local=true) void add_external_torque (const std::string & body_name, const Eigen::Vector3d & torque, bool local=false) void add_external_torque (size_t body_index, const Eigen::Vector3d & torque, bool local=false) bool adjacent_colliding () const Eigen::MatrixXd aug_mass_matrix (const std::vector< std::string > & dof_names={}) const Eigen::Isometry3d base_pose () const Eigen::Vector6d base_pose_vec () const Eigen::Vector6d body_acceleration (const std::string & body_name) const Eigen::Vector6d body_acceleration (size_t body_index) const size_t body_index (const std::string & body_name) const double body_mass (const std::string & body_name) const double body_mass (size_t body_index) const std::string body_name (size_t body_index) const std::vector< std::string > body_names () const dart::dynamics::BodyNode * body_node (const std::string & body_name) dart::dynamics::BodyNode * body_node (size_t body_index) Eigen::Isometry3d body_pose (const std::string & body_name) const Eigen::Isometry3d body_pose (size_t body_index) const Eigen::Vector6d body_pose_vec (const std::string & body_name) const Eigen::Vector6d body_pose_vec (size_t body_index) const Eigen::Vector6d body_velocity (const std::string & body_name) const Eigen::Vector6d body_velocity (size_t body_index) const bool cast_shadows () const void clear_controllers () void clear_external_forces () void clear_internal_forces () std::shared_ptr< Robot > clone () const std::shared_ptr< Robot > clone_ghost (const std::string & ghost_name=\"ghost\", const Eigen::Vector4d & ghost_color={0.3, 0.3, 0.3, 0.7}) const Eigen::Vector3d com () const Eigen::Vector6d com_acceleration () const Eigen::MatrixXd com_jacobian (const std::vector< std::string > & dof_names={}) const Eigen::MatrixXd com_jacobian_deriv (const std::vector< std::string > & dof_names={}) const Eigen::Vector6d com_velocity () const Eigen::VectorXd commands (const std::vector< std::string > & dof_names={}) const Eigen::VectorXd constraint_forces (const std::vector< std::string > & dof_names={}) const std::shared_ptr< control::RobotControl > controller (size_t index) const std::vector< std::shared_ptr< control::RobotControl > > controllers () const Eigen::VectorXd coriolis_forces (const std::vector< std::string > & dof_names={}) const Eigen::VectorXd coriolis_gravity_forces (const std::vector< std::string > & dof_names={}) const std::vector< double > coulomb_coeffs (const std::vector< std::string > & dof_names={}) const std::vector< double > damping_coeffs (const std::vector< std::string > & dof_names={}) const dart::dynamics::DegreeOfFreedom * dof (const std::string & dof_name) dart::dynamics::DegreeOfFreedom * dof (size_t dof_index) size_t dof_index (const std::string & dof_name) const const std::unordered_map< std::string, size_t > & dof_map () const std::string dof_name (size_t dof_index) const std::vector< std::string > dof_names (bool filter_mimics=false, bool filter_locked=false, bool filter_passive=false) const const std::vector< std::pair< dart::dynamics::BodyNode *, double > > & drawing_axes () const Eigen::Vector6d external_forces (const std::string & body_name) const Eigen::Vector6d external_forces (size_t body_index) const void fix_to_world () bool fixed () const Eigen::VectorXd force_lower_limits (const std::vector< std::string > & dof_names={}) const void force_position_bounds () std::pair< Eigen::Vector6d, Eigen::Vector6d > force_torque (size_t joint_index) const Eigen::VectorXd force_upper_limits (const std::vector< std::string > & dof_names={}) const Eigen::VectorXd forces (const std::vector< std::string > & dof_names={}) const bool free () const void free_from_world (const Eigen::Vector6d & pose=Eigen::Vector6d::Zero()) double friction_coeff (const std::string & body_name) double friction_coeff (size_t body_index) Eigen::Vector3d friction_dir (const std::string & body_name) Eigen::Vector3d friction_dir (size_t body_index) bool ghost () const Eigen::VectorXd gravity_forces (const std::vector< std::string > & dof_names={}) const Eigen::MatrixXd inv_aug_mass_matrix (const std::vector< std::string > & dof_names={}) const Eigen::MatrixXd inv_mass_matrix (const std::vector< std::string > & dof_names={}) const Eigen::MatrixXd jacobian (const std::string & body_name, const std::vector< std::string > & dof_names={}) const Eigen::MatrixXd jacobian_deriv (const std::string & body_name, const std::vector< std::string > & dof_names={}) const dart::dynamics::Joint * joint (const std::string & joint_name) dart::dynamics::Joint * joint (size_t joint_index) size_t joint_index (const std::string & joint_name) const const std::unordered_map< std::string, size_t > & joint_map () const std::string joint_name (size_t joint_index) const std::vector< std::string > joint_names () const std::vector< std::string > locked_dof_names () const Eigen::MatrixXd mass_matrix (const std::vector< std::string > & dof_names={}) const std::vector< std::string > mimic_dof_names () const const std::string & model_filename () const const std::vector< std::pair< std::string, std::string > > & model_packages () const const std::string & name () const size_t num_bodies () const size_t num_controllers () const size_t num_dofs () const size_t num_joints () const std::vector< std::string > passive_dof_names () const std::vector< bool > position_enforced (const std::vector< std::string > & dof_names={}) const Eigen::VectorXd position_lower_limits (const std::vector< std::string > & dof_names={}) const Eigen::VectorXd position_upper_limits (const std::vector< std::string > & dof_names={}) const Eigen::VectorXd positions (const std::vector< std::string > & dof_names={}) const void reinit_controllers () void remove_all_drawing_axis () void remove_controller (const std::shared_ptr< control::RobotControl > & controller) void remove_controller (size_t index) virtual void reset () void reset_commands () double restitution_coeff (const std::string & body_name) double restitution_coeff (size_t body_index) double secondary_friction_coeff (const std::string & body_name) double secondary_friction_coeff (size_t body_index) bool self_colliding () const void set_acceleration_lower_limits (const Eigen::VectorXd & accelerations, const std::vector< std::string > & dof_names={}) void set_acceleration_upper_limits (const Eigen::VectorXd & accelerations, const std::vector< std::string > & dof_names={}) void set_accelerations (const Eigen::VectorXd & accelerations, const std::vector< std::string > & dof_names={}) void set_actuator_type (const std::string & type, const std::string & joint_name, bool override_mimic=false, bool override_base=false) void set_actuator_types (const std::string & type, const std::vector< std::string > & joint_names={}, bool override_mimic=false, bool override_base=false) void set_base_pose (const Eigen::Isometry3d & tf) void set_base_pose (const Eigen::Vector6d & pose) set base pose: pose is a 6D vector (first 3D orientation in angle-axis and last 3D translation) void set_body_mass (const std::string & body_name, double mass) void set_body_mass (size_t body_index, double mass) void set_body_name (size_t body_index, const std::string & body_name) void set_cast_shadows (bool cast_shadows=true) void set_color_mode (const std::string & color_mode) void set_color_mode (const std::string & color_mode, const std::string & body_name) void set_commands (const Eigen::VectorXd & commands, const std::vector< std::string > & dof_names={}) void set_coulomb_coeffs (const std::vector< double > & cfrictions, const std::vector< std::string > & dof_names={}) void set_coulomb_coeffs (double cfriction, const std::vector< std::string > & dof_names={}) void set_damping_coeffs (const std::vector< double > & damps, const std::vector< std::string > & dof_names={}) void set_damping_coeffs (double damp, const std::vector< std::string > & dof_names={}) void set_draw_axis (const std::string & body_name, double size=0.25) void set_external_force (const std::string & body_name, const Eigen::Vector3d & force, const Eigen::Vector3d & offset=Eigen::Vector3d::Zero(), bool force_local=false, bool offset_local=true) void set_external_force (size_t body_index, const Eigen::Vector3d & force, const Eigen::Vector3d & offset=Eigen::Vector3d::Zero(), bool force_local=false, bool offset_local=true) void set_external_torque (const std::string & body_name, const Eigen::Vector3d & torque, bool local=false) void set_external_torque (size_t body_index, const Eigen::Vector3d & torque, bool local=false) void set_force_lower_limits (const Eigen::VectorXd & forces, const std::vector< std::string > & dof_names={}) void set_force_upper_limits (const Eigen::VectorXd & forces, const std::vector< std::string > & dof_names={}) void set_forces (const Eigen::VectorXd & forces, const std::vector< std::string > & dof_names={}) void set_friction_coeff (const std::string & body_name, double value) void set_friction_coeff (size_t body_index, double value) void set_friction_coeffs (double value) void set_friction_dir (const std::string & body_name, const Eigen::Vector3d & direction) void set_friction_dir (size_t body_index, const Eigen::Vector3d & direction) void set_ghost (bool ghost=true) void set_joint_name (size_t joint_index, const std::string & joint_name) void set_mimic (const std::string & joint_name, const std::string & mimic_joint_name, double multiplier=1., double offset=0.) void set_position_enforced (const std::vector< bool > & enforced, const std::vector< std::string > & dof_names={}) void set_position_enforced (bool enforced, const std::vector< std::string > & dof_names={}) void set_position_lower_limits (const Eigen::VectorXd & positions, const std::vector< std::string > & dof_names={}) void set_position_upper_limits (const Eigen::VectorXd & positions, const std::vector< std::string > & dof_names={}) void set_positions (const Eigen::VectorXd & positions, const std::vector< std::string > & dof_names={}) void set_restitution_coeff (const std::string & body_name, double value) void set_restitution_coeff (size_t body_index, double value) void set_restitution_coeffs (double value) void set_secondary_friction_coeff (const std::string & body_name, double value) void set_secondary_friction_coeff (size_t body_index, double value) void set_secondary_friction_coeffs (double value) void set_self_collision (bool enable_self_collisions=true, bool enable_adjacent_collisions=false) void set_spring_stiffnesses (const std::vector< double > & stiffnesses, const std::vector< std::string > & dof_names={}) void set_spring_stiffnesses (double stiffness, const std::vector< std::string > & dof_names={}) void set_velocities (const Eigen::VectorXd & velocities, const std::vector< std::string > & dof_names={}) void set_velocity_lower_limits (const Eigen::VectorXd & velocities, const std::vector< std::string > & dof_names={}) void set_velocity_upper_limits (const Eigen::VectorXd & velocities, const std::vector< std::string > & dof_names={}) dart::dynamics::SkeletonPtr skeleton () std::vector< double > spring_stiffnesses (const std::vector< std::string > & dof_names={}) const void update (double t) void update_joint_dof_maps () Eigen::VectorXd vec_dof (const Eigen::VectorXd & vec, const std::vector< std::string > & dof_names) const Eigen::VectorXd velocities (const std::vector< std::string > & dof_names={}) const Eigen::VectorXd velocity_lower_limits (const std::vector< std::string > & dof_names={}) const Eigen::VectorXd velocity_upper_limits (const std::vector< std::string > & dof_names={}) const virtual ~Robot ()"},{"location":"api/classrobot__dart_1_1robots_1_1Talos/#public-static-functions-inherited-from-robot_dartrobot","title":"Public Static Functions inherited from robot_dart::Robot","text":"

See robot_dart::Robot

Type Name std::shared_ptr< Robot > create_box (const Eigen::Vector3d & dims, const Eigen::Isometry3d & tf, const std::string & type=\"free\", double mass=1.0, const Eigen::Vector4d & color=dart::Color::Red(1.0), const std::string & box_name=\"box\") std::shared_ptr< Robot > create_box (const Eigen::Vector3d & dims, const Eigen::Vector6d & pose=Eigen::Vector6d::Zero(), const std::string & type=\"free\", double mass=1.0, const Eigen::Vector4d & color=dart::Color::Red(1.0), const std::string & box_name=\"box\") std::shared_ptr< Robot > create_ellipsoid (const Eigen::Vector3d & dims, const Eigen::Isometry3d & tf, const std::string & type=\"free\", double mass=1.0, const Eigen::Vector4d & color=dart::Color::Red(1.0), const std::string & ellipsoid_name=\"ellipsoid\") std::shared_ptr< Robot > create_ellipsoid (const Eigen::Vector3d & dims, const Eigen::Vector6d & pose=Eigen::Vector6d::Zero(), const std::string & type=\"free\", double mass=1.0, const Eigen::Vector4d & color=dart::Color::Red(1.0), const std::string & ellipsoid_name=\"ellipsoid\")"},{"location":"api/classrobot__dart_1_1robots_1_1Talos/#protected-attributes","title":"Protected Attributes","text":"Type Name size_t _frequency std::shared_ptr< sensor::ForceTorque > _ft_foot_left std::shared_ptr< sensor::ForceTorque > _ft_foot_right std::shared_ptr< sensor::ForceTorque > _ft_wrist_left std::shared_ptr< sensor::ForceTorque > _ft_wrist_right std::shared_ptr< sensor::IMU > _imu torque_map_t _torques"},{"location":"api/classrobot__dart_1_1robots_1_1Talos/#protected-attributes-inherited-from-robot_dartrobot","title":"Protected Attributes inherited from robot_dart::Robot","text":"

See robot_dart::Robot

Type Name std::vector< std::pair< dart::dynamics::BodyNode *, double > > _axis_shapes bool _cast_shadows std::vector< std::shared_ptr< control::RobotControl > > _controllers std::unordered_map< std::string, size_t > _dof_map bool _is_ghost std::unordered_map< std::string, size_t > _joint_map std::string _model_filename std::vector< std::pair< std::string, std::string > > _packages std::string _robot_name dart::dynamics::SkeletonPtr _skeleton"},{"location":"api/classrobot__dart_1_1robots_1_1Talos/#protected-functions","title":"Protected Functions","text":"Type Name virtual void _post_addition (RobotDARTSimu *) overrideFunction called by RobotDARTSimu object when adding the robot to the world. virtual void _post_removal (RobotDARTSimu *) overrideFunction called by RobotDARTSimu object when removing the robot to the world."},{"location":"api/classrobot__dart_1_1robots_1_1Talos/#protected-functions-inherited-from-robot_dartrobot","title":"Protected Functions inherited from robot_dart::Robot","text":"

See robot_dart::Robot

Type Name dart::dynamics::Joint::ActuatorType _actuator_type (size_t joint_index) const std::vector< dart::dynamics::Joint::ActuatorType > _actuator_types () const std::string _get_path (const std::string & filename) const Eigen::MatrixXd _jacobian (const Eigen::MatrixXd & full_jacobian, const std::vector< std::string > & dof_names) const dart::dynamics::SkeletonPtr _load_model (const std::string & filename, const std::vector< std::pair< std::string, std::string > > & packages=std::vector< std::pair< std::string, std::string > >(), bool is_urdf_string=false) Eigen::MatrixXd _mass_matrix (const Eigen::MatrixXd & full_mass_matrix, const std::vector< std::string > & dof_names) const virtual void _post_addition (RobotDARTSimu *) Function called by RobotDARTSimu object when adding the robot to the world. virtual void _post_removal (RobotDARTSimu *) Function called by RobotDARTSimu object when removing the robot to the world. void _set_actuator_type (size_t joint_index, dart::dynamics::Joint::ActuatorType type, bool override_mimic=false, bool override_base=false) void _set_actuator_types (const std::vector< dart::dynamics::Joint::ActuatorType > & types, bool override_mimic=false, bool override_base=false) void _set_actuator_types (dart::dynamics::Joint::ActuatorType type, bool override_mimic=false, bool override_base=false) void _set_color_mode (dart::dynamics::MeshShape::ColorMode color_mode, dart::dynamics::SkeletonPtr skel) void _set_color_mode (dart::dynamics::MeshShape::ColorMode color_mode, dart::dynamics::ShapeNode * sn)"},{"location":"api/classrobot__dart_1_1robots_1_1Talos/#public-types-documentation","title":"Public Types Documentation","text":""},{"location":"api/classrobot__dart_1_1robots_1_1Talos/#typedef-torque_map_t","title":"typedef torque_map_t","text":"
using robot_dart::robots::Talos::torque_map_t =  std::unordered_map<std::string, std::shared_ptr<sensor::Torque> >;\n
"},{"location":"api/classrobot__dart_1_1robots_1_1Talos/#public-functions-documentation","title":"Public Functions Documentation","text":""},{"location":"api/classrobot__dart_1_1robots_1_1Talos/#function-talos","title":"function Talos","text":"
robot_dart::robots::Talos::Talos (\nsize_t frequency=1000,\nconst std::string & urdf=\"talos/talos.urdf\",\nconst std::vector< std::pair< std::string, std::string > > & packages=('talos_description', 'talos/talos_description')\n) 
"},{"location":"api/classrobot__dart_1_1robots_1_1Talos/#function-ft_foot_left","title":"function ft_foot_left","text":"
inline const sensor::ForceTorque & robot_dart::robots::Talos::ft_foot_left () const\n
"},{"location":"api/classrobot__dart_1_1robots_1_1Talos/#function-ft_foot_right","title":"function ft_foot_right","text":"
inline const sensor::ForceTorque & robot_dart::robots::Talos::ft_foot_right () const\n
"},{"location":"api/classrobot__dart_1_1robots_1_1Talos/#function-ft_wrist_left","title":"function ft_wrist_left","text":"
inline const sensor::ForceTorque & robot_dart::robots::Talos::ft_wrist_left () const\n
"},{"location":"api/classrobot__dart_1_1robots_1_1Talos/#function-ft_wrist_right","title":"function ft_wrist_right","text":"
inline const sensor::ForceTorque & robot_dart::robots::Talos::ft_wrist_right () const\n
"},{"location":"api/classrobot__dart_1_1robots_1_1Talos/#function-imu","title":"function imu","text":"
inline const sensor::IMU & robot_dart::robots::Talos::imu () const\n
"},{"location":"api/classrobot__dart_1_1robots_1_1Talos/#function-reset","title":"function reset","text":"
virtual void robot_dart::robots::Talos::reset () override\n

Implements robot_dart::Robot::reset

"},{"location":"api/classrobot__dart_1_1robots_1_1Talos/#function-torques","title":"function torques","text":"
inline const torque_map_t & robot_dart::robots::Talos::torques () const\n
"},{"location":"api/classrobot__dart_1_1robots_1_1Talos/#protected-attributes-documentation","title":"Protected Attributes Documentation","text":""},{"location":"api/classrobot__dart_1_1robots_1_1Talos/#variable-_frequency","title":"variable _frequency","text":"
size_t robot_dart::robots::Talos::_frequency;\n
"},{"location":"api/classrobot__dart_1_1robots_1_1Talos/#variable-_ft_foot_left","title":"variable _ft_foot_left","text":"
std::shared_ptr<sensor::ForceTorque> robot_dart::robots::Talos::_ft_foot_left;\n
"},{"location":"api/classrobot__dart_1_1robots_1_1Talos/#variable-_ft_foot_right","title":"variable _ft_foot_right","text":"
std::shared_ptr<sensor::ForceTorque> robot_dart::robots::Talos::_ft_foot_right;\n
"},{"location":"api/classrobot__dart_1_1robots_1_1Talos/#variable-_ft_wrist_left","title":"variable _ft_wrist_left","text":"
std::shared_ptr<sensor::ForceTorque> robot_dart::robots::Talos::_ft_wrist_left;\n
"},{"location":"api/classrobot__dart_1_1robots_1_1Talos/#variable-_ft_wrist_right","title":"variable _ft_wrist_right","text":"
std::shared_ptr<sensor::ForceTorque> robot_dart::robots::Talos::_ft_wrist_right;\n
"},{"location":"api/classrobot__dart_1_1robots_1_1Talos/#variable-_imu","title":"variable _imu","text":"
std::shared_ptr<sensor::IMU> robot_dart::robots::Talos::_imu;\n
"},{"location":"api/classrobot__dart_1_1robots_1_1Talos/#variable-_torques","title":"variable _torques","text":"
torque_map_t robot_dart::robots::Talos::_torques;\n
"},{"location":"api/classrobot__dart_1_1robots_1_1Talos/#protected-functions-documentation","title":"Protected Functions Documentation","text":""},{"location":"api/classrobot__dart_1_1robots_1_1Talos/#function-_post_addition","title":"function _post_addition","text":"
virtual void robot_dart::robots::Talos::_post_addition (\nRobotDARTSimu *\n) override\n

Implements robot_dart::Robot::_post_addition

"},{"location":"api/classrobot__dart_1_1robots_1_1Talos/#function-_post_removal","title":"function _post_removal","text":"
virtual void robot_dart::robots::Talos::_post_removal (\nRobotDARTSimu *\n) override\n

Implements robot_dart::Robot::_post_removal

The documentation for this class was generated from the following file robot_dart/robots/talos.hpp

"},{"location":"api/classrobot__dart_1_1robots_1_1TalosFastCollision/","title":"Class robot_dart::robots::TalosFastCollision","text":"

ClassList > robot_dart > robots > TalosFastCollision

Inherits the following classes: robot_dart::robots::Talos

"},{"location":"api/classrobot__dart_1_1robots_1_1TalosFastCollision/#public-types-inherited-from-robot_dartrobotstalos","title":"Public Types inherited from robot_dart::robots::Talos","text":"

See robot_dart::robots::Talos

Type Name typedef std::unordered_map< std::string, std::shared_ptr< sensor::Torque > > torque_map_t"},{"location":"api/classrobot__dart_1_1robots_1_1TalosFastCollision/#public-functions","title":"Public Functions","text":"Type Name TalosFastCollision (size_t frequency=1000, const std::string & urdf=\"talos/talos_fast_collision.urdf\", const std::vector< std::pair< std::string, std::string > > & packages=('talos\\_description', 'talos/talos\\_description'))"},{"location":"api/classrobot__dart_1_1robots_1_1TalosFastCollision/#public-functions-inherited-from-robot_dartrobotstalos","title":"Public Functions inherited from robot_dart::robots::Talos","text":"

See robot_dart::robots::Talos

Type Name Talos (size_t frequency=1000, const std::string & urdf=\"talos/talos.urdf\", const std::vector< std::pair< std::string, std::string > > & packages=('talos\\_description', 'talos/talos\\_description')) const sensor::ForceTorque & ft_foot_left () const const sensor::ForceTorque & ft_foot_right () const const sensor::ForceTorque & ft_wrist_left () const const sensor::ForceTorque & ft_wrist_right () const const sensor::IMU & imu () const virtual void reset () override const torque_map_t & torques () const"},{"location":"api/classrobot__dart_1_1robots_1_1TalosFastCollision/#public-functions-inherited-from-robot_dartrobot","title":"Public Functions inherited from robot_dart::Robot","text":"

See robot_dart::Robot

Type Name Robot (const std::string & model_file, const std::vector< std::pair< std::string, std::string > > & packages, const std::string & robot_name=\"robot\", bool is_urdf_string=false, bool cast_shadows=true) Robot (const std::string & model_file, const std::string & robot_name=\"robot\", bool is_urdf_string=false, bool cast_shadows=true) Robot (dart::dynamics::SkeletonPtr skeleton, const std::string & robot_name=\"robot\", bool cast_shadows=true) Eigen::VectorXd acceleration_lower_limits (const std::vector< std::string > & dof_names={}) const Eigen::VectorXd acceleration_upper_limits (const std::vector< std::string > & dof_names={}) const Eigen::VectorXd accelerations (const std::vector< std::string > & dof_names={}) const std::vector< std::shared_ptr< control::RobotControl > > active_controllers () const std::string actuator_type (const std::string & joint_name) const std::vector< std::string > actuator_types (const std::vector< std::string > & joint_names={}) const void add_body_mass (const std::string & body_name, double mass) void add_body_mass (size_t body_index, double mass) void add_controller (const std::shared_ptr< control::RobotControl > & controller, double weight=1.0) void add_external_force (const std::string & body_name, const Eigen::Vector3d & force, const Eigen::Vector3d & offset=Eigen::Vector3d::Zero(), bool force_local=false, bool offset_local=true) void add_external_force (size_t body_index, const Eigen::Vector3d & force, const Eigen::Vector3d & offset=Eigen::Vector3d::Zero(), bool force_local=false, bool offset_local=true) void add_external_torque (const std::string & body_name, const Eigen::Vector3d & torque, bool local=false) void add_external_torque (size_t body_index, const Eigen::Vector3d & torque, bool local=false) bool adjacent_colliding () const Eigen::MatrixXd aug_mass_matrix (const std::vector< std::string > & dof_names={}) const Eigen::Isometry3d base_pose () const Eigen::Vector6d base_pose_vec () const Eigen::Vector6d body_acceleration (const std::string & body_name) const Eigen::Vector6d body_acceleration (size_t body_index) const size_t body_index (const std::string & body_name) const double body_mass (const std::string & body_name) const double body_mass (size_t body_index) const std::string body_name (size_t body_index) const std::vector< std::string > body_names () const dart::dynamics::BodyNode * body_node (const std::string & body_name) dart::dynamics::BodyNode * body_node (size_t body_index) Eigen::Isometry3d body_pose (const std::string & body_name) const Eigen::Isometry3d body_pose (size_t body_index) const Eigen::Vector6d body_pose_vec (const std::string & body_name) const Eigen::Vector6d body_pose_vec (size_t body_index) const Eigen::Vector6d body_velocity (const std::string & body_name) const Eigen::Vector6d body_velocity (size_t body_index) const bool cast_shadows () const void clear_controllers () void clear_external_forces () void clear_internal_forces () std::shared_ptr< Robot > clone () const std::shared_ptr< Robot > clone_ghost (const std::string & ghost_name=\"ghost\", const Eigen::Vector4d & ghost_color={0.3, 0.3, 0.3, 0.7}) const Eigen::Vector3d com () const Eigen::Vector6d com_acceleration () const Eigen::MatrixXd com_jacobian (const std::vector< std::string > & dof_names={}) const Eigen::MatrixXd com_jacobian_deriv (const std::vector< std::string > & dof_names={}) const Eigen::Vector6d com_velocity () const Eigen::VectorXd commands (const std::vector< std::string > & dof_names={}) const Eigen::VectorXd constraint_forces (const std::vector< std::string > & dof_names={}) const std::shared_ptr< control::RobotControl > controller (size_t index) const std::vector< std::shared_ptr< control::RobotControl > > controllers () const Eigen::VectorXd coriolis_forces (const std::vector< std::string > & dof_names={}) const Eigen::VectorXd coriolis_gravity_forces (const std::vector< std::string > & dof_names={}) const std::vector< double > coulomb_coeffs (const std::vector< std::string > & dof_names={}) const std::vector< double > damping_coeffs (const std::vector< std::string > & dof_names={}) const dart::dynamics::DegreeOfFreedom * dof (const std::string & dof_name) dart::dynamics::DegreeOfFreedom * dof (size_t dof_index) size_t dof_index (const std::string & dof_name) const const std::unordered_map< std::string, size_t > & dof_map () const std::string dof_name (size_t dof_index) const std::vector< std::string > dof_names (bool filter_mimics=false, bool filter_locked=false, bool filter_passive=false) const const std::vector< std::pair< dart::dynamics::BodyNode *, double > > & drawing_axes () const Eigen::Vector6d external_forces (const std::string & body_name) const Eigen::Vector6d external_forces (size_t body_index) const void fix_to_world () bool fixed () const Eigen::VectorXd force_lower_limits (const std::vector< std::string > & dof_names={}) const void force_position_bounds () std::pair< Eigen::Vector6d, Eigen::Vector6d > force_torque (size_t joint_index) const Eigen::VectorXd force_upper_limits (const std::vector< std::string > & dof_names={}) const Eigen::VectorXd forces (const std::vector< std::string > & dof_names={}) const bool free () const void free_from_world (const Eigen::Vector6d & pose=Eigen::Vector6d::Zero()) double friction_coeff (const std::string & body_name) double friction_coeff (size_t body_index) Eigen::Vector3d friction_dir (const std::string & body_name) Eigen::Vector3d friction_dir (size_t body_index) bool ghost () const Eigen::VectorXd gravity_forces (const std::vector< std::string > & dof_names={}) const Eigen::MatrixXd inv_aug_mass_matrix (const std::vector< std::string > & dof_names={}) const Eigen::MatrixXd inv_mass_matrix (const std::vector< std::string > & dof_names={}) const Eigen::MatrixXd jacobian (const std::string & body_name, const std::vector< std::string > & dof_names={}) const Eigen::MatrixXd jacobian_deriv (const std::string & body_name, const std::vector< std::string > & dof_names={}) const dart::dynamics::Joint * joint (const std::string & joint_name) dart::dynamics::Joint * joint (size_t joint_index) size_t joint_index (const std::string & joint_name) const const std::unordered_map< std::string, size_t > & joint_map () const std::string joint_name (size_t joint_index) const std::vector< std::string > joint_names () const std::vector< std::string > locked_dof_names () const Eigen::MatrixXd mass_matrix (const std::vector< std::string > & dof_names={}) const std::vector< std::string > mimic_dof_names () const const std::string & model_filename () const const std::vector< std::pair< std::string, std::string > > & model_packages () const const std::string & name () const size_t num_bodies () const size_t num_controllers () const size_t num_dofs () const size_t num_joints () const std::vector< std::string > passive_dof_names () const std::vector< bool > position_enforced (const std::vector< std::string > & dof_names={}) const Eigen::VectorXd position_lower_limits (const std::vector< std::string > & dof_names={}) const Eigen::VectorXd position_upper_limits (const std::vector< std::string > & dof_names={}) const Eigen::VectorXd positions (const std::vector< std::string > & dof_names={}) const void reinit_controllers () void remove_all_drawing_axis () void remove_controller (const std::shared_ptr< control::RobotControl > & controller) void remove_controller (size_t index) virtual void reset () void reset_commands () double restitution_coeff (const std::string & body_name) double restitution_coeff (size_t body_index) double secondary_friction_coeff (const std::string & body_name) double secondary_friction_coeff (size_t body_index) bool self_colliding () const void set_acceleration_lower_limits (const Eigen::VectorXd & accelerations, const std::vector< std::string > & dof_names={}) void set_acceleration_upper_limits (const Eigen::VectorXd & accelerations, const std::vector< std::string > & dof_names={}) void set_accelerations (const Eigen::VectorXd & accelerations, const std::vector< std::string > & dof_names={}) void set_actuator_type (const std::string & type, const std::string & joint_name, bool override_mimic=false, bool override_base=false) void set_actuator_types (const std::string & type, const std::vector< std::string > & joint_names={}, bool override_mimic=false, bool override_base=false) void set_base_pose (const Eigen::Isometry3d & tf) void set_base_pose (const Eigen::Vector6d & pose) set base pose: pose is a 6D vector (first 3D orientation in angle-axis and last 3D translation) void set_body_mass (const std::string & body_name, double mass) void set_body_mass (size_t body_index, double mass) void set_body_name (size_t body_index, const std::string & body_name) void set_cast_shadows (bool cast_shadows=true) void set_color_mode (const std::string & color_mode) void set_color_mode (const std::string & color_mode, const std::string & body_name) void set_commands (const Eigen::VectorXd & commands, const std::vector< std::string > & dof_names={}) void set_coulomb_coeffs (const std::vector< double > & cfrictions, const std::vector< std::string > & dof_names={}) void set_coulomb_coeffs (double cfriction, const std::vector< std::string > & dof_names={}) void set_damping_coeffs (const std::vector< double > & damps, const std::vector< std::string > & dof_names={}) void set_damping_coeffs (double damp, const std::vector< std::string > & dof_names={}) void set_draw_axis (const std::string & body_name, double size=0.25) void set_external_force (const std::string & body_name, const Eigen::Vector3d & force, const Eigen::Vector3d & offset=Eigen::Vector3d::Zero(), bool force_local=false, bool offset_local=true) void set_external_force (size_t body_index, const Eigen::Vector3d & force, const Eigen::Vector3d & offset=Eigen::Vector3d::Zero(), bool force_local=false, bool offset_local=true) void set_external_torque (const std::string & body_name, const Eigen::Vector3d & torque, bool local=false) void set_external_torque (size_t body_index, const Eigen::Vector3d & torque, bool local=false) void set_force_lower_limits (const Eigen::VectorXd & forces, const std::vector< std::string > & dof_names={}) void set_force_upper_limits (const Eigen::VectorXd & forces, const std::vector< std::string > & dof_names={}) void set_forces (const Eigen::VectorXd & forces, const std::vector< std::string > & dof_names={}) void set_friction_coeff (const std::string & body_name, double value) void set_friction_coeff (size_t body_index, double value) void set_friction_coeffs (double value) void set_friction_dir (const std::string & body_name, const Eigen::Vector3d & direction) void set_friction_dir (size_t body_index, const Eigen::Vector3d & direction) void set_ghost (bool ghost=true) void set_joint_name (size_t joint_index, const std::string & joint_name) void set_mimic (const std::string & joint_name, const std::string & mimic_joint_name, double multiplier=1., double offset=0.) void set_position_enforced (const std::vector< bool > & enforced, const std::vector< std::string > & dof_names={}) void set_position_enforced (bool enforced, const std::vector< std::string > & dof_names={}) void set_position_lower_limits (const Eigen::VectorXd & positions, const std::vector< std::string > & dof_names={}) void set_position_upper_limits (const Eigen::VectorXd & positions, const std::vector< std::string > & dof_names={}) void set_positions (const Eigen::VectorXd & positions, const std::vector< std::string > & dof_names={}) void set_restitution_coeff (const std::string & body_name, double value) void set_restitution_coeff (size_t body_index, double value) void set_restitution_coeffs (double value) void set_secondary_friction_coeff (const std::string & body_name, double value) void set_secondary_friction_coeff (size_t body_index, double value) void set_secondary_friction_coeffs (double value) void set_self_collision (bool enable_self_collisions=true, bool enable_adjacent_collisions=false) void set_spring_stiffnesses (const std::vector< double > & stiffnesses, const std::vector< std::string > & dof_names={}) void set_spring_stiffnesses (double stiffness, const std::vector< std::string > & dof_names={}) void set_velocities (const Eigen::VectorXd & velocities, const std::vector< std::string > & dof_names={}) void set_velocity_lower_limits (const Eigen::VectorXd & velocities, const std::vector< std::string > & dof_names={}) void set_velocity_upper_limits (const Eigen::VectorXd & velocities, const std::vector< std::string > & dof_names={}) dart::dynamics::SkeletonPtr skeleton () std::vector< double > spring_stiffnesses (const std::vector< std::string > & dof_names={}) const void update (double t) void update_joint_dof_maps () Eigen::VectorXd vec_dof (const Eigen::VectorXd & vec, const std::vector< std::string > & dof_names) const Eigen::VectorXd velocities (const std::vector< std::string > & dof_names={}) const Eigen::VectorXd velocity_lower_limits (const std::vector< std::string > & dof_names={}) const Eigen::VectorXd velocity_upper_limits (const std::vector< std::string > & dof_names={}) const virtual ~Robot ()"},{"location":"api/classrobot__dart_1_1robots_1_1TalosFastCollision/#public-static-functions","title":"Public Static Functions","text":"Type Name std::vector< std::tuple< std::string, uint32_t, uint32_t > > collision_vec ()"},{"location":"api/classrobot__dart_1_1robots_1_1TalosFastCollision/#public-static-functions-inherited-from-robot_dartrobot","title":"Public Static Functions inherited from robot_dart::Robot","text":"

See robot_dart::Robot

Type Name std::shared_ptr< Robot > create_box (const Eigen::Vector3d & dims, const Eigen::Isometry3d & tf, const std::string & type=\"free\", double mass=1.0, const Eigen::Vector4d & color=dart::Color::Red(1.0), const std::string & box_name=\"box\") std::shared_ptr< Robot > create_box (const Eigen::Vector3d & dims, const Eigen::Vector6d & pose=Eigen::Vector6d::Zero(), const std::string & type=\"free\", double mass=1.0, const Eigen::Vector4d & color=dart::Color::Red(1.0), const std::string & box_name=\"box\") std::shared_ptr< Robot > create_ellipsoid (const Eigen::Vector3d & dims, const Eigen::Isometry3d & tf, const std::string & type=\"free\", double mass=1.0, const Eigen::Vector4d & color=dart::Color::Red(1.0), const std::string & ellipsoid_name=\"ellipsoid\") std::shared_ptr< Robot > create_ellipsoid (const Eigen::Vector3d & dims, const Eigen::Vector6d & pose=Eigen::Vector6d::Zero(), const std::string & type=\"free\", double mass=1.0, const Eigen::Vector4d & color=dart::Color::Red(1.0), const std::string & ellipsoid_name=\"ellipsoid\")"},{"location":"api/classrobot__dart_1_1robots_1_1TalosFastCollision/#protected-attributes-inherited-from-robot_dartrobotstalos","title":"Protected Attributes inherited from robot_dart::robots::Talos","text":"

See robot_dart::robots::Talos

Type Name size_t _frequency std::shared_ptr< sensor::ForceTorque > _ft_foot_left std::shared_ptr< sensor::ForceTorque > _ft_foot_right std::shared_ptr< sensor::ForceTorque > _ft_wrist_left std::shared_ptr< sensor::ForceTorque > _ft_wrist_right std::shared_ptr< sensor::IMU > _imu torque_map_t _torques"},{"location":"api/classrobot__dart_1_1robots_1_1TalosFastCollision/#protected-attributes-inherited-from-robot_dartrobot","title":"Protected Attributes inherited from robot_dart::Robot","text":"

See robot_dart::Robot

Type Name std::vector< std::pair< dart::dynamics::BodyNode *, double > > _axis_shapes bool _cast_shadows std::vector< std::shared_ptr< control::RobotControl > > _controllers std::unordered_map< std::string, size_t > _dof_map bool _is_ghost std::unordered_map< std::string, size_t > _joint_map std::string _model_filename std::vector< std::pair< std::string, std::string > > _packages std::string _robot_name dart::dynamics::SkeletonPtr _skeleton"},{"location":"api/classrobot__dart_1_1robots_1_1TalosFastCollision/#protected-functions","title":"Protected Functions","text":"Type Name virtual void _post_addition (RobotDARTSimu *) overrideFunction called by RobotDARTSimu object when adding the robot to the world."},{"location":"api/classrobot__dart_1_1robots_1_1TalosFastCollision/#protected-functions-inherited-from-robot_dartrobotstalos","title":"Protected Functions inherited from robot_dart::robots::Talos","text":"

See robot_dart::robots::Talos

Type Name virtual void _post_addition (RobotDARTSimu *) overrideFunction called by RobotDARTSimu object when adding the robot to the world. virtual void _post_removal (RobotDARTSimu *) overrideFunction called by RobotDARTSimu object when removing the robot to the world."},{"location":"api/classrobot__dart_1_1robots_1_1TalosFastCollision/#protected-functions-inherited-from-robot_dartrobot","title":"Protected Functions inherited from robot_dart::Robot","text":"

See robot_dart::Robot

Type Name dart::dynamics::Joint::ActuatorType _actuator_type (size_t joint_index) const std::vector< dart::dynamics::Joint::ActuatorType > _actuator_types () const std::string _get_path (const std::string & filename) const Eigen::MatrixXd _jacobian (const Eigen::MatrixXd & full_jacobian, const std::vector< std::string > & dof_names) const dart::dynamics::SkeletonPtr _load_model (const std::string & filename, const std::vector< std::pair< std::string, std::string > > & packages=std::vector< std::pair< std::string, std::string > >(), bool is_urdf_string=false) Eigen::MatrixXd _mass_matrix (const Eigen::MatrixXd & full_mass_matrix, const std::vector< std::string > & dof_names) const virtual void _post_addition (RobotDARTSimu *) Function called by RobotDARTSimu object when adding the robot to the world. virtual void _post_removal (RobotDARTSimu *) Function called by RobotDARTSimu object when removing the robot to the world. void _set_actuator_type (size_t joint_index, dart::dynamics::Joint::ActuatorType type, bool override_mimic=false, bool override_base=false) void _set_actuator_types (const std::vector< dart::dynamics::Joint::ActuatorType > & types, bool override_mimic=false, bool override_base=false) void _set_actuator_types (dart::dynamics::Joint::ActuatorType type, bool override_mimic=false, bool override_base=false) void _set_color_mode (dart::dynamics::MeshShape::ColorMode color_mode, dart::dynamics::SkeletonPtr skel) void _set_color_mode (dart::dynamics::MeshShape::ColorMode color_mode, dart::dynamics::ShapeNode * sn)"},{"location":"api/classrobot__dart_1_1robots_1_1TalosFastCollision/#public-functions-documentation","title":"Public Functions Documentation","text":""},{"location":"api/classrobot__dart_1_1robots_1_1TalosFastCollision/#function-talosfastcollision","title":"function TalosFastCollision","text":"
inline robot_dart::robots::TalosFastCollision::TalosFastCollision (\nsize_t frequency=1000,\nconst std::string & urdf=\"talos/talos_fast_collision.urdf\",\nconst std::vector< std::pair< std::string, std::string > > & packages=('talos_description', 'talos/talos_description')\n) 
"},{"location":"api/classrobot__dart_1_1robots_1_1TalosFastCollision/#public-static-functions-documentation","title":"Public Static Functions Documentation","text":""},{"location":"api/classrobot__dart_1_1robots_1_1TalosFastCollision/#function-collision_vec","title":"function collision_vec","text":"
static std::vector< std::tuple< std::string, uint32_t, uint32_t > > robot_dart::robots::TalosFastCollision::collision_vec () 
"},{"location":"api/classrobot__dart_1_1robots_1_1TalosFastCollision/#protected-functions-documentation","title":"Protected Functions Documentation","text":""},{"location":"api/classrobot__dart_1_1robots_1_1TalosFastCollision/#function-_post_addition","title":"function _post_addition","text":"
virtual void robot_dart::robots::TalosFastCollision::_post_addition (\nRobotDARTSimu *\n) override\n

Implements robot_dart::robots::Talos::_post_addition

The documentation for this class was generated from the following file robot_dart/robots/talos.hpp

"},{"location":"api/classrobot__dart_1_1robots_1_1TalosLight/","title":"Class robot_dart::robots::TalosLight","text":"

ClassList > robot_dart > robots > TalosLight

Inherits the following classes: robot_dart::robots::Talos

"},{"location":"api/classrobot__dart_1_1robots_1_1TalosLight/#public-types-inherited-from-robot_dartrobotstalos","title":"Public Types inherited from robot_dart::robots::Talos","text":"

See robot_dart::robots::Talos

Type Name typedef std::unordered_map< std::string, std::shared_ptr< sensor::Torque > > torque_map_t"},{"location":"api/classrobot__dart_1_1robots_1_1TalosLight/#public-functions","title":"Public Functions","text":"Type Name TalosLight (size_t frequency=1000, const std::string & urdf=\"talos/talos_fast.urdf\", const std::vector< std::pair< std::string, std::string > > & packages=('talos\\_description', 'talos/talos\\_description'))"},{"location":"api/classrobot__dart_1_1robots_1_1TalosLight/#public-functions-inherited-from-robot_dartrobotstalos","title":"Public Functions inherited from robot_dart::robots::Talos","text":"

See robot_dart::robots::Talos

Type Name Talos (size_t frequency=1000, const std::string & urdf=\"talos/talos.urdf\", const std::vector< std::pair< std::string, std::string > > & packages=('talos\\_description', 'talos/talos\\_description')) const sensor::ForceTorque & ft_foot_left () const const sensor::ForceTorque & ft_foot_right () const const sensor::ForceTorque & ft_wrist_left () const const sensor::ForceTorque & ft_wrist_right () const const sensor::IMU & imu () const virtual void reset () override const torque_map_t & torques () const"},{"location":"api/classrobot__dart_1_1robots_1_1TalosLight/#public-functions-inherited-from-robot_dartrobot","title":"Public Functions inherited from robot_dart::Robot","text":"

See robot_dart::Robot

Type Name Robot (const std::string & model_file, const std::vector< std::pair< std::string, std::string > > & packages, const std::string & robot_name=\"robot\", bool is_urdf_string=false, bool cast_shadows=true) Robot (const std::string & model_file, const std::string & robot_name=\"robot\", bool is_urdf_string=false, bool cast_shadows=true) Robot (dart::dynamics::SkeletonPtr skeleton, const std::string & robot_name=\"robot\", bool cast_shadows=true) Eigen::VectorXd acceleration_lower_limits (const std::vector< std::string > & dof_names={}) const Eigen::VectorXd acceleration_upper_limits (const std::vector< std::string > & dof_names={}) const Eigen::VectorXd accelerations (const std::vector< std::string > & dof_names={}) const std::vector< std::shared_ptr< control::RobotControl > > active_controllers () const std::string actuator_type (const std::string & joint_name) const std::vector< std::string > actuator_types (const std::vector< std::string > & joint_names={}) const void add_body_mass (const std::string & body_name, double mass) void add_body_mass (size_t body_index, double mass) void add_controller (const std::shared_ptr< control::RobotControl > & controller, double weight=1.0) void add_external_force (const std::string & body_name, const Eigen::Vector3d & force, const Eigen::Vector3d & offset=Eigen::Vector3d::Zero(), bool force_local=false, bool offset_local=true) void add_external_force (size_t body_index, const Eigen::Vector3d & force, const Eigen::Vector3d & offset=Eigen::Vector3d::Zero(), bool force_local=false, bool offset_local=true) void add_external_torque (const std::string & body_name, const Eigen::Vector3d & torque, bool local=false) void add_external_torque (size_t body_index, const Eigen::Vector3d & torque, bool local=false) bool adjacent_colliding () const Eigen::MatrixXd aug_mass_matrix (const std::vector< std::string > & dof_names={}) const Eigen::Isometry3d base_pose () const Eigen::Vector6d base_pose_vec () const Eigen::Vector6d body_acceleration (const std::string & body_name) const Eigen::Vector6d body_acceleration (size_t body_index) const size_t body_index (const std::string & body_name) const double body_mass (const std::string & body_name) const double body_mass (size_t body_index) const std::string body_name (size_t body_index) const std::vector< std::string > body_names () const dart::dynamics::BodyNode * body_node (const std::string & body_name) dart::dynamics::BodyNode * body_node (size_t body_index) Eigen::Isometry3d body_pose (const std::string & body_name) const Eigen::Isometry3d body_pose (size_t body_index) const Eigen::Vector6d body_pose_vec (const std::string & body_name) const Eigen::Vector6d body_pose_vec (size_t body_index) const Eigen::Vector6d body_velocity (const std::string & body_name) const Eigen::Vector6d body_velocity (size_t body_index) const bool cast_shadows () const void clear_controllers () void clear_external_forces () void clear_internal_forces () std::shared_ptr< Robot > clone () const std::shared_ptr< Robot > clone_ghost (const std::string & ghost_name=\"ghost\", const Eigen::Vector4d & ghost_color={0.3, 0.3, 0.3, 0.7}) const Eigen::Vector3d com () const Eigen::Vector6d com_acceleration () const Eigen::MatrixXd com_jacobian (const std::vector< std::string > & dof_names={}) const Eigen::MatrixXd com_jacobian_deriv (const std::vector< std::string > & dof_names={}) const Eigen::Vector6d com_velocity () const Eigen::VectorXd commands (const std::vector< std::string > & dof_names={}) const Eigen::VectorXd constraint_forces (const std::vector< std::string > & dof_names={}) const std::shared_ptr< control::RobotControl > controller (size_t index) const std::vector< std::shared_ptr< control::RobotControl > > controllers () const Eigen::VectorXd coriolis_forces (const std::vector< std::string > & dof_names={}) const Eigen::VectorXd coriolis_gravity_forces (const std::vector< std::string > & dof_names={}) const std::vector< double > coulomb_coeffs (const std::vector< std::string > & dof_names={}) const std::vector< double > damping_coeffs (const std::vector< std::string > & dof_names={}) const dart::dynamics::DegreeOfFreedom * dof (const std::string & dof_name) dart::dynamics::DegreeOfFreedom * dof (size_t dof_index) size_t dof_index (const std::string & dof_name) const const std::unordered_map< std::string, size_t > & dof_map () const std::string dof_name (size_t dof_index) const std::vector< std::string > dof_names (bool filter_mimics=false, bool filter_locked=false, bool filter_passive=false) const const std::vector< std::pair< dart::dynamics::BodyNode *, double > > & drawing_axes () const Eigen::Vector6d external_forces (const std::string & body_name) const Eigen::Vector6d external_forces (size_t body_index) const void fix_to_world () bool fixed () const Eigen::VectorXd force_lower_limits (const std::vector< std::string > & dof_names={}) const void force_position_bounds () std::pair< Eigen::Vector6d, Eigen::Vector6d > force_torque (size_t joint_index) const Eigen::VectorXd force_upper_limits (const std::vector< std::string > & dof_names={}) const Eigen::VectorXd forces (const std::vector< std::string > & dof_names={}) const bool free () const void free_from_world (const Eigen::Vector6d & pose=Eigen::Vector6d::Zero()) double friction_coeff (const std::string & body_name) double friction_coeff (size_t body_index) Eigen::Vector3d friction_dir (const std::string & body_name) Eigen::Vector3d friction_dir (size_t body_index) bool ghost () const Eigen::VectorXd gravity_forces (const std::vector< std::string > & dof_names={}) const Eigen::MatrixXd inv_aug_mass_matrix (const std::vector< std::string > & dof_names={}) const Eigen::MatrixXd inv_mass_matrix (const std::vector< std::string > & dof_names={}) const Eigen::MatrixXd jacobian (const std::string & body_name, const std::vector< std::string > & dof_names={}) const Eigen::MatrixXd jacobian_deriv (const std::string & body_name, const std::vector< std::string > & dof_names={}) const dart::dynamics::Joint * joint (const std::string & joint_name) dart::dynamics::Joint * joint (size_t joint_index) size_t joint_index (const std::string & joint_name) const const std::unordered_map< std::string, size_t > & joint_map () const std::string joint_name (size_t joint_index) const std::vector< std::string > joint_names () const std::vector< std::string > locked_dof_names () const Eigen::MatrixXd mass_matrix (const std::vector< std::string > & dof_names={}) const std::vector< std::string > mimic_dof_names () const const std::string & model_filename () const const std::vector< std::pair< std::string, std::string > > & model_packages () const const std::string & name () const size_t num_bodies () const size_t num_controllers () const size_t num_dofs () const size_t num_joints () const std::vector< std::string > passive_dof_names () const std::vector< bool > position_enforced (const std::vector< std::string > & dof_names={}) const Eigen::VectorXd position_lower_limits (const std::vector< std::string > & dof_names={}) const Eigen::VectorXd position_upper_limits (const std::vector< std::string > & dof_names={}) const Eigen::VectorXd positions (const std::vector< std::string > & dof_names={}) const void reinit_controllers () void remove_all_drawing_axis () void remove_controller (const std::shared_ptr< control::RobotControl > & controller) void remove_controller (size_t index) virtual void reset () void reset_commands () double restitution_coeff (const std::string & body_name) double restitution_coeff (size_t body_index) double secondary_friction_coeff (const std::string & body_name) double secondary_friction_coeff (size_t body_index) bool self_colliding () const void set_acceleration_lower_limits (const Eigen::VectorXd & accelerations, const std::vector< std::string > & dof_names={}) void set_acceleration_upper_limits (const Eigen::VectorXd & accelerations, const std::vector< std::string > & dof_names={}) void set_accelerations (const Eigen::VectorXd & accelerations, const std::vector< std::string > & dof_names={}) void set_actuator_type (const std::string & type, const std::string & joint_name, bool override_mimic=false, bool override_base=false) void set_actuator_types (const std::string & type, const std::vector< std::string > & joint_names={}, bool override_mimic=false, bool override_base=false) void set_base_pose (const Eigen::Isometry3d & tf) void set_base_pose (const Eigen::Vector6d & pose) set base pose: pose is a 6D vector (first 3D orientation in angle-axis and last 3D translation) void set_body_mass (const std::string & body_name, double mass) void set_body_mass (size_t body_index, double mass) void set_body_name (size_t body_index, const std::string & body_name) void set_cast_shadows (bool cast_shadows=true) void set_color_mode (const std::string & color_mode) void set_color_mode (const std::string & color_mode, const std::string & body_name) void set_commands (const Eigen::VectorXd & commands, const std::vector< std::string > & dof_names={}) void set_coulomb_coeffs (const std::vector< double > & cfrictions, const std::vector< std::string > & dof_names={}) void set_coulomb_coeffs (double cfriction, const std::vector< std::string > & dof_names={}) void set_damping_coeffs (const std::vector< double > & damps, const std::vector< std::string > & dof_names={}) void set_damping_coeffs (double damp, const std::vector< std::string > & dof_names={}) void set_draw_axis (const std::string & body_name, double size=0.25) void set_external_force (const std::string & body_name, const Eigen::Vector3d & force, const Eigen::Vector3d & offset=Eigen::Vector3d::Zero(), bool force_local=false, bool offset_local=true) void set_external_force (size_t body_index, const Eigen::Vector3d & force, const Eigen::Vector3d & offset=Eigen::Vector3d::Zero(), bool force_local=false, bool offset_local=true) void set_external_torque (const std::string & body_name, const Eigen::Vector3d & torque, bool local=false) void set_external_torque (size_t body_index, const Eigen::Vector3d & torque, bool local=false) void set_force_lower_limits (const Eigen::VectorXd & forces, const std::vector< std::string > & dof_names={}) void set_force_upper_limits (const Eigen::VectorXd & forces, const std::vector< std::string > & dof_names={}) void set_forces (const Eigen::VectorXd & forces, const std::vector< std::string > & dof_names={}) void set_friction_coeff (const std::string & body_name, double value) void set_friction_coeff (size_t body_index, double value) void set_friction_coeffs (double value) void set_friction_dir (const std::string & body_name, const Eigen::Vector3d & direction) void set_friction_dir (size_t body_index, const Eigen::Vector3d & direction) void set_ghost (bool ghost=true) void set_joint_name (size_t joint_index, const std::string & joint_name) void set_mimic (const std::string & joint_name, const std::string & mimic_joint_name, double multiplier=1., double offset=0.) void set_position_enforced (const std::vector< bool > & enforced, const std::vector< std::string > & dof_names={}) void set_position_enforced (bool enforced, const std::vector< std::string > & dof_names={}) void set_position_lower_limits (const Eigen::VectorXd & positions, const std::vector< std::string > & dof_names={}) void set_position_upper_limits (const Eigen::VectorXd & positions, const std::vector< std::string > & dof_names={}) void set_positions (const Eigen::VectorXd & positions, const std::vector< std::string > & dof_names={}) void set_restitution_coeff (const std::string & body_name, double value) void set_restitution_coeff (size_t body_index, double value) void set_restitution_coeffs (double value) void set_secondary_friction_coeff (const std::string & body_name, double value) void set_secondary_friction_coeff (size_t body_index, double value) void set_secondary_friction_coeffs (double value) void set_self_collision (bool enable_self_collisions=true, bool enable_adjacent_collisions=false) void set_spring_stiffnesses (const std::vector< double > & stiffnesses, const std::vector< std::string > & dof_names={}) void set_spring_stiffnesses (double stiffness, const std::vector< std::string > & dof_names={}) void set_velocities (const Eigen::VectorXd & velocities, const std::vector< std::string > & dof_names={}) void set_velocity_lower_limits (const Eigen::VectorXd & velocities, const std::vector< std::string > & dof_names={}) void set_velocity_upper_limits (const Eigen::VectorXd & velocities, const std::vector< std::string > & dof_names={}) dart::dynamics::SkeletonPtr skeleton () std::vector< double > spring_stiffnesses (const std::vector< std::string > & dof_names={}) const void update (double t) void update_joint_dof_maps () Eigen::VectorXd vec_dof (const Eigen::VectorXd & vec, const std::vector< std::string > & dof_names) const Eigen::VectorXd velocities (const std::vector< std::string > & dof_names={}) const Eigen::VectorXd velocity_lower_limits (const std::vector< std::string > & dof_names={}) const Eigen::VectorXd velocity_upper_limits (const std::vector< std::string > & dof_names={}) const virtual ~Robot ()"},{"location":"api/classrobot__dart_1_1robots_1_1TalosLight/#public-static-functions-inherited-from-robot_dartrobot","title":"Public Static Functions inherited from robot_dart::Robot","text":"

See robot_dart::Robot

Type Name std::shared_ptr< Robot > create_box (const Eigen::Vector3d & dims, const Eigen::Isometry3d & tf, const std::string & type=\"free\", double mass=1.0, const Eigen::Vector4d & color=dart::Color::Red(1.0), const std::string & box_name=\"box\") std::shared_ptr< Robot > create_box (const Eigen::Vector3d & dims, const Eigen::Vector6d & pose=Eigen::Vector6d::Zero(), const std::string & type=\"free\", double mass=1.0, const Eigen::Vector4d & color=dart::Color::Red(1.0), const std::string & box_name=\"box\") std::shared_ptr< Robot > create_ellipsoid (const Eigen::Vector3d & dims, const Eigen::Isometry3d & tf, const std::string & type=\"free\", double mass=1.0, const Eigen::Vector4d & color=dart::Color::Red(1.0), const std::string & ellipsoid_name=\"ellipsoid\") std::shared_ptr< Robot > create_ellipsoid (const Eigen::Vector3d & dims, const Eigen::Vector6d & pose=Eigen::Vector6d::Zero(), const std::string & type=\"free\", double mass=1.0, const Eigen::Vector4d & color=dart::Color::Red(1.0), const std::string & ellipsoid_name=\"ellipsoid\")"},{"location":"api/classrobot__dart_1_1robots_1_1TalosLight/#protected-attributes-inherited-from-robot_dartrobotstalos","title":"Protected Attributes inherited from robot_dart::robots::Talos","text":"

See robot_dart::robots::Talos

Type Name size_t _frequency std::shared_ptr< sensor::ForceTorque > _ft_foot_left std::shared_ptr< sensor::ForceTorque > _ft_foot_right std::shared_ptr< sensor::ForceTorque > _ft_wrist_left std::shared_ptr< sensor::ForceTorque > _ft_wrist_right std::shared_ptr< sensor::IMU > _imu torque_map_t _torques"},{"location":"api/classrobot__dart_1_1robots_1_1TalosLight/#protected-attributes-inherited-from-robot_dartrobot","title":"Protected Attributes inherited from robot_dart::Robot","text":"

See robot_dart::Robot

Type Name std::vector< std::pair< dart::dynamics::BodyNode *, double > > _axis_shapes bool _cast_shadows std::vector< std::shared_ptr< control::RobotControl > > _controllers std::unordered_map< std::string, size_t > _dof_map bool _is_ghost std::unordered_map< std::string, size_t > _joint_map std::string _model_filename std::vector< std::pair< std::string, std::string > > _packages std::string _robot_name dart::dynamics::SkeletonPtr _skeleton"},{"location":"api/classrobot__dart_1_1robots_1_1TalosLight/#protected-functions-inherited-from-robot_dartrobotstalos","title":"Protected Functions inherited from robot_dart::robots::Talos","text":"

See robot_dart::robots::Talos

Type Name virtual void _post_addition (RobotDARTSimu *) overrideFunction called by RobotDARTSimu object when adding the robot to the world. virtual void _post_removal (RobotDARTSimu *) overrideFunction called by RobotDARTSimu object when removing the robot to the world."},{"location":"api/classrobot__dart_1_1robots_1_1TalosLight/#protected-functions-inherited-from-robot_dartrobot","title":"Protected Functions inherited from robot_dart::Robot","text":"

See robot_dart::Robot

Type Name dart::dynamics::Joint::ActuatorType _actuator_type (size_t joint_index) const std::vector< dart::dynamics::Joint::ActuatorType > _actuator_types () const std::string _get_path (const std::string & filename) const Eigen::MatrixXd _jacobian (const Eigen::MatrixXd & full_jacobian, const std::vector< std::string > & dof_names) const dart::dynamics::SkeletonPtr _load_model (const std::string & filename, const std::vector< std::pair< std::string, std::string > > & packages=std::vector< std::pair< std::string, std::string > >(), bool is_urdf_string=false) Eigen::MatrixXd _mass_matrix (const Eigen::MatrixXd & full_mass_matrix, const std::vector< std::string > & dof_names) const virtual void _post_addition (RobotDARTSimu *) Function called by RobotDARTSimu object when adding the robot to the world. virtual void _post_removal (RobotDARTSimu *) Function called by RobotDARTSimu object when removing the robot to the world. void _set_actuator_type (size_t joint_index, dart::dynamics::Joint::ActuatorType type, bool override_mimic=false, bool override_base=false) void _set_actuator_types (const std::vector< dart::dynamics::Joint::ActuatorType > & types, bool override_mimic=false, bool override_base=false) void _set_actuator_types (dart::dynamics::Joint::ActuatorType type, bool override_mimic=false, bool override_base=false) void _set_color_mode (dart::dynamics::MeshShape::ColorMode color_mode, dart::dynamics::SkeletonPtr skel) void _set_color_mode (dart::dynamics::MeshShape::ColorMode color_mode, dart::dynamics::ShapeNode * sn)"},{"location":"api/classrobot__dart_1_1robots_1_1TalosLight/#public-functions-documentation","title":"Public Functions Documentation","text":""},{"location":"api/classrobot__dart_1_1robots_1_1TalosLight/#function-taloslight","title":"function TalosLight","text":"
inline robot_dart::robots::TalosLight::TalosLight (\nsize_t frequency=1000,\nconst std::string & urdf=\"talos/talos_fast.urdf\",\nconst std::vector< std::pair< std::string, std::string > > & packages=('talos_description', 'talos/talos_description')\n) 

The documentation for this class was generated from the following file robot_dart/robots/talos.hpp

"},{"location":"api/classrobot__dart_1_1robots_1_1Tiago/","title":"Class robot_dart::robots::Tiago","text":"

ClassList > robot_dart > robots > Tiago

datasheet: https://pal-robotics.com/wp-content/uploads/2021/07/Datasheet-complete_TIAGo-2021.pdf __

Inherits the following classes: robot_dart::Robot

"},{"location":"api/classrobot__dart_1_1robots_1_1Tiago/#public-functions","title":"Public Functions","text":"Type Name Tiago (size_t frequency=1000, const std::string & urdf=\"tiago/tiago_steel.urdf\", const std::vector< std::pair< std::string, std::string > > & packages=('tiago\\_description', 'tiago/tiago\\_description')) std::vector< std::string > caster_joints () const const sensor::ForceTorque & ft_wrist () const virtual void reset () override void set_actuator_type (const std::string & type, const std::string & joint_name, bool override_mimic=false, bool override_base=false, bool override_caster=false) void set_actuator_types (const std::string & type, const std::vector< std::string > & joint_names={}, bool override_mimic=false, bool override_base=false, bool override_caster=false)"},{"location":"api/classrobot__dart_1_1robots_1_1Tiago/#public-functions-inherited-from-robot_dartrobot","title":"Public Functions inherited from robot_dart::Robot","text":"

See robot_dart::Robot

Type Name Robot (const std::string & model_file, const std::vector< std::pair< std::string, std::string > > & packages, const std::string & robot_name=\"robot\", bool is_urdf_string=false, bool cast_shadows=true) Robot (const std::string & model_file, const std::string & robot_name=\"robot\", bool is_urdf_string=false, bool cast_shadows=true) Robot (dart::dynamics::SkeletonPtr skeleton, const std::string & robot_name=\"robot\", bool cast_shadows=true) Eigen::VectorXd acceleration_lower_limits (const std::vector< std::string > & dof_names={}) const Eigen::VectorXd acceleration_upper_limits (const std::vector< std::string > & dof_names={}) const Eigen::VectorXd accelerations (const std::vector< std::string > & dof_names={}) const std::vector< std::shared_ptr< control::RobotControl > > active_controllers () const std::string actuator_type (const std::string & joint_name) const std::vector< std::string > actuator_types (const std::vector< std::string > & joint_names={}) const void add_body_mass (const std::string & body_name, double mass) void add_body_mass (size_t body_index, double mass) void add_controller (const std::shared_ptr< control::RobotControl > & controller, double weight=1.0) void add_external_force (const std::string & body_name, const Eigen::Vector3d & force, const Eigen::Vector3d & offset=Eigen::Vector3d::Zero(), bool force_local=false, bool offset_local=true) void add_external_force (size_t body_index, const Eigen::Vector3d & force, const Eigen::Vector3d & offset=Eigen::Vector3d::Zero(), bool force_local=false, bool offset_local=true) void add_external_torque (const std::string & body_name, const Eigen::Vector3d & torque, bool local=false) void add_external_torque (size_t body_index, const Eigen::Vector3d & torque, bool local=false) bool adjacent_colliding () const Eigen::MatrixXd aug_mass_matrix (const std::vector< std::string > & dof_names={}) const Eigen::Isometry3d base_pose () const Eigen::Vector6d base_pose_vec () const Eigen::Vector6d body_acceleration (const std::string & body_name) const Eigen::Vector6d body_acceleration (size_t body_index) const size_t body_index (const std::string & body_name) const double body_mass (const std::string & body_name) const double body_mass (size_t body_index) const std::string body_name (size_t body_index) const std::vector< std::string > body_names () const dart::dynamics::BodyNode * body_node (const std::string & body_name) dart::dynamics::BodyNode * body_node (size_t body_index) Eigen::Isometry3d body_pose (const std::string & body_name) const Eigen::Isometry3d body_pose (size_t body_index) const Eigen::Vector6d body_pose_vec (const std::string & body_name) const Eigen::Vector6d body_pose_vec (size_t body_index) const Eigen::Vector6d body_velocity (const std::string & body_name) const Eigen::Vector6d body_velocity (size_t body_index) const bool cast_shadows () const void clear_controllers () void clear_external_forces () void clear_internal_forces () std::shared_ptr< Robot > clone () const std::shared_ptr< Robot > clone_ghost (const std::string & ghost_name=\"ghost\", const Eigen::Vector4d & ghost_color={0.3, 0.3, 0.3, 0.7}) const Eigen::Vector3d com () const Eigen::Vector6d com_acceleration () const Eigen::MatrixXd com_jacobian (const std::vector< std::string > & dof_names={}) const Eigen::MatrixXd com_jacobian_deriv (const std::vector< std::string > & dof_names={}) const Eigen::Vector6d com_velocity () const Eigen::VectorXd commands (const std::vector< std::string > & dof_names={}) const Eigen::VectorXd constraint_forces (const std::vector< std::string > & dof_names={}) const std::shared_ptr< control::RobotControl > controller (size_t index) const std::vector< std::shared_ptr< control::RobotControl > > controllers () const Eigen::VectorXd coriolis_forces (const std::vector< std::string > & dof_names={}) const Eigen::VectorXd coriolis_gravity_forces (const std::vector< std::string > & dof_names={}) const std::vector< double > coulomb_coeffs (const std::vector< std::string > & dof_names={}) const std::vector< double > damping_coeffs (const std::vector< std::string > & dof_names={}) const dart::dynamics::DegreeOfFreedom * dof (const std::string & dof_name) dart::dynamics::DegreeOfFreedom * dof (size_t dof_index) size_t dof_index (const std::string & dof_name) const const std::unordered_map< std::string, size_t > & dof_map () const std::string dof_name (size_t dof_index) const std::vector< std::string > dof_names (bool filter_mimics=false, bool filter_locked=false, bool filter_passive=false) const const std::vector< std::pair< dart::dynamics::BodyNode *, double > > & drawing_axes () const Eigen::Vector6d external_forces (const std::string & body_name) const Eigen::Vector6d external_forces (size_t body_index) const void fix_to_world () bool fixed () const Eigen::VectorXd force_lower_limits (const std::vector< std::string > & dof_names={}) const void force_position_bounds () std::pair< Eigen::Vector6d, Eigen::Vector6d > force_torque (size_t joint_index) const Eigen::VectorXd force_upper_limits (const std::vector< std::string > & dof_names={}) const Eigen::VectorXd forces (const std::vector< std::string > & dof_names={}) const bool free () const void free_from_world (const Eigen::Vector6d & pose=Eigen::Vector6d::Zero()) double friction_coeff (const std::string & body_name) double friction_coeff (size_t body_index) Eigen::Vector3d friction_dir (const std::string & body_name) Eigen::Vector3d friction_dir (size_t body_index) bool ghost () const Eigen::VectorXd gravity_forces (const std::vector< std::string > & dof_names={}) const Eigen::MatrixXd inv_aug_mass_matrix (const std::vector< std::string > & dof_names={}) const Eigen::MatrixXd inv_mass_matrix (const std::vector< std::string > & dof_names={}) const Eigen::MatrixXd jacobian (const std::string & body_name, const std::vector< std::string > & dof_names={}) const Eigen::MatrixXd jacobian_deriv (const std::string & body_name, const std::vector< std::string > & dof_names={}) const dart::dynamics::Joint * joint (const std::string & joint_name) dart::dynamics::Joint * joint (size_t joint_index) size_t joint_index (const std::string & joint_name) const const std::unordered_map< std::string, size_t > & joint_map () const std::string joint_name (size_t joint_index) const std::vector< std::string > joint_names () const std::vector< std::string > locked_dof_names () const Eigen::MatrixXd mass_matrix (const std::vector< std::string > & dof_names={}) const std::vector< std::string > mimic_dof_names () const const std::string & model_filename () const const std::vector< std::pair< std::string, std::string > > & model_packages () const const std::string & name () const size_t num_bodies () const size_t num_controllers () const size_t num_dofs () const size_t num_joints () const std::vector< std::string > passive_dof_names () const std::vector< bool > position_enforced (const std::vector< std::string > & dof_names={}) const Eigen::VectorXd position_lower_limits (const std::vector< std::string > & dof_names={}) const Eigen::VectorXd position_upper_limits (const std::vector< std::string > & dof_names={}) const Eigen::VectorXd positions (const std::vector< std::string > & dof_names={}) const void reinit_controllers () void remove_all_drawing_axis () void remove_controller (const std::shared_ptr< control::RobotControl > & controller) void remove_controller (size_t index) virtual void reset () void reset_commands () double restitution_coeff (const std::string & body_name) double restitution_coeff (size_t body_index) double secondary_friction_coeff (const std::string & body_name) double secondary_friction_coeff (size_t body_index) bool self_colliding () const void set_acceleration_lower_limits (const Eigen::VectorXd & accelerations, const std::vector< std::string > & dof_names={}) void set_acceleration_upper_limits (const Eigen::VectorXd & accelerations, const std::vector< std::string > & dof_names={}) void set_accelerations (const Eigen::VectorXd & accelerations, const std::vector< std::string > & dof_names={}) void set_actuator_type (const std::string & type, const std::string & joint_name, bool override_mimic=false, bool override_base=false) void set_actuator_types (const std::string & type, const std::vector< std::string > & joint_names={}, bool override_mimic=false, bool override_base=false) void set_base_pose (const Eigen::Isometry3d & tf) void set_base_pose (const Eigen::Vector6d & pose) set base pose: pose is a 6D vector (first 3D orientation in angle-axis and last 3D translation) void set_body_mass (const std::string & body_name, double mass) void set_body_mass (size_t body_index, double mass) void set_body_name (size_t body_index, const std::string & body_name) void set_cast_shadows (bool cast_shadows=true) void set_color_mode (const std::string & color_mode) void set_color_mode (const std::string & color_mode, const std::string & body_name) void set_commands (const Eigen::VectorXd & commands, const std::vector< std::string > & dof_names={}) void set_coulomb_coeffs (const std::vector< double > & cfrictions, const std::vector< std::string > & dof_names={}) void set_coulomb_coeffs (double cfriction, const std::vector< std::string > & dof_names={}) void set_damping_coeffs (const std::vector< double > & damps, const std::vector< std::string > & dof_names={}) void set_damping_coeffs (double damp, const std::vector< std::string > & dof_names={}) void set_draw_axis (const std::string & body_name, double size=0.25) void set_external_force (const std::string & body_name, const Eigen::Vector3d & force, const Eigen::Vector3d & offset=Eigen::Vector3d::Zero(), bool force_local=false, bool offset_local=true) void set_external_force (size_t body_index, const Eigen::Vector3d & force, const Eigen::Vector3d & offset=Eigen::Vector3d::Zero(), bool force_local=false, bool offset_local=true) void set_external_torque (const std::string & body_name, const Eigen::Vector3d & torque, bool local=false) void set_external_torque (size_t body_index, const Eigen::Vector3d & torque, bool local=false) void set_force_lower_limits (const Eigen::VectorXd & forces, const std::vector< std::string > & dof_names={}) void set_force_upper_limits (const Eigen::VectorXd & forces, const std::vector< std::string > & dof_names={}) void set_forces (const Eigen::VectorXd & forces, const std::vector< std::string > & dof_names={}) void set_friction_coeff (const std::string & body_name, double value) void set_friction_coeff (size_t body_index, double value) void set_friction_coeffs (double value) void set_friction_dir (const std::string & body_name, const Eigen::Vector3d & direction) void set_friction_dir (size_t body_index, const Eigen::Vector3d & direction) void set_ghost (bool ghost=true) void set_joint_name (size_t joint_index, const std::string & joint_name) void set_mimic (const std::string & joint_name, const std::string & mimic_joint_name, double multiplier=1., double offset=0.) void set_position_enforced (const std::vector< bool > & enforced, const std::vector< std::string > & dof_names={}) void set_position_enforced (bool enforced, const std::vector< std::string > & dof_names={}) void set_position_lower_limits (const Eigen::VectorXd & positions, const std::vector< std::string > & dof_names={}) void set_position_upper_limits (const Eigen::VectorXd & positions, const std::vector< std::string > & dof_names={}) void set_positions (const Eigen::VectorXd & positions, const std::vector< std::string > & dof_names={}) void set_restitution_coeff (const std::string & body_name, double value) void set_restitution_coeff (size_t body_index, double value) void set_restitution_coeffs (double value) void set_secondary_friction_coeff (const std::string & body_name, double value) void set_secondary_friction_coeff (size_t body_index, double value) void set_secondary_friction_coeffs (double value) void set_self_collision (bool enable_self_collisions=true, bool enable_adjacent_collisions=false) void set_spring_stiffnesses (const std::vector< double > & stiffnesses, const std::vector< std::string > & dof_names={}) void set_spring_stiffnesses (double stiffness, const std::vector< std::string > & dof_names={}) void set_velocities (const Eigen::VectorXd & velocities, const std::vector< std::string > & dof_names={}) void set_velocity_lower_limits (const Eigen::VectorXd & velocities, const std::vector< std::string > & dof_names={}) void set_velocity_upper_limits (const Eigen::VectorXd & velocities, const std::vector< std::string > & dof_names={}) dart::dynamics::SkeletonPtr skeleton () std::vector< double > spring_stiffnesses (const std::vector< std::string > & dof_names={}) const void update (double t) void update_joint_dof_maps () Eigen::VectorXd vec_dof (const Eigen::VectorXd & vec, const std::vector< std::string > & dof_names) const Eigen::VectorXd velocities (const std::vector< std::string > & dof_names={}) const Eigen::VectorXd velocity_lower_limits (const std::vector< std::string > & dof_names={}) const Eigen::VectorXd velocity_upper_limits (const std::vector< std::string > & dof_names={}) const virtual ~Robot ()"},{"location":"api/classrobot__dart_1_1robots_1_1Tiago/#public-static-functions-inherited-from-robot_dartrobot","title":"Public Static Functions inherited from robot_dart::Robot","text":"

See robot_dart::Robot

Type Name std::shared_ptr< Robot > create_box (const Eigen::Vector3d & dims, const Eigen::Isometry3d & tf, const std::string & type=\"free\", double mass=1.0, const Eigen::Vector4d & color=dart::Color::Red(1.0), const std::string & box_name=\"box\") std::shared_ptr< Robot > create_box (const Eigen::Vector3d & dims, const Eigen::Vector6d & pose=Eigen::Vector6d::Zero(), const std::string & type=\"free\", double mass=1.0, const Eigen::Vector4d & color=dart::Color::Red(1.0), const std::string & box_name=\"box\") std::shared_ptr< Robot > create_ellipsoid (const Eigen::Vector3d & dims, const Eigen::Isometry3d & tf, const std::string & type=\"free\", double mass=1.0, const Eigen::Vector4d & color=dart::Color::Red(1.0), const std::string & ellipsoid_name=\"ellipsoid\") std::shared_ptr< Robot > create_ellipsoid (const Eigen::Vector3d & dims, const Eigen::Vector6d & pose=Eigen::Vector6d::Zero(), const std::string & type=\"free\", double mass=1.0, const Eigen::Vector4d & color=dart::Color::Red(1.0), const std::string & ellipsoid_name=\"ellipsoid\")"},{"location":"api/classrobot__dart_1_1robots_1_1Tiago/#protected-attributes","title":"Protected Attributes","text":"Type Name std::shared_ptr< sensor::ForceTorque > _ft_wrist"},{"location":"api/classrobot__dart_1_1robots_1_1Tiago/#protected-attributes-inherited-from-robot_dartrobot","title":"Protected Attributes inherited from robot_dart::Robot","text":"

See robot_dart::Robot

Type Name std::vector< std::pair< dart::dynamics::BodyNode *, double > > _axis_shapes bool _cast_shadows std::vector< std::shared_ptr< control::RobotControl > > _controllers std::unordered_map< std::string, size_t > _dof_map bool _is_ghost std::unordered_map< std::string, size_t > _joint_map std::string _model_filename std::vector< std::pair< std::string, std::string > > _packages std::string _robot_name dart::dynamics::SkeletonPtr _skeleton"},{"location":"api/classrobot__dart_1_1robots_1_1Tiago/#protected-functions","title":"Protected Functions","text":"Type Name virtual void _post_addition (RobotDARTSimu *) overrideFunction called by RobotDARTSimu object when adding the robot to the world. virtual void _post_removal (RobotDARTSimu *) overrideFunction called by RobotDARTSimu object when removing the robot to the world."},{"location":"api/classrobot__dart_1_1robots_1_1Tiago/#protected-functions-inherited-from-robot_dartrobot","title":"Protected Functions inherited from robot_dart::Robot","text":"

See robot_dart::Robot

Type Name dart::dynamics::Joint::ActuatorType _actuator_type (size_t joint_index) const std::vector< dart::dynamics::Joint::ActuatorType > _actuator_types () const std::string _get_path (const std::string & filename) const Eigen::MatrixXd _jacobian (const Eigen::MatrixXd & full_jacobian, const std::vector< std::string > & dof_names) const dart::dynamics::SkeletonPtr _load_model (const std::string & filename, const std::vector< std::pair< std::string, std::string > > & packages=std::vector< std::pair< std::string, std::string > >(), bool is_urdf_string=false) Eigen::MatrixXd _mass_matrix (const Eigen::MatrixXd & full_mass_matrix, const std::vector< std::string > & dof_names) const virtual void _post_addition (RobotDARTSimu *) Function called by RobotDARTSimu object when adding the robot to the world. virtual void _post_removal (RobotDARTSimu *) Function called by RobotDARTSimu object when removing the robot to the world. void _set_actuator_type (size_t joint_index, dart::dynamics::Joint::ActuatorType type, bool override_mimic=false, bool override_base=false) void _set_actuator_types (const std::vector< dart::dynamics::Joint::ActuatorType > & types, bool override_mimic=false, bool override_base=false) void _set_actuator_types (dart::dynamics::Joint::ActuatorType type, bool override_mimic=false, bool override_base=false) void _set_color_mode (dart::dynamics::MeshShape::ColorMode color_mode, dart::dynamics::SkeletonPtr skel) void _set_color_mode (dart::dynamics::MeshShape::ColorMode color_mode, dart::dynamics::ShapeNode * sn)"},{"location":"api/classrobot__dart_1_1robots_1_1Tiago/#public-functions-documentation","title":"Public Functions Documentation","text":""},{"location":"api/classrobot__dart_1_1robots_1_1Tiago/#function-tiago","title":"function Tiago","text":"
robot_dart::robots::Tiago::Tiago (\nsize_t frequency=1000,\nconst std::string & urdf=\"tiago/tiago_steel.urdf\",\nconst std::vector< std::pair< std::string, std::string > > & packages=('tiago_description', 'tiago/tiago_description')\n) 
"},{"location":"api/classrobot__dart_1_1robots_1_1Tiago/#function-caster_joints","title":"function caster_joints","text":"
inline std::vector< std::string > robot_dart::robots::Tiago::caster_joints () const\n
"},{"location":"api/classrobot__dart_1_1robots_1_1Tiago/#function-ft_wrist","title":"function ft_wrist","text":"
inline const sensor::ForceTorque & robot_dart::robots::Tiago::ft_wrist () const\n
"},{"location":"api/classrobot__dart_1_1robots_1_1Tiago/#function-reset","title":"function reset","text":"
virtual void robot_dart::robots::Tiago::reset () override\n

Implements robot_dart::Robot::reset

"},{"location":"api/classrobot__dart_1_1robots_1_1Tiago/#function-set_actuator_type","title":"function set_actuator_type","text":"
void robot_dart::robots::Tiago::set_actuator_type (\nconst std::string & type,\nconst std::string & joint_name,\nbool override_mimic=false,\nbool override_base=false,\nbool override_caster=false\n) 
"},{"location":"api/classrobot__dart_1_1robots_1_1Tiago/#function-set_actuator_types","title":"function set_actuator_types","text":"
void robot_dart::robots::Tiago::set_actuator_types (\nconst std::string & type,\nconst std::vector< std::string > & joint_names={},\nbool override_mimic=false,\nbool override_base=false,\nbool override_caster=false\n) 
"},{"location":"api/classrobot__dart_1_1robots_1_1Tiago/#protected-attributes-documentation","title":"Protected Attributes Documentation","text":""},{"location":"api/classrobot__dart_1_1robots_1_1Tiago/#variable-_ft_wrist","title":"variable _ft_wrist","text":"
std::shared_ptr<sensor::ForceTorque> robot_dart::robots::Tiago::_ft_wrist;\n
"},{"location":"api/classrobot__dart_1_1robots_1_1Tiago/#protected-functions-documentation","title":"Protected Functions Documentation","text":""},{"location":"api/classrobot__dart_1_1robots_1_1Tiago/#function-_post_addition","title":"function _post_addition","text":"
virtual void robot_dart::robots::Tiago::_post_addition (\nRobotDARTSimu *\n) override\n

Implements robot_dart::Robot::_post_addition

"},{"location":"api/classrobot__dart_1_1robots_1_1Tiago/#function-_post_removal","title":"function _post_removal","text":"
virtual void robot_dart::robots::Tiago::_post_removal (\nRobotDARTSimu *\n) override\n

Implements robot_dart::Robot::_post_removal

The documentation for this class was generated from the following file robot_dart/robots/tiago.hpp

"},{"location":"api/classrobot__dart_1_1robots_1_1Ur3e/","title":"Class robot_dart::robots::Ur3e","text":"

ClassList > robot_dart > robots > Ur3e

Inherits the following classes: robot_dart::Robot

Inherited by the following classes: robot_dart::robots::Ur3eHand

"},{"location":"api/classrobot__dart_1_1robots_1_1Ur3e/#public-functions","title":"Public Functions","text":"Type Name Ur3e (size_t frequency=1000, const std::string & urdf=\"ur3e/ur3e.urdf\", const std::vector< std::pair< std::string, std::string > > & packages=('ur3e\\_description', 'ur3e/ur3e\\_description')) const sensor::ForceTorque & ft_wrist () const"},{"location":"api/classrobot__dart_1_1robots_1_1Ur3e/#public-functions-inherited-from-robot_dartrobot","title":"Public Functions inherited from robot_dart::Robot","text":"

See robot_dart::Robot

Type Name Robot (const std::string & model_file, const std::vector< std::pair< std::string, std::string > > & packages, const std::string & robot_name=\"robot\", bool is_urdf_string=false, bool cast_shadows=true) Robot (const std::string & model_file, const std::string & robot_name=\"robot\", bool is_urdf_string=false, bool cast_shadows=true) Robot (dart::dynamics::SkeletonPtr skeleton, const std::string & robot_name=\"robot\", bool cast_shadows=true) Eigen::VectorXd acceleration_lower_limits (const std::vector< std::string > & dof_names={}) const Eigen::VectorXd acceleration_upper_limits (const std::vector< std::string > & dof_names={}) const Eigen::VectorXd accelerations (const std::vector< std::string > & dof_names={}) const std::vector< std::shared_ptr< control::RobotControl > > active_controllers () const std::string actuator_type (const std::string & joint_name) const std::vector< std::string > actuator_types (const std::vector< std::string > & joint_names={}) const void add_body_mass (const std::string & body_name, double mass) void add_body_mass (size_t body_index, double mass) void add_controller (const std::shared_ptr< control::RobotControl > & controller, double weight=1.0) void add_external_force (const std::string & body_name, const Eigen::Vector3d & force, const Eigen::Vector3d & offset=Eigen::Vector3d::Zero(), bool force_local=false, bool offset_local=true) void add_external_force (size_t body_index, const Eigen::Vector3d & force, const Eigen::Vector3d & offset=Eigen::Vector3d::Zero(), bool force_local=false, bool offset_local=true) void add_external_torque (const std::string & body_name, const Eigen::Vector3d & torque, bool local=false) void add_external_torque (size_t body_index, const Eigen::Vector3d & torque, bool local=false) bool adjacent_colliding () const Eigen::MatrixXd aug_mass_matrix (const std::vector< std::string > & dof_names={}) const Eigen::Isometry3d base_pose () const Eigen::Vector6d base_pose_vec () const Eigen::Vector6d body_acceleration (const std::string & body_name) const Eigen::Vector6d body_acceleration (size_t body_index) const size_t body_index (const std::string & body_name) const double body_mass (const std::string & body_name) const double body_mass (size_t body_index) const std::string body_name (size_t body_index) const std::vector< std::string > body_names () const dart::dynamics::BodyNode * body_node (const std::string & body_name) dart::dynamics::BodyNode * body_node (size_t body_index) Eigen::Isometry3d body_pose (const std::string & body_name) const Eigen::Isometry3d body_pose (size_t body_index) const Eigen::Vector6d body_pose_vec (const std::string & body_name) const Eigen::Vector6d body_pose_vec (size_t body_index) const Eigen::Vector6d body_velocity (const std::string & body_name) const Eigen::Vector6d body_velocity (size_t body_index) const bool cast_shadows () const void clear_controllers () void clear_external_forces () void clear_internal_forces () std::shared_ptr< Robot > clone () const std::shared_ptr< Robot > clone_ghost (const std::string & ghost_name=\"ghost\", const Eigen::Vector4d & ghost_color={0.3, 0.3, 0.3, 0.7}) const Eigen::Vector3d com () const Eigen::Vector6d com_acceleration () const Eigen::MatrixXd com_jacobian (const std::vector< std::string > & dof_names={}) const Eigen::MatrixXd com_jacobian_deriv (const std::vector< std::string > & dof_names={}) const Eigen::Vector6d com_velocity () const Eigen::VectorXd commands (const std::vector< std::string > & dof_names={}) const Eigen::VectorXd constraint_forces (const std::vector< std::string > & dof_names={}) const std::shared_ptr< control::RobotControl > controller (size_t index) const std::vector< std::shared_ptr< control::RobotControl > > controllers () const Eigen::VectorXd coriolis_forces (const std::vector< std::string > & dof_names={}) const Eigen::VectorXd coriolis_gravity_forces (const std::vector< std::string > & dof_names={}) const std::vector< double > coulomb_coeffs (const std::vector< std::string > & dof_names={}) const std::vector< double > damping_coeffs (const std::vector< std::string > & dof_names={}) const dart::dynamics::DegreeOfFreedom * dof (const std::string & dof_name) dart::dynamics::DegreeOfFreedom * dof (size_t dof_index) size_t dof_index (const std::string & dof_name) const const std::unordered_map< std::string, size_t > & dof_map () const std::string dof_name (size_t dof_index) const std::vector< std::string > dof_names (bool filter_mimics=false, bool filter_locked=false, bool filter_passive=false) const const std::vector< std::pair< dart::dynamics::BodyNode *, double > > & drawing_axes () const Eigen::Vector6d external_forces (const std::string & body_name) const Eigen::Vector6d external_forces (size_t body_index) const void fix_to_world () bool fixed () const Eigen::VectorXd force_lower_limits (const std::vector< std::string > & dof_names={}) const void force_position_bounds () std::pair< Eigen::Vector6d, Eigen::Vector6d > force_torque (size_t joint_index) const Eigen::VectorXd force_upper_limits (const std::vector< std::string > & dof_names={}) const Eigen::VectorXd forces (const std::vector< std::string > & dof_names={}) const bool free () const void free_from_world (const Eigen::Vector6d & pose=Eigen::Vector6d::Zero()) double friction_coeff (const std::string & body_name) double friction_coeff (size_t body_index) Eigen::Vector3d friction_dir (const std::string & body_name) Eigen::Vector3d friction_dir (size_t body_index) bool ghost () const Eigen::VectorXd gravity_forces (const std::vector< std::string > & dof_names={}) const Eigen::MatrixXd inv_aug_mass_matrix (const std::vector< std::string > & dof_names={}) const Eigen::MatrixXd inv_mass_matrix (const std::vector< std::string > & dof_names={}) const Eigen::MatrixXd jacobian (const std::string & body_name, const std::vector< std::string > & dof_names={}) const Eigen::MatrixXd jacobian_deriv (const std::string & body_name, const std::vector< std::string > & dof_names={}) const dart::dynamics::Joint * joint (const std::string & joint_name) dart::dynamics::Joint * joint (size_t joint_index) size_t joint_index (const std::string & joint_name) const const std::unordered_map< std::string, size_t > & joint_map () const std::string joint_name (size_t joint_index) const std::vector< std::string > joint_names () const std::vector< std::string > locked_dof_names () const Eigen::MatrixXd mass_matrix (const std::vector< std::string > & dof_names={}) const std::vector< std::string > mimic_dof_names () const const std::string & model_filename () const const std::vector< std::pair< std::string, std::string > > & model_packages () const const std::string & name () const size_t num_bodies () const size_t num_controllers () const size_t num_dofs () const size_t num_joints () const std::vector< std::string > passive_dof_names () const std::vector< bool > position_enforced (const std::vector< std::string > & dof_names={}) const Eigen::VectorXd position_lower_limits (const std::vector< std::string > & dof_names={}) const Eigen::VectorXd position_upper_limits (const std::vector< std::string > & dof_names={}) const Eigen::VectorXd positions (const std::vector< std::string > & dof_names={}) const void reinit_controllers () void remove_all_drawing_axis () void remove_controller (const std::shared_ptr< control::RobotControl > & controller) void remove_controller (size_t index) virtual void reset () void reset_commands () double restitution_coeff (const std::string & body_name) double restitution_coeff (size_t body_index) double secondary_friction_coeff (const std::string & body_name) double secondary_friction_coeff (size_t body_index) bool self_colliding () const void set_acceleration_lower_limits (const Eigen::VectorXd & accelerations, const std::vector< std::string > & dof_names={}) void set_acceleration_upper_limits (const Eigen::VectorXd & accelerations, const std::vector< std::string > & dof_names={}) void set_accelerations (const Eigen::VectorXd & accelerations, const std::vector< std::string > & dof_names={}) void set_actuator_type (const std::string & type, const std::string & joint_name, bool override_mimic=false, bool override_base=false) void set_actuator_types (const std::string & type, const std::vector< std::string > & joint_names={}, bool override_mimic=false, bool override_base=false) void set_base_pose (const Eigen::Isometry3d & tf) void set_base_pose (const Eigen::Vector6d & pose) set base pose: pose is a 6D vector (first 3D orientation in angle-axis and last 3D translation) void set_body_mass (const std::string & body_name, double mass) void set_body_mass (size_t body_index, double mass) void set_body_name (size_t body_index, const std::string & body_name) void set_cast_shadows (bool cast_shadows=true) void set_color_mode (const std::string & color_mode) void set_color_mode (const std::string & color_mode, const std::string & body_name) void set_commands (const Eigen::VectorXd & commands, const std::vector< std::string > & dof_names={}) void set_coulomb_coeffs (const std::vector< double > & cfrictions, const std::vector< std::string > & dof_names={}) void set_coulomb_coeffs (double cfriction, const std::vector< std::string > & dof_names={}) void set_damping_coeffs (const std::vector< double > & damps, const std::vector< std::string > & dof_names={}) void set_damping_coeffs (double damp, const std::vector< std::string > & dof_names={}) void set_draw_axis (const std::string & body_name, double size=0.25) void set_external_force (const std::string & body_name, const Eigen::Vector3d & force, const Eigen::Vector3d & offset=Eigen::Vector3d::Zero(), bool force_local=false, bool offset_local=true) void set_external_force (size_t body_index, const Eigen::Vector3d & force, const Eigen::Vector3d & offset=Eigen::Vector3d::Zero(), bool force_local=false, bool offset_local=true) void set_external_torque (const std::string & body_name, const Eigen::Vector3d & torque, bool local=false) void set_external_torque (size_t body_index, const Eigen::Vector3d & torque, bool local=false) void set_force_lower_limits (const Eigen::VectorXd & forces, const std::vector< std::string > & dof_names={}) void set_force_upper_limits (const Eigen::VectorXd & forces, const std::vector< std::string > & dof_names={}) void set_forces (const Eigen::VectorXd & forces, const std::vector< std::string > & dof_names={}) void set_friction_coeff (const std::string & body_name, double value) void set_friction_coeff (size_t body_index, double value) void set_friction_coeffs (double value) void set_friction_dir (const std::string & body_name, const Eigen::Vector3d & direction) void set_friction_dir (size_t body_index, const Eigen::Vector3d & direction) void set_ghost (bool ghost=true) void set_joint_name (size_t joint_index, const std::string & joint_name) void set_mimic (const std::string & joint_name, const std::string & mimic_joint_name, double multiplier=1., double offset=0.) void set_position_enforced (const std::vector< bool > & enforced, const std::vector< std::string > & dof_names={}) void set_position_enforced (bool enforced, const std::vector< std::string > & dof_names={}) void set_position_lower_limits (const Eigen::VectorXd & positions, const std::vector< std::string > & dof_names={}) void set_position_upper_limits (const Eigen::VectorXd & positions, const std::vector< std::string > & dof_names={}) void set_positions (const Eigen::VectorXd & positions, const std::vector< std::string > & dof_names={}) void set_restitution_coeff (const std::string & body_name, double value) void set_restitution_coeff (size_t body_index, double value) void set_restitution_coeffs (double value) void set_secondary_friction_coeff (const std::string & body_name, double value) void set_secondary_friction_coeff (size_t body_index, double value) void set_secondary_friction_coeffs (double value) void set_self_collision (bool enable_self_collisions=true, bool enable_adjacent_collisions=false) void set_spring_stiffnesses (const std::vector< double > & stiffnesses, const std::vector< std::string > & dof_names={}) void set_spring_stiffnesses (double stiffness, const std::vector< std::string > & dof_names={}) void set_velocities (const Eigen::VectorXd & velocities, const std::vector< std::string > & dof_names={}) void set_velocity_lower_limits (const Eigen::VectorXd & velocities, const std::vector< std::string > & dof_names={}) void set_velocity_upper_limits (const Eigen::VectorXd & velocities, const std::vector< std::string > & dof_names={}) dart::dynamics::SkeletonPtr skeleton () std::vector< double > spring_stiffnesses (const std::vector< std::string > & dof_names={}) const void update (double t) void update_joint_dof_maps () Eigen::VectorXd vec_dof (const Eigen::VectorXd & vec, const std::vector< std::string > & dof_names) const Eigen::VectorXd velocities (const std::vector< std::string > & dof_names={}) const Eigen::VectorXd velocity_lower_limits (const std::vector< std::string > & dof_names={}) const Eigen::VectorXd velocity_upper_limits (const std::vector< std::string > & dof_names={}) const virtual ~Robot ()"},{"location":"api/classrobot__dart_1_1robots_1_1Ur3e/#public-static-functions-inherited-from-robot_dartrobot","title":"Public Static Functions inherited from robot_dart::Robot","text":"

See robot_dart::Robot

Type Name std::shared_ptr< Robot > create_box (const Eigen::Vector3d & dims, const Eigen::Isometry3d & tf, const std::string & type=\"free\", double mass=1.0, const Eigen::Vector4d & color=dart::Color::Red(1.0), const std::string & box_name=\"box\") std::shared_ptr< Robot > create_box (const Eigen::Vector3d & dims, const Eigen::Vector6d & pose=Eigen::Vector6d::Zero(), const std::string & type=\"free\", double mass=1.0, const Eigen::Vector4d & color=dart::Color::Red(1.0), const std::string & box_name=\"box\") std::shared_ptr< Robot > create_ellipsoid (const Eigen::Vector3d & dims, const Eigen::Isometry3d & tf, const std::string & type=\"free\", double mass=1.0, const Eigen::Vector4d & color=dart::Color::Red(1.0), const std::string & ellipsoid_name=\"ellipsoid\") std::shared_ptr< Robot > create_ellipsoid (const Eigen::Vector3d & dims, const Eigen::Vector6d & pose=Eigen::Vector6d::Zero(), const std::string & type=\"free\", double mass=1.0, const Eigen::Vector4d & color=dart::Color::Red(1.0), const std::string & ellipsoid_name=\"ellipsoid\")"},{"location":"api/classrobot__dart_1_1robots_1_1Ur3e/#protected-attributes","title":"Protected Attributes","text":"Type Name std::shared_ptr< sensor::ForceTorque > _ft_wrist"},{"location":"api/classrobot__dart_1_1robots_1_1Ur3e/#protected-attributes-inherited-from-robot_dartrobot","title":"Protected Attributes inherited from robot_dart::Robot","text":"

See robot_dart::Robot

Type Name std::vector< std::pair< dart::dynamics::BodyNode *, double > > _axis_shapes bool _cast_shadows std::vector< std::shared_ptr< control::RobotControl > > _controllers std::unordered_map< std::string, size_t > _dof_map bool _is_ghost std::unordered_map< std::string, size_t > _joint_map std::string _model_filename std::vector< std::pair< std::string, std::string > > _packages std::string _robot_name dart::dynamics::SkeletonPtr _skeleton"},{"location":"api/classrobot__dart_1_1robots_1_1Ur3e/#protected-functions","title":"Protected Functions","text":"Type Name virtual void _post_addition (RobotDARTSimu *) overrideFunction called by RobotDARTSimu object when adding the robot to the world. virtual void _post_removal (RobotDARTSimu *) overrideFunction called by RobotDARTSimu object when removing the robot to the world."},{"location":"api/classrobot__dart_1_1robots_1_1Ur3e/#protected-functions-inherited-from-robot_dartrobot","title":"Protected Functions inherited from robot_dart::Robot","text":"

See robot_dart::Robot

Type Name dart::dynamics::Joint::ActuatorType _actuator_type (size_t joint_index) const std::vector< dart::dynamics::Joint::ActuatorType > _actuator_types () const std::string _get_path (const std::string & filename) const Eigen::MatrixXd _jacobian (const Eigen::MatrixXd & full_jacobian, const std::vector< std::string > & dof_names) const dart::dynamics::SkeletonPtr _load_model (const std::string & filename, const std::vector< std::pair< std::string, std::string > > & packages=std::vector< std::pair< std::string, std::string > >(), bool is_urdf_string=false) Eigen::MatrixXd _mass_matrix (const Eigen::MatrixXd & full_mass_matrix, const std::vector< std::string > & dof_names) const virtual void _post_addition (RobotDARTSimu *) Function called by RobotDARTSimu object when adding the robot to the world. virtual void _post_removal (RobotDARTSimu *) Function called by RobotDARTSimu object when removing the robot to the world. void _set_actuator_type (size_t joint_index, dart::dynamics::Joint::ActuatorType type, bool override_mimic=false, bool override_base=false) void _set_actuator_types (const std::vector< dart::dynamics::Joint::ActuatorType > & types, bool override_mimic=false, bool override_base=false) void _set_actuator_types (dart::dynamics::Joint::ActuatorType type, bool override_mimic=false, bool override_base=false) void _set_color_mode (dart::dynamics::MeshShape::ColorMode color_mode, dart::dynamics::SkeletonPtr skel) void _set_color_mode (dart::dynamics::MeshShape::ColorMode color_mode, dart::dynamics::ShapeNode * sn)"},{"location":"api/classrobot__dart_1_1robots_1_1Ur3e/#public-functions-documentation","title":"Public Functions Documentation","text":""},{"location":"api/classrobot__dart_1_1robots_1_1Ur3e/#function-ur3e","title":"function Ur3e","text":"
robot_dart::robots::Ur3e::Ur3e (\nsize_t frequency=1000,\nconst std::string & urdf=\"ur3e/ur3e.urdf\",\nconst std::vector< std::pair< std::string, std::string > > & packages=('ur3e_description', 'ur3e/ur3e_description')\n) 
"},{"location":"api/classrobot__dart_1_1robots_1_1Ur3e/#function-ft_wrist","title":"function ft_wrist","text":"
inline const sensor::ForceTorque & robot_dart::robots::Ur3e::ft_wrist () const\n
"},{"location":"api/classrobot__dart_1_1robots_1_1Ur3e/#protected-attributes-documentation","title":"Protected Attributes Documentation","text":""},{"location":"api/classrobot__dart_1_1robots_1_1Ur3e/#variable-_ft_wrist","title":"variable _ft_wrist","text":"
std::shared_ptr<sensor::ForceTorque> robot_dart::robots::Ur3e::_ft_wrist;\n
"},{"location":"api/classrobot__dart_1_1robots_1_1Ur3e/#protected-functions-documentation","title":"Protected Functions Documentation","text":""},{"location":"api/classrobot__dart_1_1robots_1_1Ur3e/#function-_post_addition","title":"function _post_addition","text":"
virtual void robot_dart::robots::Ur3e::_post_addition (\nRobotDARTSimu *\n) override\n

Implements robot_dart::Robot::_post_addition

"},{"location":"api/classrobot__dart_1_1robots_1_1Ur3e/#function-_post_removal","title":"function _post_removal","text":"
virtual void robot_dart::robots::Ur3e::_post_removal (\nRobotDARTSimu *\n) override\n

Implements robot_dart::Robot::_post_removal

The documentation for this class was generated from the following file robot_dart/robots/ur3e.hpp

"},{"location":"api/classrobot__dart_1_1robots_1_1Ur3eHand/","title":"Class robot_dart::robots::Ur3eHand","text":"

ClassList > robot_dart > robots > Ur3eHand

Inherits the following classes: robot_dart::robots::Ur3e

"},{"location":"api/classrobot__dart_1_1robots_1_1Ur3eHand/#public-functions","title":"Public Functions","text":"Type Name Ur3eHand (size_t frequency=1000, const std::string & urdf=\"ur3e/ur3e_with_schunk_hand.urdf\", const std::vector< std::pair< std::string, std::string > > & packages=('ur3e\\_description', 'ur3e/ur3e\\_description'))"},{"location":"api/classrobot__dart_1_1robots_1_1Ur3eHand/#public-functions-inherited-from-robot_dartrobotsur3e","title":"Public Functions inherited from robot_dart::robots::Ur3e","text":"

See robot_dart::robots::Ur3e

Type Name Ur3e (size_t frequency=1000, const std::string & urdf=\"ur3e/ur3e.urdf\", const std::vector< std::pair< std::string, std::string > > & packages=('ur3e\\_description', 'ur3e/ur3e\\_description')) const sensor::ForceTorque & ft_wrist () const"},{"location":"api/classrobot__dart_1_1robots_1_1Ur3eHand/#public-functions-inherited-from-robot_dartrobot","title":"Public Functions inherited from robot_dart::Robot","text":"

See robot_dart::Robot

Type Name Robot (const std::string & model_file, const std::vector< std::pair< std::string, std::string > > & packages, const std::string & robot_name=\"robot\", bool is_urdf_string=false, bool cast_shadows=true) Robot (const std::string & model_file, const std::string & robot_name=\"robot\", bool is_urdf_string=false, bool cast_shadows=true) Robot (dart::dynamics::SkeletonPtr skeleton, const std::string & robot_name=\"robot\", bool cast_shadows=true) Eigen::VectorXd acceleration_lower_limits (const std::vector< std::string > & dof_names={}) const Eigen::VectorXd acceleration_upper_limits (const std::vector< std::string > & dof_names={}) const Eigen::VectorXd accelerations (const std::vector< std::string > & dof_names={}) const std::vector< std::shared_ptr< control::RobotControl > > active_controllers () const std::string actuator_type (const std::string & joint_name) const std::vector< std::string > actuator_types (const std::vector< std::string > & joint_names={}) const void add_body_mass (const std::string & body_name, double mass) void add_body_mass (size_t body_index, double mass) void add_controller (const std::shared_ptr< control::RobotControl > & controller, double weight=1.0) void add_external_force (const std::string & body_name, const Eigen::Vector3d & force, const Eigen::Vector3d & offset=Eigen::Vector3d::Zero(), bool force_local=false, bool offset_local=true) void add_external_force (size_t body_index, const Eigen::Vector3d & force, const Eigen::Vector3d & offset=Eigen::Vector3d::Zero(), bool force_local=false, bool offset_local=true) void add_external_torque (const std::string & body_name, const Eigen::Vector3d & torque, bool local=false) void add_external_torque (size_t body_index, const Eigen::Vector3d & torque, bool local=false) bool adjacent_colliding () const Eigen::MatrixXd aug_mass_matrix (const std::vector< std::string > & dof_names={}) const Eigen::Isometry3d base_pose () const Eigen::Vector6d base_pose_vec () const Eigen::Vector6d body_acceleration (const std::string & body_name) const Eigen::Vector6d body_acceleration (size_t body_index) const size_t body_index (const std::string & body_name) const double body_mass (const std::string & body_name) const double body_mass (size_t body_index) const std::string body_name (size_t body_index) const std::vector< std::string > body_names () const dart::dynamics::BodyNode * body_node (const std::string & body_name) dart::dynamics::BodyNode * body_node (size_t body_index) Eigen::Isometry3d body_pose (const std::string & body_name) const Eigen::Isometry3d body_pose (size_t body_index) const Eigen::Vector6d body_pose_vec (const std::string & body_name) const Eigen::Vector6d body_pose_vec (size_t body_index) const Eigen::Vector6d body_velocity (const std::string & body_name) const Eigen::Vector6d body_velocity (size_t body_index) const bool cast_shadows () const void clear_controllers () void clear_external_forces () void clear_internal_forces () std::shared_ptr< Robot > clone () const std::shared_ptr< Robot > clone_ghost (const std::string & ghost_name=\"ghost\", const Eigen::Vector4d & ghost_color={0.3, 0.3, 0.3, 0.7}) const Eigen::Vector3d com () const Eigen::Vector6d com_acceleration () const Eigen::MatrixXd com_jacobian (const std::vector< std::string > & dof_names={}) const Eigen::MatrixXd com_jacobian_deriv (const std::vector< std::string > & dof_names={}) const Eigen::Vector6d com_velocity () const Eigen::VectorXd commands (const std::vector< std::string > & dof_names={}) const Eigen::VectorXd constraint_forces (const std::vector< std::string > & dof_names={}) const std::shared_ptr< control::RobotControl > controller (size_t index) const std::vector< std::shared_ptr< control::RobotControl > > controllers () const Eigen::VectorXd coriolis_forces (const std::vector< std::string > & dof_names={}) const Eigen::VectorXd coriolis_gravity_forces (const std::vector< std::string > & dof_names={}) const std::vector< double > coulomb_coeffs (const std::vector< std::string > & dof_names={}) const std::vector< double > damping_coeffs (const std::vector< std::string > & dof_names={}) const dart::dynamics::DegreeOfFreedom * dof (const std::string & dof_name) dart::dynamics::DegreeOfFreedom * dof (size_t dof_index) size_t dof_index (const std::string & dof_name) const const std::unordered_map< std::string, size_t > & dof_map () const std::string dof_name (size_t dof_index) const std::vector< std::string > dof_names (bool filter_mimics=false, bool filter_locked=false, bool filter_passive=false) const const std::vector< std::pair< dart::dynamics::BodyNode *, double > > & drawing_axes () const Eigen::Vector6d external_forces (const std::string & body_name) const Eigen::Vector6d external_forces (size_t body_index) const void fix_to_world () bool fixed () const Eigen::VectorXd force_lower_limits (const std::vector< std::string > & dof_names={}) const void force_position_bounds () std::pair< Eigen::Vector6d, Eigen::Vector6d > force_torque (size_t joint_index) const Eigen::VectorXd force_upper_limits (const std::vector< std::string > & dof_names={}) const Eigen::VectorXd forces (const std::vector< std::string > & dof_names={}) const bool free () const void free_from_world (const Eigen::Vector6d & pose=Eigen::Vector6d::Zero()) double friction_coeff (const std::string & body_name) double friction_coeff (size_t body_index) Eigen::Vector3d friction_dir (const std::string & body_name) Eigen::Vector3d friction_dir (size_t body_index) bool ghost () const Eigen::VectorXd gravity_forces (const std::vector< std::string > & dof_names={}) const Eigen::MatrixXd inv_aug_mass_matrix (const std::vector< std::string > & dof_names={}) const Eigen::MatrixXd inv_mass_matrix (const std::vector< std::string > & dof_names={}) const Eigen::MatrixXd jacobian (const std::string & body_name, const std::vector< std::string > & dof_names={}) const Eigen::MatrixXd jacobian_deriv (const std::string & body_name, const std::vector< std::string > & dof_names={}) const dart::dynamics::Joint * joint (const std::string & joint_name) dart::dynamics::Joint * joint (size_t joint_index) size_t joint_index (const std::string & joint_name) const const std::unordered_map< std::string, size_t > & joint_map () const std::string joint_name (size_t joint_index) const std::vector< std::string > joint_names () const std::vector< std::string > locked_dof_names () const Eigen::MatrixXd mass_matrix (const std::vector< std::string > & dof_names={}) const std::vector< std::string > mimic_dof_names () const const std::string & model_filename () const const std::vector< std::pair< std::string, std::string > > & model_packages () const const std::string & name () const size_t num_bodies () const size_t num_controllers () const size_t num_dofs () const size_t num_joints () const std::vector< std::string > passive_dof_names () const std::vector< bool > position_enforced (const std::vector< std::string > & dof_names={}) const Eigen::VectorXd position_lower_limits (const std::vector< std::string > & dof_names={}) const Eigen::VectorXd position_upper_limits (const std::vector< std::string > & dof_names={}) const Eigen::VectorXd positions (const std::vector< std::string > & dof_names={}) const void reinit_controllers () void remove_all_drawing_axis () void remove_controller (const std::shared_ptr< control::RobotControl > & controller) void remove_controller (size_t index) virtual void reset () void reset_commands () double restitution_coeff (const std::string & body_name) double restitution_coeff (size_t body_index) double secondary_friction_coeff (const std::string & body_name) double secondary_friction_coeff (size_t body_index) bool self_colliding () const void set_acceleration_lower_limits (const Eigen::VectorXd & accelerations, const std::vector< std::string > & dof_names={}) void set_acceleration_upper_limits (const Eigen::VectorXd & accelerations, const std::vector< std::string > & dof_names={}) void set_accelerations (const Eigen::VectorXd & accelerations, const std::vector< std::string > & dof_names={}) void set_actuator_type (const std::string & type, const std::string & joint_name, bool override_mimic=false, bool override_base=false) void set_actuator_types (const std::string & type, const std::vector< std::string > & joint_names={}, bool override_mimic=false, bool override_base=false) void set_base_pose (const Eigen::Isometry3d & tf) void set_base_pose (const Eigen::Vector6d & pose) set base pose: pose is a 6D vector (first 3D orientation in angle-axis and last 3D translation) void set_body_mass (const std::string & body_name, double mass) void set_body_mass (size_t body_index, double mass) void set_body_name (size_t body_index, const std::string & body_name) void set_cast_shadows (bool cast_shadows=true) void set_color_mode (const std::string & color_mode) void set_color_mode (const std::string & color_mode, const std::string & body_name) void set_commands (const Eigen::VectorXd & commands, const std::vector< std::string > & dof_names={}) void set_coulomb_coeffs (const std::vector< double > & cfrictions, const std::vector< std::string > & dof_names={}) void set_coulomb_coeffs (double cfriction, const std::vector< std::string > & dof_names={}) void set_damping_coeffs (const std::vector< double > & damps, const std::vector< std::string > & dof_names={}) void set_damping_coeffs (double damp, const std::vector< std::string > & dof_names={}) void set_draw_axis (const std::string & body_name, double size=0.25) void set_external_force (const std::string & body_name, const Eigen::Vector3d & force, const Eigen::Vector3d & offset=Eigen::Vector3d::Zero(), bool force_local=false, bool offset_local=true) void set_external_force (size_t body_index, const Eigen::Vector3d & force, const Eigen::Vector3d & offset=Eigen::Vector3d::Zero(), bool force_local=false, bool offset_local=true) void set_external_torque (const std::string & body_name, const Eigen::Vector3d & torque, bool local=false) void set_external_torque (size_t body_index, const Eigen::Vector3d & torque, bool local=false) void set_force_lower_limits (const Eigen::VectorXd & forces, const std::vector< std::string > & dof_names={}) void set_force_upper_limits (const Eigen::VectorXd & forces, const std::vector< std::string > & dof_names={}) void set_forces (const Eigen::VectorXd & forces, const std::vector< std::string > & dof_names={}) void set_friction_coeff (const std::string & body_name, double value) void set_friction_coeff (size_t body_index, double value) void set_friction_coeffs (double value) void set_friction_dir (const std::string & body_name, const Eigen::Vector3d & direction) void set_friction_dir (size_t body_index, const Eigen::Vector3d & direction) void set_ghost (bool ghost=true) void set_joint_name (size_t joint_index, const std::string & joint_name) void set_mimic (const std::string & joint_name, const std::string & mimic_joint_name, double multiplier=1., double offset=0.) void set_position_enforced (const std::vector< bool > & enforced, const std::vector< std::string > & dof_names={}) void set_position_enforced (bool enforced, const std::vector< std::string > & dof_names={}) void set_position_lower_limits (const Eigen::VectorXd & positions, const std::vector< std::string > & dof_names={}) void set_position_upper_limits (const Eigen::VectorXd & positions, const std::vector< std::string > & dof_names={}) void set_positions (const Eigen::VectorXd & positions, const std::vector< std::string > & dof_names={}) void set_restitution_coeff (const std::string & body_name, double value) void set_restitution_coeff (size_t body_index, double value) void set_restitution_coeffs (double value) void set_secondary_friction_coeff (const std::string & body_name, double value) void set_secondary_friction_coeff (size_t body_index, double value) void set_secondary_friction_coeffs (double value) void set_self_collision (bool enable_self_collisions=true, bool enable_adjacent_collisions=false) void set_spring_stiffnesses (const std::vector< double > & stiffnesses, const std::vector< std::string > & dof_names={}) void set_spring_stiffnesses (double stiffness, const std::vector< std::string > & dof_names={}) void set_velocities (const Eigen::VectorXd & velocities, const std::vector< std::string > & dof_names={}) void set_velocity_lower_limits (const Eigen::VectorXd & velocities, const std::vector< std::string > & dof_names={}) void set_velocity_upper_limits (const Eigen::VectorXd & velocities, const std::vector< std::string > & dof_names={}) dart::dynamics::SkeletonPtr skeleton () std::vector< double > spring_stiffnesses (const std::vector< std::string > & dof_names={}) const void update (double t) void update_joint_dof_maps () Eigen::VectorXd vec_dof (const Eigen::VectorXd & vec, const std::vector< std::string > & dof_names) const Eigen::VectorXd velocities (const std::vector< std::string > & dof_names={}) const Eigen::VectorXd velocity_lower_limits (const std::vector< std::string > & dof_names={}) const Eigen::VectorXd velocity_upper_limits (const std::vector< std::string > & dof_names={}) const virtual ~Robot ()"},{"location":"api/classrobot__dart_1_1robots_1_1Ur3eHand/#public-static-functions-inherited-from-robot_dartrobot","title":"Public Static Functions inherited from robot_dart::Robot","text":"

See robot_dart::Robot

Type Name std::shared_ptr< Robot > create_box (const Eigen::Vector3d & dims, const Eigen::Isometry3d & tf, const std::string & type=\"free\", double mass=1.0, const Eigen::Vector4d & color=dart::Color::Red(1.0), const std::string & box_name=\"box\") std::shared_ptr< Robot > create_box (const Eigen::Vector3d & dims, const Eigen::Vector6d & pose=Eigen::Vector6d::Zero(), const std::string & type=\"free\", double mass=1.0, const Eigen::Vector4d & color=dart::Color::Red(1.0), const std::string & box_name=\"box\") std::shared_ptr< Robot > create_ellipsoid (const Eigen::Vector3d & dims, const Eigen::Isometry3d & tf, const std::string & type=\"free\", double mass=1.0, const Eigen::Vector4d & color=dart::Color::Red(1.0), const std::string & ellipsoid_name=\"ellipsoid\") std::shared_ptr< Robot > create_ellipsoid (const Eigen::Vector3d & dims, const Eigen::Vector6d & pose=Eigen::Vector6d::Zero(), const std::string & type=\"free\", double mass=1.0, const Eigen::Vector4d & color=dart::Color::Red(1.0), const std::string & ellipsoid_name=\"ellipsoid\")"},{"location":"api/classrobot__dart_1_1robots_1_1Ur3eHand/#protected-attributes-inherited-from-robot_dartrobotsur3e","title":"Protected Attributes inherited from robot_dart::robots::Ur3e","text":"

See robot_dart::robots::Ur3e

Type Name std::shared_ptr< sensor::ForceTorque > _ft_wrist"},{"location":"api/classrobot__dart_1_1robots_1_1Ur3eHand/#protected-attributes-inherited-from-robot_dartrobot","title":"Protected Attributes inherited from robot_dart::Robot","text":"

See robot_dart::Robot

Type Name std::vector< std::pair< dart::dynamics::BodyNode *, double > > _axis_shapes bool _cast_shadows std::vector< std::shared_ptr< control::RobotControl > > _controllers std::unordered_map< std::string, size_t > _dof_map bool _is_ghost std::unordered_map< std::string, size_t > _joint_map std::string _model_filename std::vector< std::pair< std::string, std::string > > _packages std::string _robot_name dart::dynamics::SkeletonPtr _skeleton"},{"location":"api/classrobot__dart_1_1robots_1_1Ur3eHand/#protected-functions-inherited-from-robot_dartrobotsur3e","title":"Protected Functions inherited from robot_dart::robots::Ur3e","text":"

See robot_dart::robots::Ur3e

Type Name virtual void _post_addition (RobotDARTSimu *) overrideFunction called by RobotDARTSimu object when adding the robot to the world. virtual void _post_removal (RobotDARTSimu *) overrideFunction called by RobotDARTSimu object when removing the robot to the world."},{"location":"api/classrobot__dart_1_1robots_1_1Ur3eHand/#protected-functions-inherited-from-robot_dartrobot","title":"Protected Functions inherited from robot_dart::Robot","text":"

See robot_dart::Robot

Type Name dart::dynamics::Joint::ActuatorType _actuator_type (size_t joint_index) const std::vector< dart::dynamics::Joint::ActuatorType > _actuator_types () const std::string _get_path (const std::string & filename) const Eigen::MatrixXd _jacobian (const Eigen::MatrixXd & full_jacobian, const std::vector< std::string > & dof_names) const dart::dynamics::SkeletonPtr _load_model (const std::string & filename, const std::vector< std::pair< std::string, std::string > > & packages=std::vector< std::pair< std::string, std::string > >(), bool is_urdf_string=false) Eigen::MatrixXd _mass_matrix (const Eigen::MatrixXd & full_mass_matrix, const std::vector< std::string > & dof_names) const virtual void _post_addition (RobotDARTSimu *) Function called by RobotDARTSimu object when adding the robot to the world. virtual void _post_removal (RobotDARTSimu *) Function called by RobotDARTSimu object when removing the robot to the world. void _set_actuator_type (size_t joint_index, dart::dynamics::Joint::ActuatorType type, bool override_mimic=false, bool override_base=false) void _set_actuator_types (const std::vector< dart::dynamics::Joint::ActuatorType > & types, bool override_mimic=false, bool override_base=false) void _set_actuator_types (dart::dynamics::Joint::ActuatorType type, bool override_mimic=false, bool override_base=false) void _set_color_mode (dart::dynamics::MeshShape::ColorMode color_mode, dart::dynamics::SkeletonPtr skel) void _set_color_mode (dart::dynamics::MeshShape::ColorMode color_mode, dart::dynamics::ShapeNode * sn)"},{"location":"api/classrobot__dart_1_1robots_1_1Ur3eHand/#public-functions-documentation","title":"Public Functions Documentation","text":""},{"location":"api/classrobot__dart_1_1robots_1_1Ur3eHand/#function-ur3ehand","title":"function Ur3eHand","text":"
inline robot_dart::robots::Ur3eHand::Ur3eHand (\nsize_t frequency=1000,\nconst std::string & urdf=\"ur3e/ur3e_with_schunk_hand.urdf\",\nconst std::vector< std::pair< std::string, std::string > > & packages=('ur3e_description', 'ur3e/ur3e_description')\n) 

The documentation for this class was generated from the following file robot_dart/robots/ur3e.hpp

"},{"location":"api/classrobot__dart_1_1robots_1_1Vx300/","title":"Class robot_dart::robots::Vx300","text":"

ClassList > robot_dart > robots > Vx300

Inherits the following classes: robot_dart::Robot

"},{"location":"api/classrobot__dart_1_1robots_1_1Vx300/#public-functions","title":"Public Functions","text":"Type Name Vx300 (const std::string & urdf=\"vx300/vx300.urdf\", const std::vector< std::pair< std::string, std::string > > & packages=('interbotix\\_xsarm\\_descriptions', 'vx300'))"},{"location":"api/classrobot__dart_1_1robots_1_1Vx300/#public-functions-inherited-from-robot_dartrobot","title":"Public Functions inherited from robot_dart::Robot","text":"

See robot_dart::Robot

Type Name Robot (const std::string & model_file, const std::vector< std::pair< std::string, std::string > > & packages, const std::string & robot_name=\"robot\", bool is_urdf_string=false, bool cast_shadows=true) Robot (const std::string & model_file, const std::string & robot_name=\"robot\", bool is_urdf_string=false, bool cast_shadows=true) Robot (dart::dynamics::SkeletonPtr skeleton, const std::string & robot_name=\"robot\", bool cast_shadows=true) Eigen::VectorXd acceleration_lower_limits (const std::vector< std::string > & dof_names={}) const Eigen::VectorXd acceleration_upper_limits (const std::vector< std::string > & dof_names={}) const Eigen::VectorXd accelerations (const std::vector< std::string > & dof_names={}) const std::vector< std::shared_ptr< control::RobotControl > > active_controllers () const std::string actuator_type (const std::string & joint_name) const std::vector< std::string > actuator_types (const std::vector< std::string > & joint_names={}) const void add_body_mass (const std::string & body_name, double mass) void add_body_mass (size_t body_index, double mass) void add_controller (const std::shared_ptr< control::RobotControl > & controller, double weight=1.0) void add_external_force (const std::string & body_name, const Eigen::Vector3d & force, const Eigen::Vector3d & offset=Eigen::Vector3d::Zero(), bool force_local=false, bool offset_local=true) void add_external_force (size_t body_index, const Eigen::Vector3d & force, const Eigen::Vector3d & offset=Eigen::Vector3d::Zero(), bool force_local=false, bool offset_local=true) void add_external_torque (const std::string & body_name, const Eigen::Vector3d & torque, bool local=false) void add_external_torque (size_t body_index, const Eigen::Vector3d & torque, bool local=false) bool adjacent_colliding () const Eigen::MatrixXd aug_mass_matrix (const std::vector< std::string > & dof_names={}) const Eigen::Isometry3d base_pose () const Eigen::Vector6d base_pose_vec () const Eigen::Vector6d body_acceleration (const std::string & body_name) const Eigen::Vector6d body_acceleration (size_t body_index) const size_t body_index (const std::string & body_name) const double body_mass (const std::string & body_name) const double body_mass (size_t body_index) const std::string body_name (size_t body_index) const std::vector< std::string > body_names () const dart::dynamics::BodyNode * body_node (const std::string & body_name) dart::dynamics::BodyNode * body_node (size_t body_index) Eigen::Isometry3d body_pose (const std::string & body_name) const Eigen::Isometry3d body_pose (size_t body_index) const Eigen::Vector6d body_pose_vec (const std::string & body_name) const Eigen::Vector6d body_pose_vec (size_t body_index) const Eigen::Vector6d body_velocity (const std::string & body_name) const Eigen::Vector6d body_velocity (size_t body_index) const bool cast_shadows () const void clear_controllers () void clear_external_forces () void clear_internal_forces () std::shared_ptr< Robot > clone () const std::shared_ptr< Robot > clone_ghost (const std::string & ghost_name=\"ghost\", const Eigen::Vector4d & ghost_color={0.3, 0.3, 0.3, 0.7}) const Eigen::Vector3d com () const Eigen::Vector6d com_acceleration () const Eigen::MatrixXd com_jacobian (const std::vector< std::string > & dof_names={}) const Eigen::MatrixXd com_jacobian_deriv (const std::vector< std::string > & dof_names={}) const Eigen::Vector6d com_velocity () const Eigen::VectorXd commands (const std::vector< std::string > & dof_names={}) const Eigen::VectorXd constraint_forces (const std::vector< std::string > & dof_names={}) const std::shared_ptr< control::RobotControl > controller (size_t index) const std::vector< std::shared_ptr< control::RobotControl > > controllers () const Eigen::VectorXd coriolis_forces (const std::vector< std::string > & dof_names={}) const Eigen::VectorXd coriolis_gravity_forces (const std::vector< std::string > & dof_names={}) const std::vector< double > coulomb_coeffs (const std::vector< std::string > & dof_names={}) const std::vector< double > damping_coeffs (const std::vector< std::string > & dof_names={}) const dart::dynamics::DegreeOfFreedom * dof (const std::string & dof_name) dart::dynamics::DegreeOfFreedom * dof (size_t dof_index) size_t dof_index (const std::string & dof_name) const const std::unordered_map< std::string, size_t > & dof_map () const std::string dof_name (size_t dof_index) const std::vector< std::string > dof_names (bool filter_mimics=false, bool filter_locked=false, bool filter_passive=false) const const std::vector< std::pair< dart::dynamics::BodyNode *, double > > & drawing_axes () const Eigen::Vector6d external_forces (const std::string & body_name) const Eigen::Vector6d external_forces (size_t body_index) const void fix_to_world () bool fixed () const Eigen::VectorXd force_lower_limits (const std::vector< std::string > & dof_names={}) const void force_position_bounds () std::pair< Eigen::Vector6d, Eigen::Vector6d > force_torque (size_t joint_index) const Eigen::VectorXd force_upper_limits (const std::vector< std::string > & dof_names={}) const Eigen::VectorXd forces (const std::vector< std::string > & dof_names={}) const bool free () const void free_from_world (const Eigen::Vector6d & pose=Eigen::Vector6d::Zero()) double friction_coeff (const std::string & body_name) double friction_coeff (size_t body_index) Eigen::Vector3d friction_dir (const std::string & body_name) Eigen::Vector3d friction_dir (size_t body_index) bool ghost () const Eigen::VectorXd gravity_forces (const std::vector< std::string > & dof_names={}) const Eigen::MatrixXd inv_aug_mass_matrix (const std::vector< std::string > & dof_names={}) const Eigen::MatrixXd inv_mass_matrix (const std::vector< std::string > & dof_names={}) const Eigen::MatrixXd jacobian (const std::string & body_name, const std::vector< std::string > & dof_names={}) const Eigen::MatrixXd jacobian_deriv (const std::string & body_name, const std::vector< std::string > & dof_names={}) const dart::dynamics::Joint * joint (const std::string & joint_name) dart::dynamics::Joint * joint (size_t joint_index) size_t joint_index (const std::string & joint_name) const const std::unordered_map< std::string, size_t > & joint_map () const std::string joint_name (size_t joint_index) const std::vector< std::string > joint_names () const std::vector< std::string > locked_dof_names () const Eigen::MatrixXd mass_matrix (const std::vector< std::string > & dof_names={}) const std::vector< std::string > mimic_dof_names () const const std::string & model_filename () const const std::vector< std::pair< std::string, std::string > > & model_packages () const const std::string & name () const size_t num_bodies () const size_t num_controllers () const size_t num_dofs () const size_t num_joints () const std::vector< std::string > passive_dof_names () const std::vector< bool > position_enforced (const std::vector< std::string > & dof_names={}) const Eigen::VectorXd position_lower_limits (const std::vector< std::string > & dof_names={}) const Eigen::VectorXd position_upper_limits (const std::vector< std::string > & dof_names={}) const Eigen::VectorXd positions (const std::vector< std::string > & dof_names={}) const void reinit_controllers () void remove_all_drawing_axis () void remove_controller (const std::shared_ptr< control::RobotControl > & controller) void remove_controller (size_t index) virtual void reset () void reset_commands () double restitution_coeff (const std::string & body_name) double restitution_coeff (size_t body_index) double secondary_friction_coeff (const std::string & body_name) double secondary_friction_coeff (size_t body_index) bool self_colliding () const void set_acceleration_lower_limits (const Eigen::VectorXd & accelerations, const std::vector< std::string > & dof_names={}) void set_acceleration_upper_limits (const Eigen::VectorXd & accelerations, const std::vector< std::string > & dof_names={}) void set_accelerations (const Eigen::VectorXd & accelerations, const std::vector< std::string > & dof_names={}) void set_actuator_type (const std::string & type, const std::string & joint_name, bool override_mimic=false, bool override_base=false) void set_actuator_types (const std::string & type, const std::vector< std::string > & joint_names={}, bool override_mimic=false, bool override_base=false) void set_base_pose (const Eigen::Isometry3d & tf) void set_base_pose (const Eigen::Vector6d & pose) set base pose: pose is a 6D vector (first 3D orientation in angle-axis and last 3D translation) void set_body_mass (const std::string & body_name, double mass) void set_body_mass (size_t body_index, double mass) void set_body_name (size_t body_index, const std::string & body_name) void set_cast_shadows (bool cast_shadows=true) void set_color_mode (const std::string & color_mode) void set_color_mode (const std::string & color_mode, const std::string & body_name) void set_commands (const Eigen::VectorXd & commands, const std::vector< std::string > & dof_names={}) void set_coulomb_coeffs (const std::vector< double > & cfrictions, const std::vector< std::string > & dof_names={}) void set_coulomb_coeffs (double cfriction, const std::vector< std::string > & dof_names={}) void set_damping_coeffs (const std::vector< double > & damps, const std::vector< std::string > & dof_names={}) void set_damping_coeffs (double damp, const std::vector< std::string > & dof_names={}) void set_draw_axis (const std::string & body_name, double size=0.25) void set_external_force (const std::string & body_name, const Eigen::Vector3d & force, const Eigen::Vector3d & offset=Eigen::Vector3d::Zero(), bool force_local=false, bool offset_local=true) void set_external_force (size_t body_index, const Eigen::Vector3d & force, const Eigen::Vector3d & offset=Eigen::Vector3d::Zero(), bool force_local=false, bool offset_local=true) void set_external_torque (const std::string & body_name, const Eigen::Vector3d & torque, bool local=false) void set_external_torque (size_t body_index, const Eigen::Vector3d & torque, bool local=false) void set_force_lower_limits (const Eigen::VectorXd & forces, const std::vector< std::string > & dof_names={}) void set_force_upper_limits (const Eigen::VectorXd & forces, const std::vector< std::string > & dof_names={}) void set_forces (const Eigen::VectorXd & forces, const std::vector< std::string > & dof_names={}) void set_friction_coeff (const std::string & body_name, double value) void set_friction_coeff (size_t body_index, double value) void set_friction_coeffs (double value) void set_friction_dir (const std::string & body_name, const Eigen::Vector3d & direction) void set_friction_dir (size_t body_index, const Eigen::Vector3d & direction) void set_ghost (bool ghost=true) void set_joint_name (size_t joint_index, const std::string & joint_name) void set_mimic (const std::string & joint_name, const std::string & mimic_joint_name, double multiplier=1., double offset=0.) void set_position_enforced (const std::vector< bool > & enforced, const std::vector< std::string > & dof_names={}) void set_position_enforced (bool enforced, const std::vector< std::string > & dof_names={}) void set_position_lower_limits (const Eigen::VectorXd & positions, const std::vector< std::string > & dof_names={}) void set_position_upper_limits (const Eigen::VectorXd & positions, const std::vector< std::string > & dof_names={}) void set_positions (const Eigen::VectorXd & positions, const std::vector< std::string > & dof_names={}) void set_restitution_coeff (const std::string & body_name, double value) void set_restitution_coeff (size_t body_index, double value) void set_restitution_coeffs (double value) void set_secondary_friction_coeff (const std::string & body_name, double value) void set_secondary_friction_coeff (size_t body_index, double value) void set_secondary_friction_coeffs (double value) void set_self_collision (bool enable_self_collisions=true, bool enable_adjacent_collisions=false) void set_spring_stiffnesses (const std::vector< double > & stiffnesses, const std::vector< std::string > & dof_names={}) void set_spring_stiffnesses (double stiffness, const std::vector< std::string > & dof_names={}) void set_velocities (const Eigen::VectorXd & velocities, const std::vector< std::string > & dof_names={}) void set_velocity_lower_limits (const Eigen::VectorXd & velocities, const std::vector< std::string > & dof_names={}) void set_velocity_upper_limits (const Eigen::VectorXd & velocities, const std::vector< std::string > & dof_names={}) dart::dynamics::SkeletonPtr skeleton () std::vector< double > spring_stiffnesses (const std::vector< std::string > & dof_names={}) const void update (double t) void update_joint_dof_maps () Eigen::VectorXd vec_dof (const Eigen::VectorXd & vec, const std::vector< std::string > & dof_names) const Eigen::VectorXd velocities (const std::vector< std::string > & dof_names={}) const Eigen::VectorXd velocity_lower_limits (const std::vector< std::string > & dof_names={}) const Eigen::VectorXd velocity_upper_limits (const std::vector< std::string > & dof_names={}) const virtual ~Robot ()"},{"location":"api/classrobot__dart_1_1robots_1_1Vx300/#public-static-functions-inherited-from-robot_dartrobot","title":"Public Static Functions inherited from robot_dart::Robot","text":"

See robot_dart::Robot

Type Name std::shared_ptr< Robot > create_box (const Eigen::Vector3d & dims, const Eigen::Isometry3d & tf, const std::string & type=\"free\", double mass=1.0, const Eigen::Vector4d & color=dart::Color::Red(1.0), const std::string & box_name=\"box\") std::shared_ptr< Robot > create_box (const Eigen::Vector3d & dims, const Eigen::Vector6d & pose=Eigen::Vector6d::Zero(), const std::string & type=\"free\", double mass=1.0, const Eigen::Vector4d & color=dart::Color::Red(1.0), const std::string & box_name=\"box\") std::shared_ptr< Robot > create_ellipsoid (const Eigen::Vector3d & dims, const Eigen::Isometry3d & tf, const std::string & type=\"free\", double mass=1.0, const Eigen::Vector4d & color=dart::Color::Red(1.0), const std::string & ellipsoid_name=\"ellipsoid\") std::shared_ptr< Robot > create_ellipsoid (const Eigen::Vector3d & dims, const Eigen::Vector6d & pose=Eigen::Vector6d::Zero(), const std::string & type=\"free\", double mass=1.0, const Eigen::Vector4d & color=dart::Color::Red(1.0), const std::string & ellipsoid_name=\"ellipsoid\")"},{"location":"api/classrobot__dart_1_1robots_1_1Vx300/#protected-attributes-inherited-from-robot_dartrobot","title":"Protected Attributes inherited from robot_dart::Robot","text":"

See robot_dart::Robot

Type Name std::vector< std::pair< dart::dynamics::BodyNode *, double > > _axis_shapes bool _cast_shadows std::vector< std::shared_ptr< control::RobotControl > > _controllers std::unordered_map< std::string, size_t > _dof_map bool _is_ghost std::unordered_map< std::string, size_t > _joint_map std::string _model_filename std::vector< std::pair< std::string, std::string > > _packages std::string _robot_name dart::dynamics::SkeletonPtr _skeleton"},{"location":"api/classrobot__dart_1_1robots_1_1Vx300/#protected-functions-inherited-from-robot_dartrobot","title":"Protected Functions inherited from robot_dart::Robot","text":"

See robot_dart::Robot

Type Name dart::dynamics::Joint::ActuatorType _actuator_type (size_t joint_index) const std::vector< dart::dynamics::Joint::ActuatorType > _actuator_types () const std::string _get_path (const std::string & filename) const Eigen::MatrixXd _jacobian (const Eigen::MatrixXd & full_jacobian, const std::vector< std::string > & dof_names) const dart::dynamics::SkeletonPtr _load_model (const std::string & filename, const std::vector< std::pair< std::string, std::string > > & packages=std::vector< std::pair< std::string, std::string > >(), bool is_urdf_string=false) Eigen::MatrixXd _mass_matrix (const Eigen::MatrixXd & full_mass_matrix, const std::vector< std::string > & dof_names) const virtual void _post_addition (RobotDARTSimu *) Function called by RobotDARTSimu object when adding the robot to the world. virtual void _post_removal (RobotDARTSimu *) Function called by RobotDARTSimu object when removing the robot to the world. void _set_actuator_type (size_t joint_index, dart::dynamics::Joint::ActuatorType type, bool override_mimic=false, bool override_base=false) void _set_actuator_types (const std::vector< dart::dynamics::Joint::ActuatorType > & types, bool override_mimic=false, bool override_base=false) void _set_actuator_types (dart::dynamics::Joint::ActuatorType type, bool override_mimic=false, bool override_base=false) void _set_color_mode (dart::dynamics::MeshShape::ColorMode color_mode, dart::dynamics::SkeletonPtr skel) void _set_color_mode (dart::dynamics::MeshShape::ColorMode color_mode, dart::dynamics::ShapeNode * sn)"},{"location":"api/classrobot__dart_1_1robots_1_1Vx300/#public-functions-documentation","title":"Public Functions Documentation","text":""},{"location":"api/classrobot__dart_1_1robots_1_1Vx300/#function-vx300","title":"function Vx300","text":"
inline robot_dart::robots::Vx300::Vx300 (\nconst std::string & urdf=\"vx300/vx300.urdf\",\nconst std::vector< std::pair< std::string, std::string > > & packages=('interbotix_xsarm_descriptions', 'vx300')\n) 

The documentation for this class was generated from the following file robot_dart/robots/vx300.hpp

"},{"location":"api/namespacerobot__dart_1_1sensor/","title":"Namespace robot_dart::sensor","text":"

Namespace List > robot_dart > sensor

"},{"location":"api/namespacerobot__dart_1_1sensor/#classes","title":"Classes","text":"Type Name class ForceTorque class IMU struct IMUConfig class Sensor class Torque

The documentation for this class was generated from the following file robot_dart/gui/magnum/sensor/camera.hpp

"},{"location":"api/classrobot__dart_1_1sensor_1_1ForceTorque/","title":"Class robot_dart::sensor::ForceTorque","text":"

ClassList > robot_dart > sensor > ForceTorque

Inherits the following classes: robot_dart::sensor::Sensor

"},{"location":"api/classrobot__dart_1_1sensor_1_1ForceTorque/#public-functions","title":"Public Functions","text":"Type Name ForceTorque (dart::dynamics::Joint * joint, size_t frequency=1000, const std::string & direction=\"child_to_parent\") ForceTorque (const std::shared_ptr< Robot > & robot, const std::string & joint_name, size_t frequency=1000, const std::string & direction=\"child_to_parent\") virtual void attach_to_body (dart::dynamics::BodyNode *, const Eigen::Isometry3d &) override virtual void calculate (double) override Eigen::Vector3d force () const virtual void init () override Eigen::Vector3d torque () const virtual std::string type () override const const Eigen::Vector6d & wrench () const"},{"location":"api/classrobot__dart_1_1sensor_1_1ForceTorque/#public-functions-inherited-from-robot_dartsensorsensor","title":"Public Functions inherited from robot_dart::sensor::Sensor","text":"

See robot_dart::sensor::Sensor

Type Name Sensor (size_t freq=40) void activate (bool enable=true) bool active () const virtual void attach_to_body (dart::dynamics::BodyNode * body, const Eigen::Isometry3d & tf=Eigen::Isometry3d::Identity()) void attach_to_body (const std::shared_ptr< Robot > & robot, const std::string & body_name, const Eigen::Isometry3d & tf=Eigen::Isometry3d::Identity()) virtual void attach_to_joint (dart::dynamics::Joint * joint, const Eigen::Isometry3d & tf=Eigen::Isometry3d::Identity()) void attach_to_joint (const std::shared_ptr< Robot > & robot, const std::string & joint_name, const Eigen::Isometry3d & tf=Eigen::Isometry3d::Identity()) const std::string & attached_to () const virtual void calculate (double) = 0 void detach () size_t frequency () const virtual void init () = 0 const Eigen::Isometry3d & pose () const void refresh (double t) void set_frequency (size_t freq) void set_pose (const Eigen::Isometry3d & tf) void set_simu (RobotDARTSimu * simu) const RobotDARTSimu * simu () const virtual std::string type () const = 0 virtual ~Sensor ()"},{"location":"api/classrobot__dart_1_1sensor_1_1ForceTorque/#protected-attributes","title":"Protected Attributes","text":"Type Name std::string _direction Eigen::Vector6d _wrench"},{"location":"api/classrobot__dart_1_1sensor_1_1ForceTorque/#protected-attributes-inherited-from-robot_dartsensorsensor","title":"Protected Attributes inherited from robot_dart::sensor::Sensor","text":"

See robot_dart::sensor::Sensor

Type Name bool _active Eigen::Isometry3d _attached_tf bool _attached_to_body = = false bool _attached_to_joint = = false bool _attaching_to_body = = false bool _attaching_to_joint = = false dart::dynamics::BodyNode * _body_attached size_t _frequency dart::dynamics::Joint * _joint_attached RobotDARTSimu * _simu = = nullptr Eigen::Isometry3d _world_pose"},{"location":"api/classrobot__dart_1_1sensor_1_1ForceTorque/#public-functions-documentation","title":"Public Functions Documentation","text":""},{"location":"api/classrobot__dart_1_1sensor_1_1ForceTorque/#function-forcetorque-12","title":"function ForceTorque [\u00bd]","text":"
robot_dart::sensor::ForceTorque::ForceTorque (\ndart::dynamics::Joint * joint,\nsize_t frequency=1000,\nconst std::string & direction=\"child_to_parent\"\n) 
"},{"location":"api/classrobot__dart_1_1sensor_1_1ForceTorque/#function-forcetorque-22","title":"function ForceTorque [2/2]","text":"
inline robot_dart::sensor::ForceTorque::ForceTorque (\nconst std::shared_ptr< Robot > & robot,\nconst std::string & joint_name,\nsize_t frequency=1000,\nconst std::string & direction=\"child_to_parent\"\n) 
"},{"location":"api/classrobot__dart_1_1sensor_1_1ForceTorque/#function-attach_to_body","title":"function attach_to_body","text":"
inline virtual void robot_dart::sensor::ForceTorque::attach_to_body (\ndart::dynamics::BodyNode *,\nconst Eigen::Isometry3d &\n) override\n

Implements robot_dart::sensor::Sensor::attach_to_body

"},{"location":"api/classrobot__dart_1_1sensor_1_1ForceTorque/#function-calculate","title":"function calculate","text":"
virtual void robot_dart::sensor::ForceTorque::calculate (\ndouble\n) override\n

Implements robot_dart::sensor::Sensor::calculate

"},{"location":"api/classrobot__dart_1_1sensor_1_1ForceTorque/#function-force","title":"function force","text":"
Eigen::Vector3d robot_dart::sensor::ForceTorque::force () const\n
"},{"location":"api/classrobot__dart_1_1sensor_1_1ForceTorque/#function-init","title":"function init","text":"
virtual void robot_dart::sensor::ForceTorque::init () override\n

Implements robot_dart::sensor::Sensor::init

"},{"location":"api/classrobot__dart_1_1sensor_1_1ForceTorque/#function-torque","title":"function torque","text":"
Eigen::Vector3d robot_dart::sensor::ForceTorque::torque () const\n
"},{"location":"api/classrobot__dart_1_1sensor_1_1ForceTorque/#function-type","title":"function type","text":"
virtual std::string robot_dart::sensor::ForceTorque::type () override const\n

Implements robot_dart::sensor::Sensor::type

"},{"location":"api/classrobot__dart_1_1sensor_1_1ForceTorque/#function-wrench","title":"function wrench","text":"
const Eigen::Vector6d & robot_dart::sensor::ForceTorque::wrench () const\n
"},{"location":"api/classrobot__dart_1_1sensor_1_1ForceTorque/#protected-attributes-documentation","title":"Protected Attributes Documentation","text":""},{"location":"api/classrobot__dart_1_1sensor_1_1ForceTorque/#variable-_direction","title":"variable _direction","text":"
std::string robot_dart::sensor::ForceTorque::_direction;\n
"},{"location":"api/classrobot__dart_1_1sensor_1_1ForceTorque/#variable-_wrench","title":"variable _wrench","text":"
Eigen::Vector6d robot_dart::sensor::ForceTorque::_wrench;\n

The documentation for this class was generated from the following file robot_dart/sensor/force_torque.hpp

"},{"location":"api/classrobot__dart_1_1sensor_1_1IMU/","title":"Class robot_dart::sensor::IMU","text":"

ClassList > robot_dart > sensor > IMU

Inherits the following classes: robot_dart::sensor::Sensor

"},{"location":"api/classrobot__dart_1_1sensor_1_1IMU/#public-functions","title":"Public Functions","text":"Type Name IMU (const IMUConfig & config) const Eigen::AngleAxisd & angular_position () const Eigen::Vector3d angular_position_vec () const const Eigen::Vector3d & angular_velocity () const virtual void attach_to_joint (dart::dynamics::Joint *, const Eigen::Isometry3d &) override virtual void calculate (double) override virtual void init () override const Eigen::Vector3d & linear_acceleration () const virtual std::string type () override const"},{"location":"api/classrobot__dart_1_1sensor_1_1IMU/#public-functions-inherited-from-robot_dartsensorsensor","title":"Public Functions inherited from robot_dart::sensor::Sensor","text":"

See robot_dart::sensor::Sensor

Type Name Sensor (size_t freq=40) void activate (bool enable=true) bool active () const virtual void attach_to_body (dart::dynamics::BodyNode * body, const Eigen::Isometry3d & tf=Eigen::Isometry3d::Identity()) void attach_to_body (const std::shared_ptr< Robot > & robot, const std::string & body_name, const Eigen::Isometry3d & tf=Eigen::Isometry3d::Identity()) virtual void attach_to_joint (dart::dynamics::Joint * joint, const Eigen::Isometry3d & tf=Eigen::Isometry3d::Identity()) void attach_to_joint (const std::shared_ptr< Robot > & robot, const std::string & joint_name, const Eigen::Isometry3d & tf=Eigen::Isometry3d::Identity()) const std::string & attached_to () const virtual void calculate (double) = 0 void detach () size_t frequency () const virtual void init () = 0 const Eigen::Isometry3d & pose () const void refresh (double t) void set_frequency (size_t freq) void set_pose (const Eigen::Isometry3d & tf) void set_simu (RobotDARTSimu * simu) const RobotDARTSimu * simu () const virtual std::string type () const = 0 virtual ~Sensor ()"},{"location":"api/classrobot__dart_1_1sensor_1_1IMU/#protected-attributes","title":"Protected Attributes","text":"Type Name Eigen::AngleAxisd _angular_pos Eigen::Vector3d _angular_vel IMUConfig _config Eigen::Vector3d _linear_accel"},{"location":"api/classrobot__dart_1_1sensor_1_1IMU/#protected-attributes-inherited-from-robot_dartsensorsensor","title":"Protected Attributes inherited from robot_dart::sensor::Sensor","text":"

See robot_dart::sensor::Sensor

Type Name bool _active Eigen::Isometry3d _attached_tf bool _attached_to_body = = false bool _attached_to_joint = = false bool _attaching_to_body = = false bool _attaching_to_joint = = false dart::dynamics::BodyNode * _body_attached size_t _frequency dart::dynamics::Joint * _joint_attached RobotDARTSimu * _simu = = nullptr Eigen::Isometry3d _world_pose"},{"location":"api/classrobot__dart_1_1sensor_1_1IMU/#public-functions-documentation","title":"Public Functions Documentation","text":""},{"location":"api/classrobot__dart_1_1sensor_1_1IMU/#function-imu","title":"function IMU","text":"
robot_dart::sensor::IMU::IMU (\nconst IMUConfig & config\n) 
"},{"location":"api/classrobot__dart_1_1sensor_1_1IMU/#function-angular_position","title":"function angular_position","text":"
const Eigen::AngleAxisd & robot_dart::sensor::IMU::angular_position () const\n
"},{"location":"api/classrobot__dart_1_1sensor_1_1IMU/#function-angular_position_vec","title":"function angular_position_vec","text":"
Eigen::Vector3d robot_dart::sensor::IMU::angular_position_vec () const\n
"},{"location":"api/classrobot__dart_1_1sensor_1_1IMU/#function-angular_velocity","title":"function angular_velocity","text":"
const Eigen::Vector3d & robot_dart::sensor::IMU::angular_velocity () const\n
"},{"location":"api/classrobot__dart_1_1sensor_1_1IMU/#function-attach_to_joint","title":"function attach_to_joint","text":"
inline virtual void robot_dart::sensor::IMU::attach_to_joint (\ndart::dynamics::Joint *,\nconst Eigen::Isometry3d &\n) override\n

Implements robot_dart::sensor::Sensor::attach_to_joint

"},{"location":"api/classrobot__dart_1_1sensor_1_1IMU/#function-calculate","title":"function calculate","text":"
virtual void robot_dart::sensor::IMU::calculate (\ndouble\n) override\n

Implements robot_dart::sensor::Sensor::calculate

"},{"location":"api/classrobot__dart_1_1sensor_1_1IMU/#function-init","title":"function init","text":"
virtual void robot_dart::sensor::IMU::init () override\n

Implements robot_dart::sensor::Sensor::init

"},{"location":"api/classrobot__dart_1_1sensor_1_1IMU/#function-linear_acceleration","title":"function linear_acceleration","text":"
const Eigen::Vector3d & robot_dart::sensor::IMU::linear_acceleration () const\n
"},{"location":"api/classrobot__dart_1_1sensor_1_1IMU/#function-type","title":"function type","text":"
virtual std::string robot_dart::sensor::IMU::type () override const\n

Implements robot_dart::sensor::Sensor::type

"},{"location":"api/classrobot__dart_1_1sensor_1_1IMU/#protected-attributes-documentation","title":"Protected Attributes Documentation","text":""},{"location":"api/classrobot__dart_1_1sensor_1_1IMU/#variable-_angular_pos","title":"variable _angular_pos","text":"
Eigen::AngleAxisd robot_dart::sensor::IMU::_angular_pos;\n
"},{"location":"api/classrobot__dart_1_1sensor_1_1IMU/#variable-_angular_vel","title":"variable _angular_vel","text":"
Eigen::Vector3d robot_dart::sensor::IMU::_angular_vel;\n
"},{"location":"api/classrobot__dart_1_1sensor_1_1IMU/#variable-_config","title":"variable _config","text":"
IMUConfig robot_dart::sensor::IMU::_config;\n
"},{"location":"api/classrobot__dart_1_1sensor_1_1IMU/#variable-_linear_accel","title":"variable _linear_accel","text":"
Eigen::Vector3d robot_dart::sensor::IMU::_linear_accel;\n

The documentation for this class was generated from the following file robot_dart/sensor/imu.hpp

"},{"location":"api/structrobot__dart_1_1sensor_1_1IMUConfig/","title":"Struct robot_dart::sensor::IMUConfig","text":"

ClassList > robot_dart > sensor > IMUConfig

"},{"location":"api/structrobot__dart_1_1sensor_1_1IMUConfig/#public-attributes","title":"Public Attributes","text":"Type Name Eigen::Vector3d accel_bias = = Eigen::Vector3d::Zero() dart::dynamics::BodyNode * body = = nullptr size_t frequency = = 200 Eigen::Vector3d gyro_bias = = Eigen::Vector3d::Zero()"},{"location":"api/structrobot__dart_1_1sensor_1_1IMUConfig/#public-functions","title":"Public Functions","text":"Type Name IMUConfig (dart::dynamics::BodyNode * b, size_t f) IMUConfig (const Eigen::Vector3d & gyro_bias, const Eigen::Vector3d & accel_bias, dart::dynamics::BodyNode * b, size_t f) IMUConfig ()"},{"location":"api/structrobot__dart_1_1sensor_1_1IMUConfig/#public-attributes-documentation","title":"Public Attributes Documentation","text":""},{"location":"api/structrobot__dart_1_1sensor_1_1IMUConfig/#variable-accel_bias","title":"variable accel_bias","text":"
Eigen::Vector3d robot_dart::sensor::IMUConfig::accel_bias;\n
"},{"location":"api/structrobot__dart_1_1sensor_1_1IMUConfig/#variable-body","title":"variable body","text":"
dart::dynamics::BodyNode* robot_dart::sensor::IMUConfig::body;\n
"},{"location":"api/structrobot__dart_1_1sensor_1_1IMUConfig/#variable-frequency","title":"variable frequency","text":"
size_t robot_dart::sensor::IMUConfig::frequency;\n
"},{"location":"api/structrobot__dart_1_1sensor_1_1IMUConfig/#variable-gyro_bias","title":"variable gyro_bias","text":"
Eigen::Vector3d robot_dart::sensor::IMUConfig::gyro_bias;\n
"},{"location":"api/structrobot__dart_1_1sensor_1_1IMUConfig/#public-functions-documentation","title":"Public Functions Documentation","text":""},{"location":"api/structrobot__dart_1_1sensor_1_1IMUConfig/#function-imuconfig-13","title":"function IMUConfig [\u2153]","text":"
inline robot_dart::sensor::IMUConfig::IMUConfig (\ndart::dynamics::BodyNode * b,\nsize_t f\n) 
"},{"location":"api/structrobot__dart_1_1sensor_1_1IMUConfig/#function-imuconfig-23","title":"function IMUConfig [\u2154]","text":"
inline robot_dart::sensor::IMUConfig::IMUConfig (\nconst Eigen::Vector3d & gyro_bias,\nconst Eigen::Vector3d & accel_bias,\ndart::dynamics::BodyNode * b,\nsize_t f\n) 
"},{"location":"api/structrobot__dart_1_1sensor_1_1IMUConfig/#function-imuconfig-33","title":"function IMUConfig [3/3]","text":"
inline robot_dart::sensor::IMUConfig::IMUConfig () 

The documentation for this class was generated from the following file robot_dart/sensor/imu.hpp

"},{"location":"api/classrobot__dart_1_1sensor_1_1Sensor/","title":"Class robot_dart::sensor::Sensor","text":"

ClassList > robot_dart > sensor > Sensor

Inherited by the following classes: robot_dart::gui::magnum::sensor::Camera, robot_dart::sensor::ForceTorque, robot_dart::sensor::IMU, robot_dart::sensor::Torque

"},{"location":"api/classrobot__dart_1_1sensor_1_1Sensor/#public-functions","title":"Public Functions","text":"Type Name Sensor (size_t freq=40) void activate (bool enable=true) bool active () const virtual void attach_to_body (dart::dynamics::BodyNode * body, const Eigen::Isometry3d & tf=Eigen::Isometry3d::Identity()) void attach_to_body (const std::shared_ptr< Robot > & robot, const std::string & body_name, const Eigen::Isometry3d & tf=Eigen::Isometry3d::Identity()) virtual void attach_to_joint (dart::dynamics::Joint * joint, const Eigen::Isometry3d & tf=Eigen::Isometry3d::Identity()) void attach_to_joint (const std::shared_ptr< Robot > & robot, const std::string & joint_name, const Eigen::Isometry3d & tf=Eigen::Isometry3d::Identity()) const std::string & attached_to () const virtual void calculate (double) = 0 void detach () size_t frequency () const virtual void init () = 0 const Eigen::Isometry3d & pose () const void refresh (double t) void set_frequency (size_t freq) void set_pose (const Eigen::Isometry3d & tf) void set_simu (RobotDARTSimu * simu) const RobotDARTSimu * simu () const virtual std::string type () const = 0 virtual ~Sensor ()"},{"location":"api/classrobot__dart_1_1sensor_1_1Sensor/#protected-attributes","title":"Protected Attributes","text":"Type Name bool _active Eigen::Isometry3d _attached_tf bool _attached_to_body = = false bool _attached_to_joint = = false bool _attaching_to_body = = false bool _attaching_to_joint = = false dart::dynamics::BodyNode * _body_attached size_t _frequency dart::dynamics::Joint * _joint_attached RobotDARTSimu * _simu = = nullptr Eigen::Isometry3d _world_pose"},{"location":"api/classrobot__dart_1_1sensor_1_1Sensor/#public-functions-documentation","title":"Public Functions Documentation","text":""},{"location":"api/classrobot__dart_1_1sensor_1_1Sensor/#function-sensor","title":"function Sensor","text":"
robot_dart::sensor::Sensor::Sensor (\nsize_t freq=40\n) 
"},{"location":"api/classrobot__dart_1_1sensor_1_1Sensor/#function-activate","title":"function activate","text":"
void robot_dart::sensor::Sensor::activate (\nbool enable=true\n) 
"},{"location":"api/classrobot__dart_1_1sensor_1_1Sensor/#function-active","title":"function active","text":"
bool robot_dart::sensor::Sensor::active () const\n
"},{"location":"api/classrobot__dart_1_1sensor_1_1Sensor/#function-attach_to_body-12","title":"function attach_to_body [\u00bd]","text":"
virtual void robot_dart::sensor::Sensor::attach_to_body (\ndart::dynamics::BodyNode * body,\nconst Eigen::Isometry3d & tf=Eigen::Isometry3d::Identity()\n) 
"},{"location":"api/classrobot__dart_1_1sensor_1_1Sensor/#function-attach_to_body-22","title":"function attach_to_body [2/2]","text":"
inline void robot_dart::sensor::Sensor::attach_to_body (\nconst std::shared_ptr< Robot > & robot,\nconst std::string & body_name,\nconst Eigen::Isometry3d & tf=Eigen::Isometry3d::Identity()\n) 
"},{"location":"api/classrobot__dart_1_1sensor_1_1Sensor/#function-attach_to_joint-12","title":"function attach_to_joint [\u00bd]","text":"
virtual void robot_dart::sensor::Sensor::attach_to_joint (\ndart::dynamics::Joint * joint,\nconst Eigen::Isometry3d & tf=Eigen::Isometry3d::Identity()\n) 
"},{"location":"api/classrobot__dart_1_1sensor_1_1Sensor/#function-attach_to_joint-22","title":"function attach_to_joint [2/2]","text":"
inline void robot_dart::sensor::Sensor::attach_to_joint (\nconst std::shared_ptr< Robot > & robot,\nconst std::string & joint_name,\nconst Eigen::Isometry3d & tf=Eigen::Isometry3d::Identity()\n) 
"},{"location":"api/classrobot__dart_1_1sensor_1_1Sensor/#function-attached_to","title":"function attached_to","text":"
const std::string & robot_dart::sensor::Sensor::attached_to () const\n
"},{"location":"api/classrobot__dart_1_1sensor_1_1Sensor/#function-calculate","title":"function calculate","text":"
virtual void robot_dart::sensor::Sensor::calculate (\ndouble\n) = 0\n
"},{"location":"api/classrobot__dart_1_1sensor_1_1Sensor/#function-detach","title":"function detach","text":"
void robot_dart::sensor::Sensor::detach () 
"},{"location":"api/classrobot__dart_1_1sensor_1_1Sensor/#function-frequency","title":"function frequency","text":"
size_t robot_dart::sensor::Sensor::frequency () const\n
"},{"location":"api/classrobot__dart_1_1sensor_1_1Sensor/#function-init","title":"function init","text":"
virtual void robot_dart::sensor::Sensor::init () = 0\n
"},{"location":"api/classrobot__dart_1_1sensor_1_1Sensor/#function-pose","title":"function pose","text":"
const Eigen::Isometry3d & robot_dart::sensor::Sensor::pose () const\n
"},{"location":"api/classrobot__dart_1_1sensor_1_1Sensor/#function-refresh","title":"function refresh","text":"
void robot_dart::sensor::Sensor::refresh (\ndouble t\n) 
"},{"location":"api/classrobot__dart_1_1sensor_1_1Sensor/#function-set_frequency","title":"function set_frequency","text":"
void robot_dart::sensor::Sensor::set_frequency (\nsize_t freq\n) 
"},{"location":"api/classrobot__dart_1_1sensor_1_1Sensor/#function-set_pose","title":"function set_pose","text":"
void robot_dart::sensor::Sensor::set_pose (\nconst Eigen::Isometry3d & tf\n) 
"},{"location":"api/classrobot__dart_1_1sensor_1_1Sensor/#function-set_simu","title":"function set_simu","text":"
void robot_dart::sensor::Sensor::set_simu (\nRobotDARTSimu * simu\n) 
"},{"location":"api/classrobot__dart_1_1sensor_1_1Sensor/#function-simu","title":"function simu","text":"
const RobotDARTSimu * robot_dart::sensor::Sensor::simu () const\n
"},{"location":"api/classrobot__dart_1_1sensor_1_1Sensor/#function-type","title":"function type","text":"
virtual std::string robot_dart::sensor::Sensor::type () const = 0\n
"},{"location":"api/classrobot__dart_1_1sensor_1_1Sensor/#function-sensor_1","title":"function ~Sensor","text":"
inline virtual robot_dart::sensor::Sensor::~Sensor () 
"},{"location":"api/classrobot__dart_1_1sensor_1_1Sensor/#protected-attributes-documentation","title":"Protected Attributes Documentation","text":""},{"location":"api/classrobot__dart_1_1sensor_1_1Sensor/#variable-_active","title":"variable _active","text":"
bool robot_dart::sensor::Sensor::_active;\n
"},{"location":"api/classrobot__dart_1_1sensor_1_1Sensor/#variable-_attached_tf","title":"variable _attached_tf","text":"
Eigen::Isometry3d robot_dart::sensor::Sensor::_attached_tf;\n
"},{"location":"api/classrobot__dart_1_1sensor_1_1Sensor/#variable-_attached_to_body","title":"variable _attached_to_body","text":"
bool robot_dart::sensor::Sensor::_attached_to_body;\n
"},{"location":"api/classrobot__dart_1_1sensor_1_1Sensor/#variable-_attached_to_joint","title":"variable _attached_to_joint","text":"
bool robot_dart::sensor::Sensor::_attached_to_joint;\n
"},{"location":"api/classrobot__dart_1_1sensor_1_1Sensor/#variable-_attaching_to_body","title":"variable _attaching_to_body","text":"
bool robot_dart::sensor::Sensor::_attaching_to_body;\n
"},{"location":"api/classrobot__dart_1_1sensor_1_1Sensor/#variable-_attaching_to_joint","title":"variable _attaching_to_joint","text":"
bool robot_dart::sensor::Sensor::_attaching_to_joint;\n
"},{"location":"api/classrobot__dart_1_1sensor_1_1Sensor/#variable-_body_attached","title":"variable _body_attached","text":"
dart::dynamics::BodyNode* robot_dart::sensor::Sensor::_body_attached;\n
"},{"location":"api/classrobot__dart_1_1sensor_1_1Sensor/#variable-_frequency","title":"variable _frequency","text":"
size_t robot_dart::sensor::Sensor::_frequency;\n
"},{"location":"api/classrobot__dart_1_1sensor_1_1Sensor/#variable-_joint_attached","title":"variable _joint_attached","text":"
dart::dynamics::Joint* robot_dart::sensor::Sensor::_joint_attached;\n
"},{"location":"api/classrobot__dart_1_1sensor_1_1Sensor/#variable-_simu","title":"variable _simu","text":"
RobotDARTSimu* robot_dart::sensor::Sensor::_simu;\n
"},{"location":"api/classrobot__dart_1_1sensor_1_1Sensor/#variable-_world_pose","title":"variable _world_pose","text":"
Eigen::Isometry3d robot_dart::sensor::Sensor::_world_pose;\n

The documentation for this class was generated from the following file robot_dart/sensor/sensor.hpp

"},{"location":"api/classrobot__dart_1_1sensor_1_1Torque/","title":"Class robot_dart::sensor::Torque","text":"

ClassList > robot_dart > sensor > Torque

Inherits the following classes: robot_dart::sensor::Sensor

"},{"location":"api/classrobot__dart_1_1sensor_1_1Torque/#public-functions","title":"Public Functions","text":"Type Name Torque (dart::dynamics::Joint * joint, size_t frequency=1000) Torque (const std::shared_ptr< Robot > & robot, const std::string & joint_name, size_t frequency=1000) virtual void attach_to_body (dart::dynamics::BodyNode *, const Eigen::Isometry3d &) override virtual void calculate (double) override virtual void init () override const Eigen::VectorXd & torques () const virtual std::string type () override const"},{"location":"api/classrobot__dart_1_1sensor_1_1Torque/#public-functions-inherited-from-robot_dartsensorsensor","title":"Public Functions inherited from robot_dart::sensor::Sensor","text":"

See robot_dart::sensor::Sensor

Type Name Sensor (size_t freq=40) void activate (bool enable=true) bool active () const virtual void attach_to_body (dart::dynamics::BodyNode * body, const Eigen::Isometry3d & tf=Eigen::Isometry3d::Identity()) void attach_to_body (const std::shared_ptr< Robot > & robot, const std::string & body_name, const Eigen::Isometry3d & tf=Eigen::Isometry3d::Identity()) virtual void attach_to_joint (dart::dynamics::Joint * joint, const Eigen::Isometry3d & tf=Eigen::Isometry3d::Identity()) void attach_to_joint (const std::shared_ptr< Robot > & robot, const std::string & joint_name, const Eigen::Isometry3d & tf=Eigen::Isometry3d::Identity()) const std::string & attached_to () const virtual void calculate (double) = 0 void detach () size_t frequency () const virtual void init () = 0 const Eigen::Isometry3d & pose () const void refresh (double t) void set_frequency (size_t freq) void set_pose (const Eigen::Isometry3d & tf) void set_simu (RobotDARTSimu * simu) const RobotDARTSimu * simu () const virtual std::string type () const = 0 virtual ~Sensor ()"},{"location":"api/classrobot__dart_1_1sensor_1_1Torque/#protected-attributes","title":"Protected Attributes","text":"Type Name Eigen::VectorXd _torques"},{"location":"api/classrobot__dart_1_1sensor_1_1Torque/#protected-attributes-inherited-from-robot_dartsensorsensor","title":"Protected Attributes inherited from robot_dart::sensor::Sensor","text":"

See robot_dart::sensor::Sensor

Type Name bool _active Eigen::Isometry3d _attached_tf bool _attached_to_body = = false bool _attached_to_joint = = false bool _attaching_to_body = = false bool _attaching_to_joint = = false dart::dynamics::BodyNode * _body_attached size_t _frequency dart::dynamics::Joint * _joint_attached RobotDARTSimu * _simu = = nullptr Eigen::Isometry3d _world_pose"},{"location":"api/classrobot__dart_1_1sensor_1_1Torque/#public-functions-documentation","title":"Public Functions Documentation","text":""},{"location":"api/classrobot__dart_1_1sensor_1_1Torque/#function-torque-12","title":"function Torque [\u00bd]","text":"
robot_dart::sensor::Torque::Torque (\ndart::dynamics::Joint * joint,\nsize_t frequency=1000\n) 
"},{"location":"api/classrobot__dart_1_1sensor_1_1Torque/#function-torque-22","title":"function Torque [2/2]","text":"
inline robot_dart::sensor::Torque::Torque (\nconst std::shared_ptr< Robot > & robot,\nconst std::string & joint_name,\nsize_t frequency=1000\n) 
"},{"location":"api/classrobot__dart_1_1sensor_1_1Torque/#function-attach_to_body","title":"function attach_to_body","text":"
inline virtual void robot_dart::sensor::Torque::attach_to_body (\ndart::dynamics::BodyNode *,\nconst Eigen::Isometry3d &\n) override\n

Implements robot_dart::sensor::Sensor::attach_to_body

"},{"location":"api/classrobot__dart_1_1sensor_1_1Torque/#function-calculate","title":"function calculate","text":"
virtual void robot_dart::sensor::Torque::calculate (\ndouble\n) override\n

Implements robot_dart::sensor::Sensor::calculate

"},{"location":"api/classrobot__dart_1_1sensor_1_1Torque/#function-init","title":"function init","text":"
virtual void robot_dart::sensor::Torque::init () override\n

Implements robot_dart::sensor::Sensor::init

"},{"location":"api/classrobot__dart_1_1sensor_1_1Torque/#function-torques","title":"function torques","text":"
const Eigen::VectorXd & robot_dart::sensor::Torque::torques () const\n
"},{"location":"api/classrobot__dart_1_1sensor_1_1Torque/#function-type","title":"function type","text":"
virtual std::string robot_dart::sensor::Torque::type () override const\n

Implements robot_dart::sensor::Sensor::type

"},{"location":"api/classrobot__dart_1_1sensor_1_1Torque/#protected-attributes-documentation","title":"Protected Attributes Documentation","text":""},{"location":"api/classrobot__dart_1_1sensor_1_1Torque/#variable-_torques","title":"variable _torques","text":"
Eigen::VectorXd robot_dart::sensor::Torque::_torques;\n

The documentation for this class was generated from the following file robot_dart/sensor/torque.hpp

"},{"location":"api/namespacerobot__dart_1_1simu/","title":"Namespace robot_dart::simu","text":"

Namespace List > robot_dart > simu

"},{"location":"api/namespacerobot__dart_1_1simu/#classes","title":"Classes","text":"Type Name struct GUIData struct TextData

The documentation for this class was generated from the following file robot_dart/gui_data.hpp

"},{"location":"api/structrobot__dart_1_1simu_1_1GUIData/","title":"Struct robot_dart::simu::GUIData","text":"

ClassList > robot_dart > simu > GUIData

"},{"location":"api/structrobot__dart_1_1simu_1_1GUIData/#public-functions","title":"Public Functions","text":"Type Name std::shared_ptr< simu::TextData > add_text (const std::string & text, const Eigen::Affine2d & tf=Eigen::Affine2d::Identity(), Eigen::Vector4d color=Eigen::Vector4d(1, 1, 1, 1), std::uint8_t alignment=(1|3<< 3), bool draw_bg=false, Eigen::Vector4d bg_color=Eigen::Vector4d(0, 0, 0, 0.75), double font_size=28) bool cast_shadows (dart::dynamics::ShapeNode * shape) const std::vector< std::pair< dart::dynamics::BodyNode *, double > > drawing_axes () const const std::vector< std::shared_ptr< simu::TextData > > & drawing_texts () const bool ghost (dart::dynamics::ShapeNode * shape) const void remove_robot (const std::shared_ptr< Robot > & robot) void remove_text (const std::shared_ptr< simu::TextData > & data) void remove_text (size_t index) void update_robot (const std::shared_ptr< Robot > & robot)"},{"location":"api/structrobot__dart_1_1simu_1_1GUIData/#public-functions-documentation","title":"Public Functions Documentation","text":""},{"location":"api/structrobot__dart_1_1simu_1_1GUIData/#function-add_text","title":"function add_text","text":"
inline std::shared_ptr< simu::TextData > robot_dart::simu::GUIData::add_text (\nconst std::string & text,\nconst Eigen::Affine2d & tf=Eigen::Affine2d::Identity(),\nEigen::Vector4d color=Eigen::Vector4d(1, 1, 1, 1),\nstd::uint8_t alignment=(1|3<< 3),\nbool draw_bg=false,\nEigen::Vector4d bg_color=Eigen::Vector4d(0, 0, 0, 0.75),\ndouble font_size=28\n) 
"},{"location":"api/structrobot__dart_1_1simu_1_1GUIData/#function-cast_shadows","title":"function cast_shadows","text":"
inline bool robot_dart::simu::GUIData::cast_shadows (\ndart::dynamics::ShapeNode * shape\n) const\n
"},{"location":"api/structrobot__dart_1_1simu_1_1GUIData/#function-drawing_axes","title":"function drawing_axes","text":"
inline std::vector< std::pair< dart::dynamics::BodyNode *, double > > robot_dart::simu::GUIData::drawing_axes () const\n
"},{"location":"api/structrobot__dart_1_1simu_1_1GUIData/#function-drawing_texts","title":"function drawing_texts","text":"
inline const std::vector< std::shared_ptr< simu::TextData > > & robot_dart::simu::GUIData::drawing_texts () const\n
"},{"location":"api/structrobot__dart_1_1simu_1_1GUIData/#function-ghost","title":"function ghost","text":"
inline bool robot_dart::simu::GUIData::ghost (\ndart::dynamics::ShapeNode * shape\n) const\n
"},{"location":"api/structrobot__dart_1_1simu_1_1GUIData/#function-remove_robot","title":"function remove_robot","text":"
inline void robot_dart::simu::GUIData::remove_robot (\nconst std::shared_ptr< Robot > & robot\n) 
"},{"location":"api/structrobot__dart_1_1simu_1_1GUIData/#function-remove_text-12","title":"function remove_text [\u00bd]","text":"
inline void robot_dart::simu::GUIData::remove_text (\nconst std::shared_ptr< simu::TextData > & data\n) 
"},{"location":"api/structrobot__dart_1_1simu_1_1GUIData/#function-remove_text-22","title":"function remove_text [2/2]","text":"
inline void robot_dart::simu::GUIData::remove_text (\nsize_t index\n) 
"},{"location":"api/structrobot__dart_1_1simu_1_1GUIData/#function-update_robot","title":"function update_robot","text":"
inline void robot_dart::simu::GUIData::update_robot (\nconst std::shared_ptr< Robot > & robot\n) 

The documentation for this class was generated from the following file robot_dart/gui_data.hpp

"},{"location":"api/structrobot__dart_1_1simu_1_1TextData/","title":"Struct robot_dart::simu::TextData","text":"

ClassList > robot_dart > simu > TextData

"},{"location":"api/structrobot__dart_1_1simu_1_1TextData/#public-attributes","title":"Public Attributes","text":"Type Name std::uint8_t alignment Eigen::Vector4d background_color Eigen::Vector4d color bool draw_background double font_size = = 28. std::string text Eigen::Affine2d transformation"},{"location":"api/structrobot__dart_1_1simu_1_1TextData/#public-attributes-documentation","title":"Public Attributes Documentation","text":""},{"location":"api/structrobot__dart_1_1simu_1_1TextData/#variable-alignment","title":"variable alignment","text":"
std::uint8_t robot_dart::simu::TextData::alignment;\n
"},{"location":"api/structrobot__dart_1_1simu_1_1TextData/#variable-background_color","title":"variable background_color","text":"
Eigen::Vector4d robot_dart::simu::TextData::background_color;\n
"},{"location":"api/structrobot__dart_1_1simu_1_1TextData/#variable-color","title":"variable color","text":"
Eigen::Vector4d robot_dart::simu::TextData::color;\n
"},{"location":"api/structrobot__dart_1_1simu_1_1TextData/#variable-draw_background","title":"variable draw_background","text":"
bool robot_dart::simu::TextData::draw_background;\n
"},{"location":"api/structrobot__dart_1_1simu_1_1TextData/#variable-font_size","title":"variable font_size","text":"
double robot_dart::simu::TextData::font_size;\n
"},{"location":"api/structrobot__dart_1_1simu_1_1TextData/#variable-text","title":"variable text","text":"
std::string robot_dart::simu::TextData::text;\n
"},{"location":"api/structrobot__dart_1_1simu_1_1TextData/#variable-transformation","title":"variable transformation","text":"
Eigen::Affine2d robot_dart::simu::TextData::transformation;\n

The documentation for this class was generated from the following file robot_dart/robot_dart_simu.hpp

"},{"location":"api/namespacerobot__dart_1_1gui_1_1magnum_1_1gs_1_1_0d21/","title":"Namespace robot_dart::gui::magnum::@21","text":"

Namespace List > @21

"},{"location":"api/namespacerobot__dart_1_1gui_1_1magnum_1_1gs_1_1_0d21/#public-types","title":"Public Types","text":"Type Name enum Magnum::Int @0"},{"location":"api/namespacerobot__dart_1_1gui_1_1magnum_1_1gs_1_1_0d21/#public-types-documentation","title":"Public Types Documentation","text":""},{"location":"api/namespacerobot__dart_1_1gui_1_1magnum_1_1gs_1_1_0d21/#enum-0","title":"enum @0","text":"
enum @21::@0;\n

The documentation for this class was generated from the following file robot_dart/gui/magnum/gs/create_compatibility_shader.hpp

"},{"location":"api/structrobot__dart_1_1simu_1_1GUIData_1_1RobotData/","title":"Struct robot_dart::simu::GUIData::RobotData","text":"

ClassList > RobotData

"},{"location":"api/structrobot__dart_1_1simu_1_1GUIData_1_1RobotData/#public-attributes","title":"Public Attributes","text":"Type Name bool casting_shadows bool is_ghost"},{"location":"api/structrobot__dart_1_1simu_1_1GUIData_1_1RobotData/#public-attributes-documentation","title":"Public Attributes Documentation","text":""},{"location":"api/structrobot__dart_1_1simu_1_1GUIData_1_1RobotData/#variable-casting_shadows","title":"variable casting_shadows","text":"
bool robot_dart::simu::GUIData::RobotData::casting_shadows;\n
"},{"location":"api/structrobot__dart_1_1simu_1_1GUIData_1_1RobotData/#variable-is_ghost","title":"variable is_ghost","text":"
bool robot_dart::simu::GUIData::RobotData::is_ghost;\n

The documentation for this class was generated from the following file robot_dart/gui_data.hpp

"},{"location":"api/namespacestd/","title":"Namespace std","text":"

Namespace List > std

The documentation for this class was generated from the following file [generated]

"},{"location":"api/namespacesubprocess/","title":"Namespace subprocess","text":"

Namespace List > subprocess

The documentation for this class was generated from the following file robot_dart/gui/magnum/gs/camera.hpp

"},{"location":"api/dir_166284c5f0440000a6384365f2a45567/","title":"Dir robot_dart","text":"

FileList > robot_dart

"},{"location":"api/dir_166284c5f0440000a6384365f2a45567/#files","title":"Files","text":"Type Name file gui_data.hpp file robot.cpp file robot.hpp file robot_dart_simu.cpp file robot_dart_simu.hpp file robot_pool.cpp file robot_pool.hpp file scheduler.cpp file scheduler.hpp file utils.hpp file utils_headers_dart_collision.hpp file utils_headers_dart_dynamics.hpp file utils_headers_dart_io.hpp file utils_headers_external.hpp file utils_headers_external_gui.hpp"},{"location":"api/dir_166284c5f0440000a6384365f2a45567/#directories","title":"Directories","text":"Type Name dir control dir gui dir robots dir sensor

The documentation for this class was generated from the following file robot_dart/

"},{"location":"api/gui__data_8hpp/","title":"File gui_data.hpp","text":"

FileList > robot_dart > gui_data.hpp

Go to the source code of this file

"},{"location":"api/gui__data_8hpp/#namespaces","title":"Namespaces","text":"Type Name namespace robot_dart namespace simu"},{"location":"api/gui__data_8hpp/#classes","title":"Classes","text":"Type Name struct GUIData

The documentation for this class was generated from the following file robot_dart/gui_data.hpp

"},{"location":"api/gui__data_8hpp_source/","title":"File gui_data.hpp","text":"

File List > robot_dart > gui_data.hpp

Go to the documentation of this file

#ifndef ROBOT_DART_SIMU_GUI_DATA_HPP\n#define ROBOT_DART_SIMU_GUI_DATA_HPP\n#include \"robot_dart_simu.hpp\"\n#include \"utils_headers_dart_dynamics.hpp\"\n#include <unordered_map>\n#include <vector>\nnamespace robot_dart {\nnamespace simu {\nstruct GUIData {\nprivate:\nstruct RobotData {\nbool casting_shadows;\nbool is_ghost;\n};\nstd::unordered_map<dart::dynamics::ShapeNode*, RobotData> robot_data;\nstd::unordered_map<Robot*, std::vector<std::pair<dart::dynamics::BodyNode*, double>>> robot_axes;\nstd::vector<std::shared_ptr<simu::TextData>> text_drawings;\npublic:\nstd::shared_ptr<simu::TextData> add_text(const std::string& text, const Eigen::Affine2d& tf = Eigen::Affine2d::Identity(), Eigen::Vector4d color = Eigen::Vector4d(1, 1, 1, 1), std::uint8_t alignment = (1 | 3 << 3), bool draw_bg = false, Eigen::Vector4d bg_color = Eigen::Vector4d(0, 0, 0, 0.75), double font_size = 28)\n{\ntext_drawings.emplace_back(new TextData{text, tf, color, alignment, draw_bg, bg_color, font_size});\nreturn text_drawings.back();\n}\nvoid remove_text(const std::shared_ptr<simu::TextData>& data)\n{\nfor (size_t i = 0; i < text_drawings.size(); i++) {\nif (text_drawings[i] == data) {\ntext_drawings.erase(text_drawings.begin() + i);\nreturn;\n}\n}\n}\nvoid remove_text(size_t index)\n{\nif (index >= text_drawings.size())\nreturn;\ntext_drawings.erase(text_drawings.begin() + index);\n}\nvoid update_robot(const std::shared_ptr<Robot>& robot)\n{\nauto robot_ptr = &*robot;\nauto skel = robot->skeleton();\nbool cast = robot->cast_shadows();\nbool ghost = robot->ghost();\nfor (size_t i = 0; i < skel->getNumBodyNodes(); ++i) {\nauto bd = skel->getBodyNode(i);\nauto& shapes = bd->getShapeNodesWith<dart::dynamics::VisualAspect>();\nfor (size_t j = 0; j < shapes.size(); j++) {\nrobot_data[shapes[j]] = {cast, ghost};\n}\n}\nauto& axes = robot->drawing_axes();\nif (axes.size() > 0)\nrobot_axes[robot_ptr] = axes;\n}\nvoid remove_robot(const std::shared_ptr<Robot>& robot)\n{\nauto robot_ptr = &*robot;\nauto skel = robot->skeleton();\nfor (size_t i = 0; i < skel->getNumShapeNodes(); ++i) {\nauto shape = skel->getShapeNode(i);\nauto shape_iter = robot_data.find(shape);\nif (shape_iter != robot_data.end())\nrobot_data.erase(shape_iter);\n}\nauto iter = robot_axes.find(robot_ptr);\nif (iter != robot_axes.end())\nrobot_axes.erase(iter);\n}\nbool cast_shadows(dart::dynamics::ShapeNode* shape) const\n{\nauto shape_iter = robot_data.find(shape);\nif (shape_iter != robot_data.end())\nreturn robot_data.at(shape).casting_shadows;\n// if not in the array, cast shadow by default\nreturn true;\n}\nbool ghost(dart::dynamics::ShapeNode* shape) const\n{\nauto shape_iter = robot_data.find(shape);\nif (shape_iter != robot_data.end())\nreturn robot_data.at(shape).is_ghost;\n// if not in the array, the robot is not ghost by default\nreturn false;\n}\nstd::vector<std::pair<dart::dynamics::BodyNode*, double>> drawing_axes() const\n{\nstd::vector<std::pair<dart::dynamics::BodyNode*, double>> axes;\nfor (std::pair<Robot*, std::vector<std::pair<dart::dynamics::BodyNode*, double>>> elem : robot_axes) {\naxes.insert(axes.end(), elem.second.begin(), elem.second.end());\n}\nreturn axes;\n}\nconst std::vector<std::shared_ptr<simu::TextData>>& drawing_texts() const { return text_drawings; }\n};\n} // namespace simu\n} // namespace robot_dart\n#endif\n
"},{"location":"api/robot_8cpp/","title":"File robot.cpp","text":"

FileList > robot_dart > robot.cpp

Go to the source code of this file

"},{"location":"api/robot_8cpp/#namespaces","title":"Namespaces","text":"Type Name namespace robot_dart namespace detail

The documentation for this class was generated from the following file robot_dart/robot.cpp

"},{"location":"api/robot_8cpp_source/","title":"File robot.cpp","text":"

File List > robot_dart > robot.cpp

Go to the documentation of this file

#include <unistd.h>\n#include <robot_dart/robot.hpp>\n#include <robot_dart/utils.hpp>\n#include <robot_dart/utils_headers_dart_dynamics.hpp>\n#include <robot_dart/utils_headers_dart_io.hpp>\n#include <robot_dart/control/robot_control.hpp>\n#include <utheque/utheque.hpp> // library of URDF\nnamespace robot_dart {\nnamespace detail {\ntemplate <int content>\nEigen::VectorXd dof_data(dart::dynamics::SkeletonPtr skeleton, const std::vector<std::string>& dof_names, const std::unordered_map<std::string, size_t>& dof_map)\n{\n// Return all values\nif (dof_names.empty()) {\nif (content == 0)\nreturn skeleton->getPositions();\nelse if (content == 1)\nreturn skeleton->getVelocities();\nelse if (content == 2)\nreturn skeleton->getAccelerations();\nelse if (content == 3)\nreturn skeleton->getForces();\nelse if (content == 4)\nreturn skeleton->getCommands();\nelse if (content == 5)\nreturn skeleton->getPositionLowerLimits();\nelse if (content == 6)\nreturn skeleton->getPositionUpperLimits();\nelse if (content == 7)\nreturn skeleton->getVelocityLowerLimits();\nelse if (content == 8)\nreturn skeleton->getVelocityUpperLimits();\nelse if (content == 9)\nreturn skeleton->getAccelerationLowerLimits();\nelse if (content == 10)\nreturn skeleton->getAccelerationUpperLimits();\nelse if (content == 11)\nreturn skeleton->getForceLowerLimits();\nelse if (content == 12)\nreturn skeleton->getForceUpperLimits();\nelse if (content == 13)\nreturn skeleton->getCoriolisForces();\nelse if (content == 14)\nreturn skeleton->getGravityForces();\nelse if (content == 15)\nreturn skeleton->getCoriolisAndGravityForces();\nelse if (content == 16)\nreturn skeleton->getConstraintForces();\nROBOT_DART_EXCEPTION_ASSERT(false, \"Unknown type of data!\");\n}\nEigen::VectorXd data(dof_names.size());\nEigen::VectorXd tmp;\nif (content == 13)\ntmp = skeleton->getCoriolisForces();\nelse if (content == 14)\ntmp = skeleton->getGravityForces();\nelse if (content == 15)\ntmp = skeleton->getCoriolisAndGravityForces();\nelse if (content == 16)\ntmp = skeleton->getConstraintForces();\nfor (size_t i = 0; i < dof_names.size(); i++) {\nauto it = dof_map.find(dof_names[i]);\nROBOT_DART_ASSERT(it != dof_map.end(), \"dof_data: \" + dof_names[i] + \" is not in dof_map\", Eigen::VectorXd());\nauto dof = skeleton->getDof(it->second);\nif (content == 0)\ndata(i) = dof->getPosition();\nelse if (content == 1)\ndata(i) = dof->getVelocity();\nelse if (content == 2)\ndata(i) = dof->getAcceleration();\nelse if (content == 3)\ndata(i) = dof->getForce();\nelse if (content == 4)\ndata(i) = dof->getCommand();\nelse if (content == 5)\ndata(i) = dof->getPositionLowerLimit();\nelse if (content == 6)\ndata(i) = dof->getPositionUpperLimit();\nelse if (content == 7)\ndata(i) = dof->getVelocityLowerLimit();\nelse if (content == 8)\ndata(i) = dof->getVelocityUpperLimit();\nelse if (content == 9)\ndata(i) = dof->getAccelerationLowerLimit();\nelse if (content == 10)\ndata(i) = dof->getAccelerationUpperLimit();\nelse if (content == 11)\ndata(i) = dof->getForceLowerLimit();\nelse if (content == 12)\ndata(i) = dof->getForceUpperLimit();\nelse if (content == 13 || content == 14 || content == 15 || content == 16)\ndata(i) = tmp(it->second);\nelse\nROBOT_DART_EXCEPTION_ASSERT(false, \"Unknown type of data!\");\n}\nreturn data;\n}\ntemplate <int content>\nvoid set_dof_data(const Eigen::VectorXd& data, dart::dynamics::SkeletonPtr skeleton, const std::vector<std::string>& dof_names, const std::unordered_map<std::string, size_t>& dof_map)\n{\n// Set all values\nif (dof_names.empty()) {\nROBOT_DART_ASSERT(static_cast<size_t>(data.size()) == skeleton->getNumDofs(), \"set_dof_data: size of data is not the same as the DoFs\", );\nif (content == 0)\nreturn skeleton->setPositions(data);\nelse if (content == 1)\nreturn skeleton->setVelocities(data);\nelse if (content == 2)\nreturn skeleton->setAccelerations(data);\nelse if (content == 3)\nreturn skeleton->setForces(data);\nelse if (content == 4)\nreturn skeleton->setCommands(data);\nelse if (content == 5)\nreturn skeleton->setPositionLowerLimits(data);\nelse if (content == 6)\nreturn skeleton->setPositionUpperLimits(data);\nelse if (content == 7)\nreturn skeleton->setVelocityLowerLimits(data);\nelse if (content == 8)\nreturn skeleton->setVelocityUpperLimits(data);\nelse if (content == 9)\nreturn skeleton->setAccelerationLowerLimits(data);\nelse if (content == 10)\nreturn skeleton->setAccelerationUpperLimits(data);\nelse if (content == 11)\nreturn skeleton->setForceLowerLimits(data);\nelse if (content == 12)\nreturn skeleton->setForceUpperLimits(data);\nROBOT_DART_EXCEPTION_ASSERT(false, \"Unknown type of data!\");\n}\nROBOT_DART_ASSERT(static_cast<size_t>(data.size()) == dof_names.size(), \"set_dof_data: size of data is not the same as the dof_names size\", );\nfor (size_t i = 0; i < dof_names.size(); i++) {\nauto it = dof_map.find(dof_names[i]);\nROBOT_DART_ASSERT(it != dof_map.end(), \"dof_data: \" + dof_names[i] + \" is not in dof_map\", );\nauto dof = skeleton->getDof(it->second);\nif (content == 0)\ndof->setPosition(data(i));\nelse if (content == 1)\ndof->setVelocity(data(i));\nelse if (content == 2)\ndof->setAcceleration(data(i));\nelse if (content == 3)\ndof->setForce(data(i));\nelse if (content == 4)\ndof->setCommand(data(i));\nelse if (content == 5)\ndof->setPositionLowerLimit(data(i));\nelse if (content == 6)\ndof->setPositionUpperLimit(data(i));\nelse if (content == 7)\ndof->setVelocityLowerLimit(data(i));\nelse if (content == 8)\ndof->setVelocityUpperLimit(data(i));\nelse if (content == 9)\ndof->setAccelerationLowerLimit(data(i));\nelse if (content == 10)\ndof->setAccelerationUpperLimit(data(i));\nelse if (content == 11)\ndof->setForceLowerLimit(data(i));\nelse if (content == 12)\ndof->setForceUpperLimit(data(i));\nelse\nROBOT_DART_EXCEPTION_ASSERT(false, \"Unknown type of data!\");\n}\n}\ntemplate <int content>\nvoid add_dof_data(const Eigen::VectorXd& data, dart::dynamics::SkeletonPtr skeleton, const std::vector<std::string>& dof_names, const std::unordered_map<std::string, size_t>& dof_map)\n{\n// Set all values\nif (dof_names.empty()) {\nROBOT_DART_ASSERT(static_cast<size_t>(data.size()) == skeleton->getNumDofs(), \"set_dof_data: size of data is not the same as the DoFs\", );\nif (content == 0)\nreturn skeleton->setPositions(skeleton->getPositions() + data);\nelse if (content == 1)\nreturn skeleton->setVelocities(skeleton->getVelocities() + data);\nelse if (content == 2)\nreturn skeleton->setAccelerations(skeleton->getAccelerations() + data);\nelse if (content == 3)\nreturn skeleton->setForces(skeleton->getForces() + data);\nelse if (content == 4)\nreturn skeleton->setCommands(skeleton->getCommands() + data);\nelse if (content == 5)\nreturn skeleton->setPositionLowerLimits(skeleton->getPositionLowerLimits() + data);\nelse if (content == 6)\nreturn skeleton->setPositionUpperLimits(skeleton->getPositionUpperLimits() + data);\nelse if (content == 7)\nreturn skeleton->setVelocityLowerLimits(skeleton->getVelocityLowerLimits() + data);\nelse if (content == 8)\nreturn skeleton->setVelocityUpperLimits(skeleton->getVelocityUpperLimits() + data);\nelse if (content == 9)\nreturn skeleton->setAccelerationLowerLimits(skeleton->getAccelerationLowerLimits() + data);\nelse if (content == 10)\nreturn skeleton->setAccelerationUpperLimits(skeleton->getAccelerationUpperLimits() + data);\nelse if (content == 11)\nreturn skeleton->setForceLowerLimits(skeleton->getForceLowerLimits() + data);\nelse if (content == 12)\nreturn skeleton->setForceUpperLimits(skeleton->getForceUpperLimits() + data);\nROBOT_DART_EXCEPTION_ASSERT(false, \"Unknown type of data!\");\n}\nROBOT_DART_ASSERT(static_cast<size_t>(data.size()) == dof_names.size(), \"add_dof_data: size of data is not the same as the dof_names size\", );\nfor (size_t i = 0; i < dof_names.size(); i++) {\nauto it = dof_map.find(dof_names[i]);\nROBOT_DART_ASSERT(it != dof_map.end(), \"dof_data: \" + dof_names[i] + \" is not in dof_map\", );\nauto dof = skeleton->getDof(it->second);\nif (content == 0)\ndof->setPosition(dof->getPosition() + data(i));\nelse if (content == 1)\ndof->setVelocity(dof->getVelocity() + data(i));\nelse if (content == 2)\ndof->setAcceleration(dof->getAcceleration() + data(i));\nelse if (content == 3)\ndof->setForce(dof->getForce() + data(i));\nelse if (content == 4)\ndof->setCommand(dof->getCommand() + data(i));\nelse if (content == 5)\ndof->setPositionLowerLimit(dof->getPositionLowerLimit() + data(i));\nelse if (content == 6)\ndof->setPositionUpperLimit(dof->getPositionUpperLimit() + data(i));\nelse if (content == 7)\ndof->setVelocityLowerLimit(dof->getVelocityLowerLimit() + data(i));\nelse if (content == 8)\ndof->setVelocityUpperLimit(dof->getVelocityUpperLimit() + data(i));\nelse if (content == 9)\ndof->setAccelerationLowerLimit(dof->getAccelerationLowerLimit() + data(i));\nelse if (content == 10)\ndof->setAccelerationUpperLimit(dof->getAccelerationUpperLimit() + data(i));\nelse if (content == 11)\ndof->setForceLowerLimit(dof->getForceLowerLimit() + data(i));\nelse if (content == 12)\ndof->setForceUpperLimit(dof->getForceUpperLimit() + data(i));\nelse\nROBOT_DART_EXCEPTION_ASSERT(false, \"Unknown type of data!\");\n}\n}\n} // namespace detail\nRobot::Robot(const std::string& model_file, const std::vector<std::pair<std::string, std::string>>& packages, const std::string& robot_name, bool is_urdf_string, bool cast_shadows)\n: _robot_name(robot_name), _skeleton(_load_model(model_file, packages, is_urdf_string)), _cast_shadows(cast_shadows), _is_ghost(false)\n{\nROBOT_DART_EXCEPTION_INTERNAL_ASSERT(_skeleton != nullptr);\nupdate_joint_dof_maps();\n}\nRobot::Robot(const std::string& model_file, const std::string& robot_name, bool is_urdf_string, bool cast_shadows)\n: Robot(model_file, std::vector<std::pair<std::string, std::string>>(), robot_name, is_urdf_string, cast_shadows)\n{\n}\nRobot::Robot(dart::dynamics::SkeletonPtr skeleton, const std::string& robot_name, bool cast_shadows)\n: _robot_name(robot_name), _skeleton(skeleton), _cast_shadows(cast_shadows), _is_ghost(false)\n{\nROBOT_DART_EXCEPTION_INTERNAL_ASSERT(_skeleton != nullptr);\n_skeleton->setName(robot_name);\nupdate_joint_dof_maps();\nreset();\n}\nstd::shared_ptr<Robot> Robot::clone() const\n{\n// safely clone the skeleton\n_skeleton->getMutex().lock();\n#if DART_VERSION_AT_LEAST(6, 7, 2)\nauto tmp_skel = _skeleton->cloneSkeleton();\n#else\nauto tmp_skel = _skeleton->clone();\n#endif\n_skeleton->getMutex().unlock();\nauto robot = std::make_shared<Robot>(tmp_skel, _robot_name);\n#if DART_VERSION_AT_LEAST(6, 13, 0)\n// Deep copy everything\nfor (auto& bd : robot->skeleton()->getBodyNodes()) {\nauto& visual_shapes = bd->getShapeNodesWith<dart::dynamics::VisualAspect>();\nfor (auto& shape : visual_shapes) {\nif (shape->getShape()->getType() != dart::dynamics::SoftMeshShape::getStaticType())\nshape->setShape(shape->getShape()->clone());\n}\n}\n#endif\nrobot->set_positions(this->positions());\nrobot->_model_filename = _model_filename;\nrobot->_controllers.clear();\nfor (auto& ctrl : _controllers) {\nrobot->add_controller(ctrl->clone(), ctrl->weight());\n}\nreturn robot;\n}\nstd::shared_ptr<Robot> Robot::clone_ghost(const std::string& ghost_name, const Eigen::Vector4d& ghost_color) const\n{\n// safely clone the skeleton\n_skeleton->getMutex().lock();\n#if DART_VERSION_AT_LEAST(6, 7, 2)\nauto tmp_skel = _skeleton->cloneSkeleton();\n#else\nauto tmp_skel = _skeleton->clone();\n#endif\n_skeleton->getMutex().unlock();\nauto robot = std::make_shared<Robot>(tmp_skel, ghost_name + \"_\" + _robot_name);\nrobot->_model_filename = _model_filename;\n// ghost robots have no controllers\nrobot->_controllers.clear();\n// ghost robots do not do physics updates\nrobot->skeleton()->setMobile(false);\nfor (auto& bd : robot->skeleton()->getBodyNodes()) {\n// ghost robots do not have collisions\nauto& collision_shapes = bd->getShapeNodesWith<dart::dynamics::CollisionAspect>();\nfor (auto& shape : collision_shapes) {\nshape->removeAspect<dart::dynamics::CollisionAspect>();\n}\n// ghost robots do not have dynamics\nauto& dyn_shapes = bd->getShapeNodesWith<dart::dynamics::DynamicsAspect>();\nfor (auto& shape : dyn_shapes) {\nshape->removeAspect<dart::dynamics::DynamicsAspect>();\n}\n// ghost robots have a different color (same for all bodies)\nauto& visual_shapes = bd->getShapeNodesWith<dart::dynamics::VisualAspect>();\nfor (auto& shape : visual_shapes) {\n#if DART_VERSION_AT_LEAST(6, 13, 0)\nif (shape->getShape()->getType() != dart::dynamics::SoftMeshShape::getStaticType())\nshape->setShape(shape->getShape()->clone());\n#endif\nshape->getVisualAspect()->setRGBA(ghost_color);\n}\n}\n// set positions\nrobot->set_positions(this->positions());\n// ghost robots, by default, use the color from the VisualAspect\nrobot->set_color_mode(\"aspect\");\n// ghost robots do not cast shadows\nrobot->set_cast_shadows(false);\n// set the ghost flag\nrobot->set_ghost(true);\nreturn robot;\n}\ndart::dynamics::SkeletonPtr Robot::skeleton() { return _skeleton; }\ndart::dynamics::BodyNode* Robot::body_node(const std::string& body_name) { return _skeleton->getBodyNode(body_name); }\ndart::dynamics::BodyNode* Robot::body_node(size_t body_index)\n{\nROBOT_DART_ASSERT(body_index < _skeleton->getNumBodyNodes(), \"BodyNode index out of bounds\", nullptr);\nreturn _skeleton->getBodyNode(body_index);\n}\ndart::dynamics::Joint* Robot::joint(const std::string& joint_name) { return _skeleton->getJoint(joint_name); }\ndart::dynamics::Joint* Robot::joint(size_t joint_index)\n{\nROBOT_DART_ASSERT(joint_index < _skeleton->getNumJoints(), \"Joint index out of bounds\", nullptr);\nreturn _skeleton->getJoint(joint_index);\n}\ndart::dynamics::DegreeOfFreedom* Robot::dof(const std::string& dof_name) { return _skeleton->getDof(dof_name); }\ndart::dynamics::DegreeOfFreedom* Robot::dof(size_t dof_index)\n{\nROBOT_DART_ASSERT(dof_index < _skeleton->getNumDofs(), \"Dof index out of bounds\", nullptr);\nreturn _skeleton->getDof(dof_index);\n}\nconst std::string& Robot::name() const { return _robot_name; }\nvoid Robot::update(double t)\n{\n_skeleton->setCommands(Eigen::VectorXd::Zero(_skeleton->getNumDofs()));\nfor (auto& ctrl : _controllers) {\nif (ctrl->active())\ndetail::add_dof_data<4>(ctrl->weight() * ctrl->calculate(t), _skeleton,\nctrl->controllable_dofs(), _dof_map);\n}\n}\nvoid Robot::reinit_controllers()\n{\nfor (auto& ctrl : _controllers)\nctrl->init();\n}\nsize_t Robot::num_controllers() const { return _controllers.size(); }\nstd::vector<std::shared_ptr<control::RobotControl>> Robot::controllers() const\n{\nreturn _controllers;\n}\nstd::vector<std::shared_ptr<control::RobotControl>> Robot::active_controllers() const\n{\nstd::vector<std::shared_ptr<control::RobotControl>> ctrls;\nfor (auto& ctrl : _controllers) {\nif (ctrl->active())\nctrls.push_back(ctrl);\n}\nreturn ctrls;\n}\nstd::shared_ptr<control::RobotControl> Robot::controller(size_t index) const\n{\nROBOT_DART_ASSERT(index < _controllers.size(), \"Controller index out of bounds\", nullptr);\nreturn _controllers[index];\n}\nvoid Robot::add_controller(\nconst std::shared_ptr<control::RobotControl>& controller, double weight)\n{\n_controllers.push_back(controller);\ncontroller->set_robot(this->shared_from_this());\ncontroller->set_weight(weight);\ncontroller->init();\n}\nvoid Robot::remove_controller(const std::shared_ptr<control::RobotControl>& controller)\n{\nauto it = std::find(_controllers.begin(), _controllers.end(), controller);\nif (it != _controllers.end())\n_controllers.erase(it);\n}\nvoid Robot::remove_controller(size_t index)\n{\nROBOT_DART_ASSERT(index < _controllers.size(), \"Controller index out of bounds\", );\n_controllers.erase(_controllers.begin() + index);\n}\nvoid Robot::clear_controllers() { _controllers.clear(); }\nvoid Robot::fix_to_world()\n{\nauto parent_jt = _skeleton->getRootBodyNode()->getParentJoint();\nROBOT_DART_ASSERT(parent_jt != nullptr, \"RootBodyNode does not have a parent joint!\", );\nif (fixed())\nreturn;\nEigen::Isometry3d tf(dart::math::expAngular(_skeleton->getPositions().head(3)));\ntf.translation() = _skeleton->getPositions().segment(3, 3);\ndart::dynamics::WeldJoint::Properties properties;\nproperties.mName = parent_jt->getName();\n_skeleton->getRootBodyNode()->changeParentJointType<dart::dynamics::WeldJoint>(properties);\n_skeleton->getRootBodyNode()->getParentJoint()->setTransformFromParentBodyNode(tf);\nreinit_controllers();\nupdate_joint_dof_maps();\n}\n// pose: Orientation-Position\nvoid Robot::free_from_world(const Eigen::Vector6d& pose)\n{\nauto parent_jt = _skeleton->getRootBodyNode()->getParentJoint();\nROBOT_DART_ASSERT(parent_jt != nullptr, \"RootBodyNode does not have a parent joint!\", );\nEigen::Isometry3d tf(dart::math::expAngular(pose.head(3)));\ntf.translation() = pose.segment(3, 3);\n// if already free, we only change the transformation\nif (free()) {\nparent_jt->setTransformFromParentBodyNode(tf);\nreturn;\n}\ndart::dynamics::FreeJoint::Properties properties;\nproperties.mName = parent_jt->getName();\n_skeleton->getRootBodyNode()->changeParentJointType<dart::dynamics::FreeJoint>(properties);\n_skeleton->getRootBodyNode()->getParentJoint()->setTransformFromParentBodyNode(tf);\nreinit_controllers();\nupdate_joint_dof_maps();\n}\nbool Robot::fixed() const\n{\nauto parent_jt = _skeleton->getRootBodyNode()->getParentJoint();\nROBOT_DART_ASSERT(parent_jt != nullptr, \"RootBodyNode does not have a parent joint!\", false);\nreturn parent_jt->getType() == dart::dynamics::WeldJoint::getStaticType();\n}\nbool Robot::free() const\n{\nauto parent_jt = _skeleton->getRootBodyNode()->getParentJoint();\nROBOT_DART_ASSERT(parent_jt != nullptr, \"RootBodyNode does not have a parent joint!\", false);\nreturn parent_jt->getType() == dart::dynamics::FreeJoint::getStaticType();\n}\nvoid Robot::reset()\n{\n_skeleton->resetPositions();\n_skeleton->resetVelocities();\n_skeleton->resetAccelerations();\nclear_internal_forces();\nreset_commands();\nclear_external_forces();\n}\nvoid Robot::clear_external_forces() { _skeleton->clearExternalForces(); }\nvoid Robot::clear_internal_forces()\n{\n_skeleton->clearInternalForces();\n_skeleton->clearConstraintImpulses();\n}\nvoid Robot::reset_commands() { _skeleton->resetCommands(); }\nvoid Robot::set_actuator_types(const std::string& type, const std::vector<std::string>& joint_names, bool override_mimic, bool override_base)\n{\n// Set all dofs to same actuator type\nif (joint_names.empty()) {\nif (type == \"torque\") {\nreturn _set_actuator_types(dart::dynamics::Joint::FORCE, override_mimic, override_base);\n}\nelse if (type == \"servo\") {\nreturn _set_actuator_types(dart::dynamics::Joint::SERVO, override_mimic, override_base);\n}\nelse if (type == \"velocity\") {\nreturn _set_actuator_types(dart::dynamics::Joint::VELOCITY, override_mimic, override_base);\n}\nelse if (type == \"passive\") {\nreturn _set_actuator_types(dart::dynamics::Joint::PASSIVE, override_mimic, override_base);\n}\nelse if (type == \"locked\") {\nreturn _set_actuator_types(dart::dynamics::Joint::LOCKED, override_mimic, override_base);\n}\nelse if (type == \"mimic\") {\nROBOT_DART_WARNING(true, \"Use this only if you know what you are doing. Use set_mimic otherwise.\");\nreturn _set_actuator_types(dart::dynamics::Joint::MIMIC, override_mimic, override_base);\n}\nROBOT_DART_EXCEPTION_ASSERT(false, \"Unknown type of actuator type. Valid values: torque, servo, velocity, passive, locked, mimic\");\n}\nfor (size_t i = 0; i < joint_names.size(); i++) {\nauto it = _joint_map.find(joint_names[i]);\nROBOT_DART_ASSERT(it != _joint_map.end(), \"set_actuator_type: \" + joint_names[i] + \" is not in joint_map\", );\nif (type == \"torque\") {\n_set_actuator_type(it->second, dart::dynamics::Joint::FORCE, override_mimic, override_base);\n}\nelse if (type == \"servo\") {\n_set_actuator_type(it->second, dart::dynamics::Joint::SERVO, override_mimic, override_base);\n}\nelse if (type == \"velocity\") {\n_set_actuator_type(it->second, dart::dynamics::Joint::VELOCITY, override_mimic, override_base);\n}\nelse if (type == \"passive\") {\n_set_actuator_type(it->second, dart::dynamics::Joint::PASSIVE, override_mimic, override_base);\n}\nelse if (type == \"locked\") {\n_set_actuator_type(it->second, dart::dynamics::Joint::LOCKED, override_mimic, override_base);\n}\nelse if (type == \"mimic\") {\nROBOT_DART_WARNING(true, \"Use this only if you know what you are doing. Use set_mimic otherwise.\");\n_set_actuator_type(it->second, dart::dynamics::Joint::MIMIC, override_mimic, override_base);\n}\nelse\nROBOT_DART_EXCEPTION_ASSERT(false, \"Unknown type of actuator type. Valid values: torque, servo, velocity, passive, locked, mimic\");\n}\n}\nvoid Robot::set_actuator_type(const std::string& type, const std::string& joint_name, bool override_mimic, bool override_base)\n{\nset_actuator_types(type, {joint_name}, override_mimic, override_base);\n}\nvoid Robot::set_mimic(const std::string& joint_name, const std::string& mimic_joint_name, double multiplier, double offset)\n{\ndart::dynamics::Joint* jnt = _skeleton->getJoint(joint_name);\nconst dart::dynamics::Joint* mimic_jnt = _skeleton->getJoint(mimic_joint_name);\nROBOT_DART_ASSERT((jnt && mimic_jnt), \"set_mimic: joint names do not exist\", );\njnt->setActuatorType(dart::dynamics::Joint::MIMIC);\njnt->setMimicJoint(mimic_jnt, multiplier, offset);\n}\nstd::string Robot::actuator_type(const std::string& joint_name) const\n{\nauto it = _joint_map.find(joint_name);\nROBOT_DART_ASSERT(it != _joint_map.end(), \"actuator_type: \" + joint_name + \" is not in joint_map\", \"invalid\");\nauto type = _actuator_type(it->second);\nif (type == dart::dynamics::Joint::FORCE)\nreturn \"torque\";\nelse if (type == dart::dynamics::Joint::SERVO)\nreturn \"servo\";\nelse if (type == dart::dynamics::Joint::VELOCITY)\nreturn \"velocity\";\nelse if (type == dart::dynamics::Joint::PASSIVE)\nreturn \"passive\";\nelse if (type == dart::dynamics::Joint::LOCKED)\nreturn \"locked\";\nelse if (type == dart::dynamics::Joint::MIMIC)\nreturn \"mimic\";\nROBOT_DART_ASSERT(false, \"actuator_type: we should not reach here\", \"invalid\");\n}\nstd::vector<std::string> Robot::actuator_types(const std::vector<std::string>& joint_names) const\n{\nstd::vector<std::string> str_types;\n// Get all dofs\nif (joint_names.empty()) {\nauto types = _actuator_types();\nfor (size_t i = 0; i < types.size(); i++) {\nauto type = types[i];\nif (type == dart::dynamics::Joint::FORCE)\nstr_types.push_back(\"torque\");\nelse if (type == dart::dynamics::Joint::SERVO)\nstr_types.push_back(\"servo\");\nelse if (type == dart::dynamics::Joint::VELOCITY)\nstr_types.push_back(\"velocity\");\nelse if (type == dart::dynamics::Joint::PASSIVE)\nstr_types.push_back(\"passive\");\nelse if (type == dart::dynamics::Joint::LOCKED)\nstr_types.push_back(\"locked\");\nelse if (type == dart::dynamics::Joint::MIMIC)\nstr_types.push_back(\"mimic\");\n}\nROBOT_DART_ASSERT(str_types.size() == types.size(), \"actuator_types: sizes of retrieved modes do not match\", {});\nreturn str_types;\n}\nfor (size_t i = 0; i < joint_names.size(); i++) {\nstr_types.push_back(actuator_type(joint_names[i]));\n}\nROBOT_DART_ASSERT(str_types.size() == joint_names.size(), \"actuator_types: sizes of retrieved modes do not match\", {});\nreturn str_types;\n}\nvoid Robot::set_position_enforced(const std::vector<bool>& enforced, const std::vector<std::string>& dof_names)\n{\nsize_t n_dofs = dof_names.size();\nif (n_dofs == 0) {\nROBOT_DART_ASSERT(enforced.size() == _skeleton->getNumDofs(),\n\"Position enforced vector size is not the same as the DOFs of the robot\", );\nfor (size_t i = 0; i < _skeleton->getNumDofs(); ++i) {\n#if DART_VERSION_AT_LEAST(6, 10, 0)\n_skeleton->getDof(i)->getJoint()->setLimitEnforcement(enforced[i]);\n#else\n_skeleton->getDof(i)->getJoint()->setPositionLimitEnforced(enforced[i]);\n#endif\n}\n}\nelse {\nROBOT_DART_ASSERT(enforced.size() == dof_names.size(),\n\"Position enforced vector size is not the same as the dof_names size\", );\nfor (size_t i = 0; i < dof_names.size(); i++) {\nauto it = _dof_map.find(dof_names[i]);\nROBOT_DART_ASSERT(it != _dof_map.end(), \"set_position_enforced: \" + dof_names[i] + \" is not in dof_map\", );\n#if DART_VERSION_AT_LEAST(6, 10, 0)\n_skeleton->getDof(it->second)->getJoint()->setLimitEnforcement(enforced[i]);\n#else\n_skeleton->getDof(it->second)->getJoint()->setPositionLimitEnforced(enforced[i]);\n#endif\n}\n}\n}\nvoid Robot::set_position_enforced(bool enforced, const std::vector<std::string>& dof_names)\n{\nsize_t n_dofs = dof_names.size();\nif (n_dofs == 0)\nn_dofs = _skeleton->getNumDofs();\nstd::vector<bool> enforced_all(n_dofs, enforced);\nset_position_enforced(enforced_all, dof_names);\n}\nstd::vector<bool> Robot::position_enforced(const std::vector<std::string>& dof_names) const\n{\nstd::vector<bool> pos;\nif (dof_names.size() == 0) {\nfor (size_t i = 0; i < _skeleton->getNumDofs(); ++i) {\n#if DART_VERSION_AT_LEAST(6, 10, 0)\npos.push_back(_skeleton->getDof(i)->getJoint()->areLimitsEnforced());\n#else\npos.push_back(_skeleton->getDof(i)->getJoint()->isPositionLimitEnforced());\n#endif\n}\n}\nelse {\nfor (size_t i = 0; i < dof_names.size(); i++) {\nauto it = _dof_map.find(dof_names[i]);\nROBOT_DART_ASSERT(it != _dof_map.end(), \"position_enforced: \" + dof_names[i] + \" is not in dof_map\", std::vector<bool>());\n#if DART_VERSION_AT_LEAST(6, 10, 0)\npos.push_back(_skeleton->getDof(it->second)->getJoint()->areLimitsEnforced());\n#else\npos.push_back(_skeleton->getDof(it->second)->getJoint()->isPositionLimitEnforced());\n#endif\n}\n}\nreturn pos;\n}\nvoid Robot::force_position_bounds()\n{\nfor (size_t i = 0; i < _skeleton->getNumDofs(); ++i) {\nauto dof = _skeleton->getDof(i);\nauto jt = dof->getJoint();\n#if DART_VERSION_AT_LEAST(6, 10, 0)\nbool force = jt->areLimitsEnforced();\n#else\nbool force = jt->isPositionLimitEnforced();\n#endif\nauto type = jt->getActuatorType();\nforce = force || type == dart::dynamics::Joint::SERVO || type == dart::dynamics::Joint::MIMIC;\nif (force) {\ndouble epsilon = 1e-5;\nif (dof->getPosition() > dof->getPositionUpperLimit()) {\ndof->setPosition(dof->getPositionUpperLimit() - epsilon);\n}\nelse if (dof->getPosition() < dof->getPositionLowerLimit()) {\ndof->setPosition(dof->getPositionLowerLimit() + epsilon);\n}\n}\n}\n}\nvoid Robot::set_damping_coeffs(const std::vector<double>& damps, const std::vector<std::string>& dof_names)\n{\nsize_t n_dofs = dof_names.size();\nif (n_dofs == 0) {\nROBOT_DART_ASSERT(damps.size() == _skeleton->getNumDofs(),\n\"Damping coefficient vector size is not the same as the DOFs of the robot\", );\nfor (size_t i = 0; i < _skeleton->getNumDofs(); ++i) {\n_skeleton->getDof(i)->setDampingCoefficient(damps[i]);\n}\n}\nelse {\nROBOT_DART_ASSERT(damps.size() == dof_names.size(),\n\"Damping coefficient vector size is not the same as the dof_names size\", );\nfor (size_t i = 0; i < dof_names.size(); i++) {\nauto it = _dof_map.find(dof_names[i]);\nROBOT_DART_ASSERT(it != _dof_map.end(), \"set_damping_coeffs: \" + dof_names[i] + \" is not in dof_map\", );\n_skeleton->getDof(it->second)->setDampingCoefficient(damps[i]);\n}\n}\n}\nvoid Robot::set_damping_coeffs(double damp, const std::vector<std::string>& dof_names)\n{\nsize_t n_dofs = dof_names.size();\nif (n_dofs == 0)\nn_dofs = _skeleton->getNumDofs();\nstd::vector<double> damps_all(n_dofs, damp);\nset_damping_coeffs(damps_all, dof_names);\n}\nstd::vector<double> Robot::damping_coeffs(const std::vector<std::string>& dof_names) const\n{\nstd::vector<double> dampings;\nif (dof_names.size() == 0) {\nfor (size_t i = 0; i < _skeleton->getNumDofs(); ++i) {\ndampings.push_back(_skeleton->getDof(i)->getDampingCoefficient());\n}\n}\nelse {\nfor (size_t i = 0; i < dof_names.size(); i++) {\nauto it = _dof_map.find(dof_names[i]);\nROBOT_DART_ASSERT(it != _dof_map.end(), \"damping_coeffs: \" + dof_names[i] + \" is not in dof_map\", std::vector<double>());\ndampings.push_back(_skeleton->getDof(it->second)->getDampingCoefficient());\n}\n}\nreturn dampings;\n}\nvoid Robot::set_coulomb_coeffs(const std::vector<double>& cfrictions, const std::vector<std::string>& dof_names)\n{\nsize_t n_dofs = dof_names.size();\nif (n_dofs == 0) {\nROBOT_DART_ASSERT(cfrictions.size() == _skeleton->getNumDofs(),\n\"Coulomb friction coefficient vector size is not the same as the DOFs of the robot\", );\nfor (size_t i = 0; i < _skeleton->getNumDofs(); ++i) {\n_skeleton->getDof(i)->setCoulombFriction(cfrictions[i]);\n}\n}\nelse {\nROBOT_DART_ASSERT(cfrictions.size() == dof_names.size(),\n\"Coulomb friction coefficient vector size is not the same as the dof_names size\", );\nfor (size_t i = 0; i < dof_names.size(); i++) {\nauto it = _dof_map.find(dof_names[i]);\nROBOT_DART_ASSERT(it != _dof_map.end(), \"set_coulomb_coeffs: \" + dof_names[i] + \" is not in dof_map\", );\n_skeleton->getDof(it->second)->setCoulombFriction(cfrictions[i]);\n}\n}\n}\nvoid Robot::set_coulomb_coeffs(double cfriction, const std::vector<std::string>& dof_names)\n{\nsize_t n_dofs = dof_names.size();\nif (n_dofs == 0)\nn_dofs = _skeleton->getNumDofs();\nstd::vector<double> cfrictions(n_dofs, cfriction);\nset_coulomb_coeffs(cfrictions, dof_names);\n}\nstd::vector<double> Robot::coulomb_coeffs(const std::vector<std::string>& dof_names) const\n{\nstd::vector<double> cfrictions;\nif (dof_names.size() == 0) {\nfor (size_t i = 0; i < _skeleton->getNumDofs(); ++i) {\ncfrictions.push_back(_skeleton->getDof(i)->getCoulombFriction());\n}\n}\nelse {\nfor (size_t i = 0; i < dof_names.size(); i++) {\nauto it = _dof_map.find(dof_names[i]);\nROBOT_DART_ASSERT(it != _dof_map.end(), \"coulomb_coeffs: \" + dof_names[i] + \" is not in dof_map\", std::vector<double>());\ncfrictions.push_back(_skeleton->getDof(it->second)->getCoulombFriction());\n}\n}\nreturn cfrictions;\n}\nvoid Robot::set_spring_stiffnesses(const std::vector<double>& stiffnesses, const std::vector<std::string>& dof_names)\n{\nsize_t n_dofs = dof_names.size();\nif (n_dofs == 0) {\nROBOT_DART_ASSERT(stiffnesses.size() == _skeleton->getNumDofs(),\n\"Spring stiffnesses vector size is not the same as the DOFs of the robot\", );\nfor (size_t i = 0; i < _skeleton->getNumDofs(); ++i) {\n_skeleton->getDof(i)->setSpringStiffness(stiffnesses[i]);\n}\n}\nelse {\nROBOT_DART_ASSERT(stiffnesses.size() == dof_names.size(),\n\"Spring stiffnesses vector size is not the same as the dof_names size\", );\nfor (size_t i = 0; i < dof_names.size(); i++) {\nauto it = _dof_map.find(dof_names[i]);\nROBOT_DART_ASSERT(it != _dof_map.end(), \"set_spring_stiffnesses: \" + dof_names[i] + \" is not in dof_map\", );\n_skeleton->getDof(it->second)->setSpringStiffness(stiffnesses[i]);\n}\n}\n}\nvoid Robot::set_spring_stiffnesses(double stiffness, const std::vector<std::string>& dof_names)\n{\nsize_t n_dofs = dof_names.size();\nif (n_dofs == 0)\nn_dofs = _skeleton->getNumDofs();\nstd::vector<double> stiffnesses(n_dofs, stiffness);\nset_spring_stiffnesses(stiffnesses, dof_names);\n}\nstd::vector<double> Robot::spring_stiffnesses(const std::vector<std::string>& dof_names) const\n{\nstd::vector<double> stiffnesses;\nif (dof_names.size() == 0) {\nfor (size_t i = 0; i < _skeleton->getNumDofs(); ++i) {\nstiffnesses.push_back(_skeleton->getDof(i)->getSpringStiffness());\n}\n}\nelse {\nfor (size_t i = 0; i < dof_names.size(); i++) {\nauto it = _dof_map.find(dof_names[i]);\nROBOT_DART_ASSERT(it != _dof_map.end(), \"spring_stiffnesses: \" + dof_names[i] + \" is not in dof_map\", std::vector<double>());\nstiffnesses.push_back(_skeleton->getDof(it->second)->getSpringStiffness());\n}\n}\nreturn stiffnesses;\n}\n#if DART_VERSION_AT_LEAST(6, 10, 0)\nauto body_node_set_friction_dir = [](dart::dynamics::BodyNode* body, const Eigen::Vector3d& direction) {\nauto& dyn_shapes = body->getShapeNodesWith<dart::dynamics::DynamicsAspect>();\nfor (auto& shape : dyn_shapes) {\nconst auto& dyn = shape->getDynamicsAspect();\ndyn->setFirstFrictionDirection(direction);\ndyn->setFirstFrictionDirectionFrame(body);\n}\n};\n#endif\nvoid Robot::set_friction_dir(const std::string& body_name, const Eigen::Vector3d& direction)\n{\n#if DART_VERSION_AT_LEAST(6, 10, 0)\nauto bd = _skeleton->getBodyNode(body_name);\nROBOT_DART_ASSERT(bd != nullptr, \"BodyNode does not exist in skeleton!\", );\nbody_node_set_friction_dir(bd, direction);\n#else\nROBOT_DART_WARNING(true, \"DART supports the frictional direction from v.6.10 onwards!\");\n#endif\n}\nvoid Robot::set_friction_dir(size_t body_index, const Eigen::Vector3d& direction)\n{\n#if DART_VERSION_AT_LEAST(6, 10, 0)\nROBOT_DART_ASSERT(body_index < _skeleton->getNumBodyNodes(), \"BodyNode index out of bounds\", );\nbody_node_set_friction_dir(_skeleton->getBodyNode(body_index), direction);\n#else\nROBOT_DART_WARNING(true, \"DART supports the frictional direction from v.6.10 onwards!\");\n#endif\n}\n#if DART_VERSION_AT_LEAST(6, 10, 0)\nauto body_node_get_friction_dir = [](dart::dynamics::BodyNode* body) {\nauto& dyn_shapes = body->getShapeNodesWith<dart::dynamics::DynamicsAspect>();\nfor (auto& shape : dyn_shapes) {\nconst auto& dyn = shape->getDynamicsAspect();\nreturn dyn->getFirstFrictionDirection(); // assume all shape nodes have the same friction direction\n}\nreturn Eigen::Vector3d(Eigen::Vector3d::Zero());\n};\n#endif\nEigen::Vector3d Robot::friction_dir(const std::string& body_name)\n{\n#if DART_VERSION_AT_LEAST(6, 10, 0)\nauto bd = _skeleton->getBodyNode(body_name);\nROBOT_DART_ASSERT(bd != nullptr, \"BodyNode does not exist in skeleton!\", Eigen::Vector3d::Zero());\nreturn body_node_get_friction_dir(bd);\n#else\nROBOT_DART_WARNING(true, \"DART supports the frictional direction from v.6.10 onwards!\");\nreturn Eigen::Vector3d::Zero();\n#endif\n}\nEigen::Vector3d Robot::friction_dir(size_t body_index)\n{\n#if DART_VERSION_AT_LEAST(6, 10, 0)\nROBOT_DART_ASSERT(body_index < _skeleton->getNumBodyNodes(), \"BodyNode index out of bounds\", Eigen::Vector3d::Zero());\nreturn body_node_get_friction_dir(_skeleton->getBodyNode(body_index));\n#else\nROBOT_DART_WARNING(true, \"DART supports the frictional direction from v.6.10 onwards!\");\nreturn Eigen::Vector3d::Zero();\n#endif\n}\nauto body_node_set_friction_coeff = [](dart::dynamics::BodyNode* body, double value) {\n#if DART_VERSION_AT_LEAST(6, 10, 0)\nauto& dyn_shapes = body->getShapeNodesWith<dart::dynamics::DynamicsAspect>();\nfor (auto& shape : dyn_shapes) {\nshape->getDynamicsAspect()->setFrictionCoeff(value);\n}\n#else\nbody->setFrictionCoeff(value);\n#endif\n};\nvoid Robot::set_friction_coeff(const std::string& body_name, double value)\n{\nauto bd = _skeleton->getBodyNode(body_name);\nROBOT_DART_ASSERT(bd != nullptr, \"BodyNode does not exist in skeleton!\", );\nbody_node_set_friction_coeff(bd, value);\n}\nvoid Robot::set_friction_coeff(size_t body_index, double value)\n{\nROBOT_DART_ASSERT(body_index < _skeleton->getNumBodyNodes(), \"BodyNode index out of bounds\", );\nbody_node_set_friction_coeff(_skeleton->getBodyNode(body_index), value);\n}\nvoid Robot::set_friction_coeffs(double value)\n{\nfor (auto bd : _skeleton->getBodyNodes())\nbody_node_set_friction_coeff(bd, value);\n}\nauto body_node_get_friction_coeff = [](dart::dynamics::BodyNode* body) {\n#if DART_VERSION_AT_LEAST(6, 10, 0)\nauto& dyn_shapes = body->getShapeNodesWith<dart::dynamics::DynamicsAspect>();\nfor (auto& shape : dyn_shapes) {\nreturn shape->getDynamicsAspect()->getFrictionCoeff(); // assume all shape nodes have the same friction\n}\nreturn 0.;\n#else\nreturn body->getFrictionCoeff();\n#endif\n};\ndouble Robot::friction_coeff(const std::string& body_name)\n{\nauto bd = _skeleton->getBodyNode(body_name);\nROBOT_DART_ASSERT(bd != nullptr, \"BodyNode does not exist in skeleton!\", 0.);\nreturn body_node_get_friction_coeff(bd);\n}\ndouble Robot::friction_coeff(size_t body_index)\n{\nROBOT_DART_ASSERT(body_index < _skeleton->getNumBodyNodes(), \"BodyNode index out of bounds\", 0.);\nreturn body_node_get_friction_coeff(_skeleton->getBodyNode(body_index));\n}\n#if DART_VERSION_AT_LEAST(6, 10, 0)\nauto body_node_set_secondary_friction_coeff = [](dart::dynamics::BodyNode* body, double value) {\nauto& dyn_shapes = body->getShapeNodesWith<dart::dynamics::DynamicsAspect>();\nfor (auto& shape : dyn_shapes) {\nshape->getDynamicsAspect()->setSecondaryFrictionCoeff(value);\n}\n};\n#endif\nvoid Robot::set_secondary_friction_coeff(const std::string& body_name, double value)\n{\n#if DART_VERSION_AT_LEAST(6, 10, 0)\nauto bd = _skeleton->getBodyNode(body_name);\nROBOT_DART_ASSERT(bd != nullptr, \"BodyNode does not exist in skeleton!\", );\nbody_node_set_secondary_friction_coeff(bd, value);\n#else\nROBOT_DART_WARNING(true, \"DART supports the secondary friction coefficient from v.6.10 onwards!\");\n#endif\n}\nvoid Robot::set_secondary_friction_coeff(size_t body_index, double value)\n{\n#if DART_VERSION_AT_LEAST(6, 10, 0)\nROBOT_DART_ASSERT(body_index < _skeleton->getNumBodyNodes(), \"BodyNode index out of bounds\", );\nbody_node_set_secondary_friction_coeff(_skeleton->getBodyNode(body_index), value);\n#else\nROBOT_DART_WARNING(true, \"DART supports the secondary friction coefficient from v.6.10 onwards!\");\n#endif\n}\nvoid Robot::set_secondary_friction_coeffs(double value)\n{\n#if DART_VERSION_AT_LEAST(6, 10, 0)\nfor (auto bd : _skeleton->getBodyNodes())\nbody_node_set_secondary_friction_coeff(bd, value);\n#else\nROBOT_DART_WARNING(true, \"DART supports the secondary friction coefficient from v.6.10 onwards!\");\n#endif\n}\n#if DART_VERSION_AT_LEAST(6, 10, 0)\nauto body_node_get_secondary_friction_coeff = [](dart::dynamics::BodyNode* body) {\nauto& dyn_shapes = body->getShapeNodesWith<dart::dynamics::DynamicsAspect>();\nfor (auto& shape : dyn_shapes) {\nreturn shape->getDynamicsAspect()->getSecondaryFrictionCoeff(); // assume all shape nodes have the same friction\n}\nreturn 0.;\n};\n#endif\ndouble Robot::secondary_friction_coeff(const std::string& body_name)\n{\n#if DART_VERSION_AT_LEAST(6, 10, 0)\nauto bd = _skeleton->getBodyNode(body_name);\nROBOT_DART_ASSERT(bd != nullptr, \"BodyNode does not exist in skeleton!\", 0.);\nreturn body_node_get_secondary_friction_coeff(bd);\n#else\nROBOT_DART_WARNING(true, \"DART supports the secondary friction coefficient from v.6.10 onwards!\");\nreturn 0.;\n#endif\n}\ndouble Robot::secondary_friction_coeff(size_t body_index)\n{\n#if DART_VERSION_AT_LEAST(6, 10, 0)\nROBOT_DART_ASSERT(body_index < _skeleton->getNumBodyNodes(), \"BodyNode index out of bounds\", 0.);\nreturn body_node_get_secondary_friction_coeff(_skeleton->getBodyNode(body_index));\n#else\nROBOT_DART_WARNING(true, \"DART supports the secondary friction coefficient from v.6.10 onwards!\");\nreturn 0.;\n#endif\n}\nauto body_node_set_restitution_coeff = [](dart::dynamics::BodyNode* body, double value) {\n#if DART_VERSION_AT_LEAST(6, 10, 0)\nauto& dyn_shapes = body->getShapeNodesWith<dart::dynamics::DynamicsAspect>();\nfor (auto& shape : dyn_shapes) {\nshape->getDynamicsAspect()->setRestitutionCoeff(value);\n}\n#else\nbody->setRestitutionCoeff(value);\n#endif\n};\nvoid Robot::set_restitution_coeff(const std::string& body_name, double value)\n{\nauto bd = _skeleton->getBodyNode(body_name);\nROBOT_DART_ASSERT(bd != nullptr, \"BodyNode does not exist in skeleton!\", );\nbody_node_set_restitution_coeff(bd, value);\n}\nvoid Robot::set_restitution_coeff(size_t body_index, double value)\n{\nROBOT_DART_ASSERT(body_index < _skeleton->getNumBodyNodes(), \"BodyNode index out of bounds\", );\nbody_node_set_restitution_coeff(_skeleton->getBodyNode(body_index), value);\n}\nvoid Robot::set_restitution_coeffs(double value)\n{\nfor (auto bd : _skeleton->getBodyNodes())\nbody_node_set_restitution_coeff(bd, value);\n}\nauto body_node_get_restitution_coeff = [](dart::dynamics::BodyNode* body) {\n#if DART_VERSION_AT_LEAST(6, 10, 0)\nauto& dyn_shapes = body->getShapeNodesWith<dart::dynamics::DynamicsAspect>();\nfor (auto& shape : dyn_shapes) {\nreturn shape->getDynamicsAspect()->getRestitutionCoeff(); // assume all shape nodes have the same restitution\n}\nreturn 0.;\n#else\nreturn body->getRestitutionCoeff();\n#endif\n};\ndouble Robot::restitution_coeff(const std::string& body_name)\n{\nauto bd = _skeleton->getBodyNode(body_name);\nROBOT_DART_ASSERT(bd != nullptr, \"BodyNode does not exist in skeleton!\", 0.);\nreturn body_node_get_restitution_coeff(bd);\n}\ndouble Robot::restitution_coeff(size_t body_index)\n{\nROBOT_DART_ASSERT(body_index < _skeleton->getNumBodyNodes(), \"BodyNode index out of bounds\", 0.);\nreturn body_node_get_restitution_coeff(_skeleton->getBodyNode(body_index));\n}\nEigen::Isometry3d Robot::base_pose() const\n{\nif (free()) {\nEigen::Isometry3d tf(Eigen::Isometry3d::Identity());\ntf.linear() = dart::math::expMapRot(_skeleton->getPositions().head<6>().head<3>());\ntf.translation() = _skeleton->getPositions().head<6>().tail<3>();\nreturn tf;\n}\nauto jt = _skeleton->getRootBodyNode()->getParentJoint();\nROBOT_DART_ASSERT(jt != nullptr, \"Skeleton does not have a proper root BodyNode!\",\nEigen::Isometry3d::Identity());\nreturn jt->getTransformFromParentBodyNode();\n}\nEigen::Vector6d Robot::base_pose_vec() const\n{\nif (free())\nreturn _skeleton->getPositions().head(6);\nauto jt = _skeleton->getRootBodyNode()->getParentJoint();\nROBOT_DART_ASSERT(jt != nullptr, \"Skeleton does not have a proper root BodyNode!\",\nEigen::Vector6d::Zero());\nEigen::Isometry3d tf = jt->getTransformFromParentBodyNode();\nEigen::Vector6d x;\nx.head<3>() = dart::math::logMap(tf.linear());\nx.tail<3>() = tf.translation();\nreturn x;\n}\nvoid Robot::set_base_pose(const Eigen::Isometry3d& tf)\n{\nauto jt = _skeleton->getRootBodyNode()->getParentJoint();\nif (jt) {\nif (free()) {\nEigen::Vector6d x;\nx.head<3>() = dart::math::logMap(tf.linear());\nx.tail<3>() = tf.translation();\njt->setPositions(x);\n}\nelse\njt->setTransformFromParentBodyNode(tf);\n}\n}\nvoid Robot::set_base_pose(const Eigen::Vector6d& pose)\n{\nauto jt = _skeleton->getRootBodyNode()->getParentJoint();\nif (jt) {\nif (free())\njt->setPositions(pose);\nelse {\nEigen::Isometry3d tf(Eigen::Isometry3d::Identity());\ntf.linear() = dart::math::expMapRot(pose.head<3>());\ntf.translation() = pose.tail<3>();\njt->setTransformFromParentBodyNode(tf);\n}\n}\n}\nsize_t Robot::num_dofs() const { return _skeleton->getNumDofs(); }\nsize_t Robot::num_joints() const { return _skeleton->getNumJoints(); }\nsize_t Robot::num_bodies() const { return _skeleton->getNumBodyNodes(); }\nEigen::Vector3d Robot::com() const { return _skeleton->getCOM(); }\nEigen::Vector6d Robot::com_velocity() const { return _skeleton->getCOMSpatialVelocity(); }\nEigen::Vector6d Robot::com_acceleration() const { return _skeleton->getCOMSpatialAcceleration(); }\nEigen::VectorXd Robot::positions(const std::vector<std::string>& dof_names) const\n{\nreturn detail::dof_data<0>(_skeleton, dof_names, _dof_map);\n}\nvoid Robot::set_positions(const Eigen::VectorXd& positions, const std::vector<std::string>& dof_names)\n{\ndetail::set_dof_data<0>(positions, _skeleton, dof_names, _dof_map);\n}\nEigen::VectorXd Robot::position_lower_limits(const std::vector<std::string>& dof_names) const\n{\nreturn detail::dof_data<5>(_skeleton, dof_names, _dof_map);\n}\nvoid Robot::set_position_lower_limits(const Eigen::VectorXd& positions, const std::vector<std::string>& dof_names)\n{\ndetail::set_dof_data<5>(positions, _skeleton, dof_names, _dof_map);\n}\nEigen::VectorXd Robot::position_upper_limits(const std::vector<std::string>& dof_names) const\n{\nreturn detail::dof_data<6>(_skeleton, dof_names, _dof_map);\n}\nvoid Robot::set_position_upper_limits(const Eigen::VectorXd& positions, const std::vector<std::string>& dof_names)\n{\ndetail::set_dof_data<6>(positions, _skeleton, dof_names, _dof_map);\n}\nEigen::VectorXd Robot::velocities(const std::vector<std::string>& dof_names) const\n{\nreturn detail::dof_data<1>(_skeleton, dof_names, _dof_map);\n}\nvoid Robot::set_velocities(const Eigen::VectorXd& velocities, const std::vector<std::string>& dof_names)\n{\ndetail::set_dof_data<1>(velocities, _skeleton, dof_names, _dof_map);\n}\nEigen::VectorXd Robot::velocity_lower_limits(const std::vector<std::string>& dof_names) const\n{\nreturn detail::dof_data<7>(_skeleton, dof_names, _dof_map);\n}\nvoid Robot::set_velocity_lower_limits(const Eigen::VectorXd& velocities, const std::vector<std::string>& dof_names)\n{\ndetail::set_dof_data<7>(velocities, _skeleton, dof_names, _dof_map);\n}\nEigen::VectorXd Robot::velocity_upper_limits(const std::vector<std::string>& dof_names) const\n{\nreturn detail::dof_data<8>(_skeleton, dof_names, _dof_map);\n}\nvoid Robot::set_velocity_upper_limits(const Eigen::VectorXd& velocities, const std::vector<std::string>& dof_names)\n{\ndetail::set_dof_data<8>(velocities, _skeleton, dof_names, _dof_map);\n}\nEigen::VectorXd Robot::accelerations(const std::vector<std::string>& dof_names) const\n{\nreturn detail::dof_data<2>(_skeleton, dof_names, _dof_map);\n}\nvoid Robot::set_accelerations(const Eigen::VectorXd& accelerations, const std::vector<std::string>& dof_names)\n{\ndetail::set_dof_data<2>(accelerations, _skeleton, dof_names, _dof_map);\n}\nEigen::VectorXd Robot::acceleration_lower_limits(const std::vector<std::string>& dof_names) const\n{\nreturn detail::dof_data<9>(_skeleton, dof_names, _dof_map);\n}\nvoid Robot::set_acceleration_lower_limits(const Eigen::VectorXd& accelerations, const std::vector<std::string>& dof_names)\n{\ndetail::set_dof_data<9>(accelerations, _skeleton, dof_names, _dof_map);\n}\nEigen::VectorXd Robot::acceleration_upper_limits(const std::vector<std::string>& dof_names) const\n{\nreturn detail::dof_data<10>(_skeleton, dof_names, _dof_map);\n}\nvoid Robot::set_acceleration_upper_limits(const Eigen::VectorXd& accelerations, const std::vector<std::string>& dof_names)\n{\ndetail::set_dof_data<10>(accelerations, _skeleton, dof_names, _dof_map);\n}\nEigen::VectorXd Robot::forces(const std::vector<std::string>& dof_names) const\n{\nreturn detail::dof_data<3>(_skeleton, dof_names, _dof_map);\n}\nvoid Robot::set_forces(const Eigen::VectorXd& forces, const std::vector<std::string>& dof_names)\n{\ndetail::set_dof_data<3>(forces, _skeleton, dof_names, _dof_map);\n}\nEigen::VectorXd Robot::force_lower_limits(const std::vector<std::string>& dof_names) const\n{\nreturn detail::dof_data<11>(_skeleton, dof_names, _dof_map);\n}\nvoid Robot::set_force_lower_limits(const Eigen::VectorXd& forces, const std::vector<std::string>& dof_names)\n{\ndetail::set_dof_data<11>(forces, _skeleton, dof_names, _dof_map);\n}\nEigen::VectorXd Robot::force_upper_limits(const std::vector<std::string>& dof_names) const\n{\nreturn detail::dof_data<12>(_skeleton, dof_names, _dof_map);\n}\nvoid Robot::set_force_upper_limits(const Eigen::VectorXd& forces, const std::vector<std::string>& dof_names)\n{\ndetail::set_dof_data<12>(forces, _skeleton, dof_names, _dof_map);\n}\nEigen::VectorXd Robot::commands(const std::vector<std::string>& dof_names) const\n{\nreturn detail::dof_data<4>(_skeleton, dof_names, _dof_map);\n}\nvoid Robot::set_commands(const Eigen::VectorXd& commands, const std::vector<std::string>& dof_names)\n{\ndetail::set_dof_data<4>(commands, _skeleton, dof_names, _dof_map);\n}\nstd::pair<Eigen::Vector6d, Eigen::Vector6d> Robot::force_torque(size_t joint_index) const\n{\nROBOT_DART_ASSERT(joint_index < _skeleton->getNumJoints(), \"Joint index out of bounds\", {});\nauto jt = _skeleton->getJoint(joint_index);\nEigen::Vector6d F1 = Eigen::Vector6d::Zero();\nEigen::Vector6d F2 = Eigen::Vector6d::Zero();\nEigen::Isometry3d T12 = jt->getRelativeTransform();\nauto child_body = jt->getChildBodyNode();\n// ROBOT_DART_ASSERT(child_body != nullptr, \"Child BodyNode is nullptr\", {});\nif (child_body)\nF2 = -dart::math::dAdT(jt->getTransformFromChildBodyNode(), child_body->getBodyForce());\nF1 = -dart::math::dAdInvR(T12, F2);\n// F1 contains the force applied by the parent Link on the Joint specified in the parent\n// Link frame, F2 contains the force applied by the child Link on the Joint specified in\n// the child Link frame\nreturn {F1, F2};\n}\nvoid Robot::set_external_force(const std::string& body_name, const Eigen::Vector3d& force, const Eigen::Vector3d& offset, bool force_local, bool offset_local)\n{\nauto bd = _skeleton->getBodyNode(body_name);\nROBOT_DART_ASSERT(bd != nullptr, \"BodyNode does not exist in skeleton!\", );\nbd->setExtForce(force, offset, force_local, offset_local);\n}\nvoid Robot::set_external_force(size_t body_index, const Eigen::Vector3d& force, const Eigen::Vector3d& offset, bool force_local, bool offset_local)\n{\nROBOT_DART_ASSERT(body_index < _skeleton->getNumBodyNodes(), \"BodyNode index out of bounds\", );\nauto bd = _skeleton->getBodyNode(body_index);\nbd->setExtForce(force, offset, force_local, offset_local);\n}\nvoid Robot::add_external_force(const std::string& body_name, const Eigen::Vector3d& force, const Eigen::Vector3d& offset, bool force_local, bool offset_local)\n{\nauto bd = _skeleton->getBodyNode(body_name);\nROBOT_DART_ASSERT(bd != nullptr, \"BodyNode does not exist in skeleton!\", );\nbd->addExtForce(force, offset, force_local, offset_local);\n}\nvoid Robot::add_external_force(size_t body_index, const Eigen::Vector3d& force, const Eigen::Vector3d& offset, bool force_local, bool offset_local)\n{\nROBOT_DART_ASSERT(body_index < _skeleton->getNumBodyNodes(), \"BodyNode index out of bounds\", );\nauto bd = _skeleton->getBodyNode(body_index);\nbd->addExtForce(force, offset, force_local, offset_local);\n}\nvoid Robot::set_external_torque(const std::string& body_name, const Eigen::Vector3d& torque, bool local)\n{\nauto bd = _skeleton->getBodyNode(body_name);\nROBOT_DART_ASSERT(bd != nullptr, \"BodyNode does not exist in skeleton!\", );\nbd->setExtTorque(torque, local);\n}\nvoid Robot::set_external_torque(size_t body_index, const Eigen::Vector3d& torque, bool local)\n{\nROBOT_DART_ASSERT(body_index < _skeleton->getNumBodyNodes(), \"BodyNode index out of bounds\", );\nauto bd = _skeleton->getBodyNode(body_index);\nbd->setExtTorque(torque, local);\n}\nvoid Robot::add_external_torque(const std::string& body_name, const Eigen::Vector3d& torque, bool local)\n{\nauto bd = _skeleton->getBodyNode(body_name);\nROBOT_DART_ASSERT(bd != nullptr, \"BodyNode does not exist in skeleton!\", );\nbd->addExtTorque(torque, local);\n}\nvoid Robot::add_external_torque(size_t body_index, const Eigen::Vector3d& torque, bool local)\n{\nROBOT_DART_ASSERT(body_index < _skeleton->getNumBodyNodes(), \"BodyNode index out of bounds\", );\nauto bd = _skeleton->getBodyNode(body_index);\nbd->addExtTorque(torque, local);\n}\nEigen::Vector6d Robot::external_forces(const std::string& body_name) const\n{\nauto bd = _skeleton->getBodyNode(body_name);\nROBOT_DART_ASSERT(bd != nullptr, \"BodyNode does not exist in skeleton!\", Eigen::Vector6d::Zero());\nreturn bd->getExternalForceGlobal();\n}\nEigen::Vector6d Robot::external_forces(size_t body_index) const\n{\nROBOT_DART_ASSERT(body_index < _skeleton->getNumBodyNodes(), \"BodyNode index out of bounds\",\nEigen::Vector6d::Zero());\nauto bd = _skeleton->getBodyNode(body_index);\nreturn bd->getExternalForceGlobal();\n}\nEigen::Isometry3d Robot::body_pose(const std::string& body_name) const\n{\nauto bd = _skeleton->getBodyNode(body_name);\nROBOT_DART_ASSERT(bd != nullptr, \"BodyNode does not exist in skeleton!\", Eigen::Isometry3d::Identity());\nreturn bd->getWorldTransform();\n}\nEigen::Isometry3d Robot::body_pose(size_t body_index) const\n{\nROBOT_DART_ASSERT(body_index < _skeleton->getNumBodyNodes(), \"BodyNode index out of bounds\", Eigen::Isometry3d::Identity());\nreturn _skeleton->getBodyNode(body_index)->getWorldTransform();\n}\nEigen::Vector6d Robot::body_pose_vec(const std::string& body_name) const\n{\nauto bd = _skeleton->getBodyNode(body_name);\nROBOT_DART_ASSERT(bd != nullptr, \"BodyNode does not exist in skeleton!\", Eigen::Vector6d::Zero());\nEigen::Isometry3d tf = bd->getWorldTransform();\nEigen::Vector6d x;\nx.head<3>() = dart::math::logMap(tf.linear());\nx.tail<3>() = tf.translation();\nreturn x;\n}\nEigen::Vector6d Robot::body_pose_vec(size_t body_index) const\n{\nROBOT_DART_ASSERT(body_index < _skeleton->getNumBodyNodes(), \"BodyNode index out of bounds\", Eigen::Vector6d::Zero());\nEigen::Isometry3d tf = _skeleton->getBodyNode(body_index)->getWorldTransform();\nEigen::Vector6d x;\nx.head<3>() = dart::math::logMap(tf.linear());\nx.tail<3>() = tf.translation();\nreturn x;\n}\nEigen::Vector6d Robot::body_velocity(const std::string& body_name) const\n{\nauto bd = _skeleton->getBodyNode(body_name);\nROBOT_DART_ASSERT(bd != nullptr, \"BodyNode does not exist in skeleton!\", Eigen::Vector6d::Zero());\nreturn bd->getSpatialVelocity(dart::dynamics::Frame::World(), dart::dynamics::Frame::World());\n}\nEigen::Vector6d Robot::body_velocity(size_t body_index) const\n{\nROBOT_DART_ASSERT(body_index < _skeleton->getNumBodyNodes(), \"BodyNode index out of bounds\", Eigen::Vector6d::Zero());\nreturn _skeleton->getBodyNode(body_index)->getSpatialVelocity(dart::dynamics::Frame::World(), dart::dynamics::Frame::World());\n}\nEigen::Vector6d Robot::body_acceleration(const std::string& body_name) const\n{\nauto bd = _skeleton->getBodyNode(body_name);\nROBOT_DART_ASSERT(bd != nullptr, \"BodyNode does not exist in skeleton!\", Eigen::Vector6d::Zero());\nreturn bd->getSpatialAcceleration(dart::dynamics::Frame::World(), dart::dynamics::Frame::World());\n}\nEigen::Vector6d Robot::body_acceleration(size_t body_index) const\n{\nROBOT_DART_ASSERT(body_index < _skeleton->getNumBodyNodes(), \"BodyNode index out of bounds\", Eigen::Vector6d::Zero());\nreturn _skeleton->getBodyNode(body_index)->getSpatialAcceleration(dart::dynamics::Frame::World(), dart::dynamics::Frame::World());\n}\nstd::vector<std::string> Robot::body_names() const\n{\nstd::vector<std::string> names;\nfor (auto& bd : _skeleton->getBodyNodes())\nnames.push_back(bd->getName());\nreturn names;\n}\nstd::string Robot::body_name(size_t body_index) const\n{\nROBOT_DART_ASSERT(body_index < _skeleton->getNumBodyNodes(), \"BodyNode index out of bounds\", \"\");\nreturn _skeleton->getBodyNode(body_index)->getName();\n}\nvoid Robot::set_body_name(size_t body_index, const std::string& body_name)\n{\nROBOT_DART_ASSERT(body_index < _skeleton->getNumBodyNodes(), \"BodyNode index out of bounds\", );\n_skeleton->getBodyNode(body_index)->setName(body_name);\n}\nsize_t Robot::body_index(const std::string& body_name) const\n{\nauto bd = _skeleton->getBodyNode(body_name);\nROBOT_DART_ASSERT(bd, \"body_index : \" + body_name + \" is not in the skeleton\", 0);\nreturn bd->getIndexInSkeleton();\n}\ndouble Robot::body_mass(const std::string& body_name) const\n{\nauto bd = _skeleton->getBodyNode(body_name);\nROBOT_DART_ASSERT(bd != nullptr, \"BodyNode does not exist in skeleton!\", 0.);\nreturn bd->getMass();\n}\ndouble Robot::body_mass(size_t body_index) const\n{\nROBOT_DART_ASSERT(body_index < _skeleton->getNumBodyNodes(), \"BodyNode index out of bounds\", 0.);\nreturn _skeleton->getBodyNode(body_index)->getMass();\n}\nvoid Robot::set_body_mass(const std::string& body_name, double mass)\n{\nauto bd = _skeleton->getBodyNode(body_name);\nROBOT_DART_ASSERT(bd != nullptr, \"BodyNode does not exist in skeleton!\", );\nbd->setMass(mass); // TO-DO: Recompute inertia?\n}\nvoid Robot::set_body_mass(size_t body_index, double mass)\n{\nROBOT_DART_ASSERT(body_index < _skeleton->getNumBodyNodes(), \"BodyNode index out of bounds\", );\n_skeleton->getBodyNode(body_index)->setMass(mass); // TO-DO: Recompute inertia?\n}\nvoid Robot::add_body_mass(const std::string& body_name, double mass)\n{\nauto bd = _skeleton->getBodyNode(body_name);\nROBOT_DART_ASSERT(bd != nullptr, \"BodyNode does not exist in skeleton!\", );\nbd->setMass(mass + bd->getMass()); // TO-DO: Recompute inertia?\n}\nvoid Robot::add_body_mass(size_t body_index, double mass)\n{\nROBOT_DART_ASSERT(body_index < _skeleton->getNumBodyNodes(), \"BodyNode index out of bounds\", );\nauto bd = _skeleton->getBodyNode(body_index);\nbd->setMass(mass + bd->getMass()); // TO-DO: Recompute inertia?\n}\nEigen::MatrixXd Robot::jacobian(const std::string& body_name, const std::vector<std::string>& dof_names) const\n{\nauto bd = _skeleton->getBodyNode(body_name);\nROBOT_DART_ASSERT(bd != nullptr, \"BodyNode does not exist in skeleton!\", Eigen::MatrixXd());\nEigen::MatrixXd jac = _skeleton->getWorldJacobian(bd);\nreturn _jacobian(jac, dof_names);\n}\nEigen::MatrixXd Robot::jacobian_deriv(const std::string& body_name, const std::vector<std::string>& dof_names) const\n{\nauto bd = _skeleton->getBodyNode(body_name);\nROBOT_DART_ASSERT(bd != nullptr, \"BodyNode does not exist in skeleton!\", Eigen::MatrixXd());\nEigen::MatrixXd jac = _skeleton->getJacobianSpatialDeriv(bd, dart::dynamics::Frame::World());\nreturn _jacobian(jac, dof_names);\n}\nEigen::MatrixXd Robot::com_jacobian(const std::vector<std::string>& dof_names) const\n{\nEigen::MatrixXd jac = _skeleton->getCOMJacobian();\nreturn _jacobian(jac, dof_names);\n}\nEigen::MatrixXd Robot::com_jacobian_deriv(const std::vector<std::string>& dof_names) const\n{\nEigen::MatrixXd jac = _skeleton->getCOMJacobianSpatialDeriv();\nreturn _jacobian(jac, dof_names);\n}\nEigen::MatrixXd Robot::mass_matrix(const std::vector<std::string>& dof_names) const\n{\nEigen::MatrixXd M = _skeleton->getMassMatrix();\nreturn _mass_matrix(M, dof_names);\n}\nEigen::MatrixXd Robot::aug_mass_matrix(const std::vector<std::string>& dof_names) const\n{\nEigen::MatrixXd M = _skeleton->getAugMassMatrix();\nreturn _mass_matrix(M, dof_names);\n}\nEigen::MatrixXd Robot::inv_mass_matrix(const std::vector<std::string>& dof_names) const\n{\nEigen::MatrixXd M = _skeleton->getInvMassMatrix();\nreturn _mass_matrix(M, dof_names);\n}\nEigen::MatrixXd Robot::inv_aug_mass_matrix(const std::vector<std::string>& dof_names) const\n{\nEigen::MatrixXd M = _skeleton->getInvAugMassMatrix();\nreturn _mass_matrix(M, dof_names);\n}\nEigen::VectorXd Robot::coriolis_forces(const std::vector<std::string>& dof_names) const\n{\nreturn detail::dof_data<13>(_skeleton, dof_names, _dof_map);\n}\nEigen::VectorXd Robot::gravity_forces(const std::vector<std::string>& dof_names) const\n{\nreturn detail::dof_data<14>(_skeleton, dof_names, _dof_map);\n}\nEigen::VectorXd Robot::coriolis_gravity_forces(const std::vector<std::string>& dof_names) const\n{\nreturn detail::dof_data<15>(_skeleton, dof_names, _dof_map);\n}\nEigen::VectorXd Robot::constraint_forces(const std::vector<std::string>& dof_names) const\n{\nreturn detail::dof_data<16>(_skeleton, dof_names, _dof_map);\n}\nEigen::VectorXd Robot::vec_dof(const Eigen::VectorXd& vec, const std::vector<std::string>& dof_names) const\n{\nassert(vec.size() == static_cast<int>(_skeleton->getNumDofs()));\nEigen::VectorXd ret(dof_names.size());\nfor (size_t i = 0; i < dof_names.size(); i++) {\nauto it = _dof_map.find(dof_names[i]);\nROBOT_DART_ASSERT(it != _dof_map.end(), \"vec_dof: \" + dof_names[i] + \" is not in dof_map\", Eigen::VectorXd());\nret(i) = vec[it->second];\n}\nreturn ret;\n}\nvoid Robot::update_joint_dof_maps()\n{\n// DoFs\n_dof_map.clear();\nfor (size_t i = 0; i < _skeleton->getNumDofs(); ++i)\n_dof_map[_skeleton->getDof(i)->getName()] = i;\n// Joints\n_joint_map.clear();\nfor (size_t i = 0; i < _skeleton->getNumJoints(); ++i)\n_joint_map[_skeleton->getJoint(i)->getName()] = i;\n}\nconst std::unordered_map<std::string, size_t>& Robot::dof_map() const { return _dof_map; }\nconst std::unordered_map<std::string, size_t>& Robot::joint_map() const { return _joint_map; }\nstd::vector<std::string> Robot::dof_names(bool filter_mimics, bool filter_locked, bool filter_passive) const\n{\nstd::vector<std::string> names;\nfor (auto& dof : _skeleton->getDofs()) {\nauto jt = dof->getJoint();\nif ((!filter_mimics\n#if DART_VERSION_AT_LEAST(6, 7, 0)\n|| jt->getActuatorType() != dart::dynamics::Joint::MIMIC\n#else\n|| true\n#endif\n)\n&& (!filter_locked || jt->getActuatorType() != dart::dynamics::Joint::LOCKED)\n&& (!filter_passive || jt->getActuatorType() != dart::dynamics::Joint::PASSIVE))\nnames.push_back(dof->getName());\n}\nreturn names;\n}\nstd::vector<std::string> Robot::mimic_dof_names() const\n{\nstd::vector<std::string> names;\n#if DART_VERSION_AT_LEAST(6, 7, 0)\nfor (auto& dof : _skeleton->getDofs()) {\nauto jt = dof->getJoint();\nif (jt->getActuatorType() == dart::dynamics::Joint::MIMIC)\nnames.push_back(dof->getName());\n}\n#endif\nreturn names;\n}\nstd::vector<std::string> Robot::locked_dof_names() const\n{\nstd::vector<std::string> names;\nfor (auto& dof : _skeleton->getDofs()) {\nauto jt = dof->getJoint();\nif (jt->getActuatorType() == dart::dynamics::Joint::LOCKED)\nnames.push_back(dof->getName());\n}\nreturn names;\n}\nstd::vector<std::string> Robot::passive_dof_names() const\n{\nstd::vector<std::string> names;\nfor (auto& dof : _skeleton->getDofs()) {\nauto jt = dof->getJoint();\nif (jt->getActuatorType() == dart::dynamics::Joint::PASSIVE)\nnames.push_back(dof->getName());\n}\nreturn names;\n}\nstd::string Robot::dof_name(size_t dof_index) const\n{\nROBOT_DART_ASSERT(dof_index < _skeleton->getNumDofs(), \"Dof index out of bounds\", \"\");\nreturn _skeleton->getDof(dof_index)->getName();\n}\nsize_t Robot::dof_index(const std::string& dof_name) const\n{\nif (_dof_map.empty()) {\nROBOT_DART_WARNING(true,\n\"DoF map is empty. Iterating over all skeleton DoFs to get the index. Consider \"\n\"calling update_joint_dof_maps() before using dof_index()\");\nfor (size_t i = 0; i < _skeleton->getNumDofs(); i++)\nif (_skeleton->getDof(i)->getName() == dof_name)\nreturn i;\nROBOT_DART_ASSERT(false, \"dof_index : \" + dof_name + \" is not in the skeleton\", 0);\n}\nauto it = _dof_map.find(dof_name);\nROBOT_DART_ASSERT(it != _dof_map.end(), \"dof_index : \" + dof_name + \" is not in DoF map\", 0);\nreturn it->second;\n}\nstd::vector<std::string> Robot::joint_names() const\n{\nstd::vector<std::string> names;\nfor (auto& jt : _skeleton->getJoints())\nnames.push_back(jt->getName());\nreturn names;\n}\nstd::string Robot::joint_name(size_t joint_index) const\n{\nROBOT_DART_ASSERT(joint_index < _skeleton->getNumJoints(), \"Joint index out of bounds\", \"\");\nreturn _skeleton->getJoint(joint_index)->getName();\n}\nvoid Robot::set_joint_name(size_t joint_index, const std::string& joint_name)\n{\nROBOT_DART_ASSERT(joint_index < _skeleton->getNumJoints(), \"Joint index out of bounds\", );\n_skeleton->getJoint(joint_index)->setName(joint_name);\nupdate_joint_dof_maps();\n}\nsize_t Robot::joint_index(const std::string& joint_name) const\n{\nif (_joint_map.empty()) {\nROBOT_DART_WARNING(true,\n\"Joint map is empty. Iterating over all skeleton joints to get the index. \"\n\"Consider calling update_joint_dof_maps() before using joint_index()\");\nfor (size_t i = 0; i < _skeleton->getNumJoints(); i++)\nif (_skeleton->getJoint(i)->getName() == joint_name)\nreturn i;\nROBOT_DART_ASSERT(false, \"joint_index : \" + joint_name + \" is not in the skeleton\", 0);\n}\nauto it = _joint_map.find(joint_name);\nROBOT_DART_ASSERT(it != _joint_map.end(), \"joint_index : \" + joint_name + \" is not in Joint map\", 0);\nreturn it->second;\n}\nvoid Robot::set_color_mode(const std::string& color_mode)\n{\nif (color_mode == \"material\")\n_set_color_mode(dart::dynamics::MeshShape::ColorMode::MATERIAL_COLOR, _skeleton);\nelse if (color_mode == \"assimp\")\n_set_color_mode(dart::dynamics::MeshShape::ColorMode::COLOR_INDEX, _skeleton);\nelse if (color_mode == \"aspect\")\n_set_color_mode(dart::dynamics::MeshShape::ColorMode::SHAPE_COLOR, _skeleton);\nelse\nROBOT_DART_EXCEPTION_ASSERT(false, \"Unknown color mode. Valid values: material, assimp and aspect.\");\n}\nvoid Robot::set_color_mode(const std::string& color_mode, const std::string& body_name)\n{\ndart::dynamics::MeshShape::ColorMode cmode;\nif (color_mode == \"material\")\ncmode = dart::dynamics::MeshShape::ColorMode::MATERIAL_COLOR;\nelse if (color_mode == \"assimp\")\ncmode = dart::dynamics::MeshShape::ColorMode::COLOR_INDEX;\nelse if (color_mode == \"aspect\")\ncmode = dart::dynamics::MeshShape::ColorMode::SHAPE_COLOR;\nelse\nROBOT_DART_EXCEPTION_ASSERT(false, \"Unknown color mode. Valid values: material, assimp and aspect.\");\nauto bn = _skeleton->getBodyNode(body_name);\nif (bn) {\nfor (size_t j = 0; j < bn->getNumShapeNodes(); ++j) {\ndart::dynamics::ShapeNode* sn = bn->getShapeNode(j);\n_set_color_mode(cmode, sn);\n}\n}\n}\nvoid Robot::set_self_collision(bool enable_self_collisions, bool enable_adjacent_collisions)\n{\n_skeleton->setSelfCollisionCheck(enable_self_collisions);\n_skeleton->setAdjacentBodyCheck(enable_adjacent_collisions);\n}\nbool Robot::self_colliding() const\n{\nreturn _skeleton->getSelfCollisionCheck();\n}\nbool Robot::adjacent_colliding() const\n{\nreturn _skeleton->getAdjacentBodyCheck() && self_colliding();\n}\nvoid Robot::set_cast_shadows(bool cast_shadows) { _cast_shadows = cast_shadows; }\nbool Robot::cast_shadows() const { return _cast_shadows; }\nvoid Robot::set_ghost(bool ghost) { _is_ghost = ghost; }\nbool Robot::ghost() const { return _is_ghost; }\nvoid Robot::set_draw_axis(const std::string& body_name, double size)\n{\nauto bd = _skeleton->getBodyNode(body_name);\nROBOT_DART_ASSERT(bd, \"Body name does not exist in skeleton\", );\nstd::pair<dart::dynamics::BodyNode*, double> p = {bd, size};\nauto iter = std::find(_axis_shapes.begin(), _axis_shapes.end(), p);\nif (iter == _axis_shapes.end())\n_axis_shapes.push_back(p);\n}\nvoid Robot::remove_all_drawing_axis()\n{\n_axis_shapes.clear();\n}\nconst std::vector<std::pair<dart::dynamics::BodyNode*, double>>& Robot::drawing_axes() const { return _axis_shapes; }\ndart::dynamics::SkeletonPtr Robot::_load_model(const std::string& filename, const std::vector<std::pair<std::string, std::string>>& packages, bool is_urdf_string)\n{\nROBOT_DART_EXCEPTION_ASSERT(!filename.empty(), \"Empty URDF filename\");\ndart::dynamics::SkeletonPtr tmp_skel;\nif (!is_urdf_string) {\n// search for the right directory for our files\nstd::string model_file = utheque::path(filename, false, std::string(ROBOT_DART_PREFIX));\n// store the name for future use\n_model_filename = model_file;\n_packages = packages;\n// std::cout << \"RobotDART:: using: \" << model_file << std::endl;\nfs::path path(model_file);\nstd::string extension = path.extension().string();\nif (extension == \".urdf\") {\n#if DART_VERSION_AT_LEAST(6, 12, 0)\ndart::io::DartLoader::Options options;\n// if links have no inertia, we put ~zero mass and very very small inertia\noptions.mDefaultInertia = dart::dynamics::Inertia(1e-10, Eigen::Vector3d::Zero(), Eigen::Matrix3d::Identity() * 1e-6);\ndart::io::DartLoader loader(options);\n#else\ndart::io::DartLoader loader;\n#endif\nfor (size_t i = 0; i < packages.size(); i++) {\nstd::string package = std::get<1>(packages[i]);\nstd::string package_path = utheque::directory(package, false, std::string(ROBOT_DART_PREFIX));\nloader.addPackageDirectory(\nstd::get<0>(packages[i]), package_path + \"/\" + package);\n}\ntmp_skel = loader.parseSkeleton(model_file);\n}\nelse if (extension == \".sdf\")\ntmp_skel = dart::io::SdfParser::readSkeleton(model_file);\nelse if (extension == \".skel\") {\ntmp_skel = dart::io::SkelParser::readSkeleton(model_file);\n// if the skel file contains a world\n// try to read the skeleton with name 'robot_name'\nif (!tmp_skel) {\ndart::simulation::WorldPtr world = dart::io::SkelParser::readWorld(model_file);\ntmp_skel = world->getSkeleton(_robot_name);\n}\n}\nelse\nreturn nullptr;\n}\nelse {\n// Load from URDF string\ndart::io::DartLoader loader;\nfor (size_t i = 0; i < packages.size(); i++) {\nstd::string package = std::get<1>(packages[i]);\nstd::string package_path = utheque::directory(package, false, std::string(ROBOT_DART_PREFIX));\nloader.addPackageDirectory(std::get<0>(packages[i]), package_path + \"/\" + package);\n}\ntmp_skel = loader.parseSkeletonString(filename, \"\");\n}\nif (tmp_skel == nullptr)\nreturn nullptr;\ntmp_skel->setName(_robot_name);\n// Set joint limits\nfor (size_t i = 0; i < tmp_skel->getNumJoints(); ++i) {\n#if DART_VERSION_AT_LEAST(6, 10, 0)\ntmp_skel->getJoint(i)->setLimitEnforcement(true);\n#else\ntmp_skel->getJoint(i)->setPositionLimitEnforced(true);\n#endif\n}\n_set_color_mode(dart::dynamics::MeshShape::ColorMode::SHAPE_COLOR, tmp_skel);\nreturn tmp_skel;\n}\nvoid Robot::_set_color_mode(dart::dynamics::MeshShape::ColorMode color_mode, dart::dynamics::SkeletonPtr skel)\n{\nfor (size_t i = 0; i < skel->getNumBodyNodes(); ++i) {\ndart::dynamics::BodyNode* bn = skel->getBodyNode(i);\nfor (size_t j = 0; j < bn->getNumShapeNodes(); ++j) {\ndart::dynamics::ShapeNode* sn = bn->getShapeNode(j);\n_set_color_mode(color_mode, sn);\n}\n}\n}\nvoid Robot::_set_color_mode(dart::dynamics::MeshShape::ColorMode color_mode, dart::dynamics::ShapeNode* sn)\n{\nif (sn->getVisualAspect()) {\ndart::dynamics::MeshShape* ms\n= dynamic_cast<dart::dynamics::MeshShape*>(sn->getShape().get());\nif (ms)\nms->setColorMode(color_mode);\n}\n}\nvoid Robot::_set_actuator_type(size_t joint_index, dart::dynamics::Joint::ActuatorType type, bool override_mimic, bool override_base)\n{\nROBOT_DART_ASSERT(joint_index < _skeleton->getNumJoints(), \"joint_index index out of bounds\", );\nauto jt = _skeleton->getJoint(joint_index);\n// Do not override 6D base if robot is free and override_base is false\nif (free() && (!override_base && _skeleton->getRootJoint() == jt))\nreturn;\n#if DART_VERSION_AT_LEAST(6, 7, 0)\nif (override_mimic || jt->getActuatorType() != dart::dynamics::Joint::MIMIC)\n#endif\njt->setActuatorType(type);\n}\nvoid Robot::_set_actuator_types(const std::vector<dart::dynamics::Joint::ActuatorType>& types, bool override_mimic, bool override_base)\n{\nROBOT_DART_ASSERT(types.size() == _skeleton->getNumJoints(), \"Actuator types vector size is not the same as the joints of the robot\", );\n// Ignore first root joint if robot is free, and override_base is false\nbool ignore_base = free() && !override_base;\nauto root_jt = _skeleton->getRootJoint();\nfor (size_t i = 0; i < _skeleton->getNumJoints(); ++i) {\nauto jt = _skeleton->getJoint(i);\nif (jt->getNumDofs() == 0 || (ignore_base && jt == root_jt))\ncontinue;\n#if DART_VERSION_AT_LEAST(6, 7, 0)\nif (override_mimic || jt->getActuatorType() != dart::dynamics::Joint::MIMIC)\n#endif\njt->setActuatorType(types[i]);\n}\n}\nvoid Robot::_set_actuator_types(dart::dynamics::Joint::ActuatorType type, bool override_mimic, bool override_base)\n{\n// Ignore first root joint if robot is free, and override_base is false\nbool ignore_base = free() && !override_base;\nauto root_jt = _skeleton->getRootJoint();\nfor (size_t i = 0; i < _skeleton->getNumJoints(); ++i) {\nauto jt = _skeleton->getJoint(i);\nif (jt->getNumDofs() == 0 || (ignore_base && jt == root_jt))\ncontinue;\n#if DART_VERSION_AT_LEAST(6, 7, 0)\nif (override_mimic || jt->getActuatorType() != dart::dynamics::Joint::MIMIC)\n#endif\njt->setActuatorType(type);\n}\n}\ndart::dynamics::Joint::ActuatorType Robot::_actuator_type(size_t joint_index) const\n{\nROBOT_DART_ASSERT(joint_index < _skeleton->getNumJoints(), \"joint_index out of bounds\", dart::dynamics::Joint::ActuatorType::FORCE);\nreturn _skeleton->getJoint(joint_index)->getActuatorType();\n}\nstd::vector<dart::dynamics::Joint::ActuatorType> Robot::_actuator_types() const\n{\nstd::vector<dart::dynamics::Joint::ActuatorType> types;\nfor (size_t i = 0; i < _skeleton->getNumJoints(); ++i) {\ntypes.push_back(_skeleton->getJoint(i)->getActuatorType());\n}\nreturn types;\n}\nEigen::MatrixXd Robot::_jacobian(const Eigen::MatrixXd& full_jacobian, const std::vector<std::string>& dof_names) const\n{\nif (dof_names.empty())\nreturn full_jacobian;\nEigen::MatrixXd jac_ret(6, dof_names.size());\nfor (size_t i = 0; i < dof_names.size(); i++) {\nauto it = _dof_map.find(dof_names[i]);\nROBOT_DART_ASSERT(it != _dof_map.end(), \"_jacobian: \" + dof_names[i] + \" is not in dof_map\", Eigen::MatrixXd());\njac_ret.col(i) = full_jacobian.col(it->second);\n}\nreturn jac_ret;\n}\nEigen::MatrixXd Robot::_mass_matrix(const Eigen::MatrixXd& full_mass_matrix, const std::vector<std::string>& dof_names) const\n{\nif (dof_names.empty())\nreturn full_mass_matrix;\nEigen::MatrixXd M_ret(dof_names.size(), dof_names.size());\nfor (size_t i = 0; i < dof_names.size(); i++) {\nauto it = _dof_map.find(dof_names[i]);\nROBOT_DART_ASSERT(it != _dof_map.end(), \"mass_matrix: \" + dof_names[i] + \" is not in dof_map\", Eigen::MatrixXd());\nM_ret(i, i) = full_mass_matrix(it->second, it->second);\nfor (size_t j = i + 1; j < dof_names.size(); j++) {\nauto it2 = _dof_map.find(dof_names[j]);\nROBOT_DART_ASSERT(it2 != _dof_map.end(), \"mass_matrix: \" + dof_names[j] + \" is not in dof_map\", Eigen::MatrixXd());\nM_ret(i, j) = full_mass_matrix(it->second, it2->second);\nM_ret(j, i) = full_mass_matrix(it2->second, it->second);\n}\n}\nreturn M_ret;\n}\nstd::shared_ptr<Robot> Robot::create_box(const Eigen::Vector3d& dims, const Eigen::Isometry3d& tf, const std::string& type, double mass, const Eigen::Vector4d& color, const std::string& box_name)\n{\nEigen::Vector6d x;\nx.head<3>() = dart::math::logMap(tf.linear());\nx.tail<3>() = tf.translation();\nreturn create_box(dims, x, type, mass, color, box_name);\n}\nstd::shared_ptr<Robot> Robot::create_box(const Eigen::Vector3d& dims, const Eigen::Vector6d& pose, const std::string& type, double mass, const Eigen::Vector4d& color, const std::string& box_name)\n{\nROBOT_DART_ASSERT((dims.array() > 0.).all(), \"Dimensions should be bigger than zero!\", nullptr);\nROBOT_DART_ASSERT(mass > 0., \"Box mass should be bigger than zero!\", nullptr);\ndart::dynamics::SkeletonPtr box_skel = dart::dynamics::Skeleton::create(box_name);\n// Give the box a body\ndart::dynamics::BodyNodePtr body;\nif (type == \"free\")\nbody = box_skel->createJointAndBodyNodePair<dart::dynamics::FreeJoint>(nullptr).second;\nelse\nbody = box_skel->createJointAndBodyNodePair<dart::dynamics::WeldJoint>(nullptr).second;\nbody->setName(box_name);\n// Give the body a shape\nauto box = std::make_shared<dart::dynamics::BoxShape>(dims);\nauto box_node = body->createShapeNodeWith<dart::dynamics::VisualAspect,\ndart::dynamics::CollisionAspect, dart::dynamics::DynamicsAspect>(box);\nbox_node->getVisualAspect()->setColor(color);\n// Set up inertia\ndart::dynamics::Inertia inertia;\ninertia.setMass(mass);\ninertia.setMoment(box->computeInertia(mass));\nbody->setInertia(inertia);\n// Put the body into position\nauto robot = std::make_shared<Robot>(box_skel, box_name);\nif (type == \"free\") // free floating\nrobot->set_positions(pose);\nelse // fixed\n{\nEigen::Isometry3d T;\nT.linear() = dart::math::expMapRot(pose.head<3>());\nT.translation() = pose.tail<3>();\nbody->getParentJoint()->setTransformFromParentBodyNode(T);\n}\nreturn robot;\n}\nstd::shared_ptr<Robot> Robot::create_ellipsoid(const Eigen::Vector3d& dims, const Eigen::Isometry3d& tf, const std::string& type, double mass, const Eigen::Vector4d& color, const std::string& ellipsoid_name)\n{\nEigen::Vector6d x;\nx.head<3>() = dart::math::logMap(tf.linear());\nx.tail<3>() = tf.translation();\nreturn create_ellipsoid(dims, x, type, mass, color, ellipsoid_name);\n}\nstd::shared_ptr<Robot> Robot::create_ellipsoid(const Eigen::Vector3d& dims, const Eigen::Vector6d& pose, const std::string& type, double mass, const Eigen::Vector4d& color, const std::string& ellipsoid_name)\n{\nROBOT_DART_ASSERT((dims.array() > 0.).all(), \"Dimensions should be bigger than zero!\", nullptr);\nROBOT_DART_ASSERT(mass > 0., \"Box mass should be bigger than zero!\", nullptr);\ndart::dynamics::SkeletonPtr ellipsoid_skel = dart::dynamics::Skeleton::create(ellipsoid_name);\n// Give the ellipsoid a body\ndart::dynamics::BodyNodePtr body;\nif (type == \"free\")\nbody = ellipsoid_skel->createJointAndBodyNodePair<dart::dynamics::FreeJoint>(nullptr).second;\nelse\nbody = ellipsoid_skel->createJointAndBodyNodePair<dart::dynamics::WeldJoint>(nullptr).second;\nbody->setName(ellipsoid_name);\n// Give the body a shape\nauto ellipsoid = std::make_shared<dart::dynamics::EllipsoidShape>(dims);\nauto ellipsoid_node = body->createShapeNodeWith<dart::dynamics::VisualAspect,\ndart::dynamics::CollisionAspect, dart::dynamics::DynamicsAspect>(ellipsoid);\nellipsoid_node->getVisualAspect()->setColor(color);\n// Set up inertia\ndart::dynamics::Inertia inertia;\ninertia.setMass(mass);\ninertia.setMoment(ellipsoid->computeInertia(mass));\nbody->setInertia(inertia);\nauto robot = std::make_shared<Robot>(ellipsoid_skel, ellipsoid_name);\n// Put the body into position\nif (type == \"free\") // free floating\nrobot->set_positions(pose);\nelse // fixed\n{\nEigen::Isometry3d T;\nT.linear() = dart::math::expMapRot(pose.head<3>());\nT.translation() = pose.tail<3>();\nbody->getParentJoint()->setTransformFromParentBodyNode(T);\n}\nreturn robot;\n}\n} // namespace robot_dart\n
"},{"location":"api/robot_8hpp/","title":"File robot.hpp","text":"

FileList > robot_dart > robot.hpp

Go to the source code of this file

"},{"location":"api/robot_8hpp/#namespaces","title":"Namespaces","text":"Type Name namespace robot_dart namespace control"},{"location":"api/robot_8hpp/#classes","title":"Classes","text":"Type Name class Robot

The documentation for this class was generated from the following file robot_dart/robot.hpp

"},{"location":"api/robot_8hpp_source/","title":"File robot.hpp","text":"

File List > robot_dart > robot.hpp

Go to the documentation of this file

#ifndef ROBOT_DART_ROBOT_HPP\n#define ROBOT_DART_ROBOT_HPP\n#include <unordered_map>\n#include <robot_dart/utils.hpp>\nnamespace robot_dart {\nclass RobotDARTSimu;\nnamespace control {\nclass RobotControl;\n}\nclass Robot : public std::enable_shared_from_this<Robot> {\npublic:\nRobot(const std::string& model_file, const std::vector<std::pair<std::string, std::string>>& packages, const std::string& robot_name = \"robot\", bool is_urdf_string = false, bool cast_shadows = true);\nRobot(const std::string& model_file, const std::string& robot_name = \"robot\", bool is_urdf_string = false, bool cast_shadows = true);\nRobot(dart::dynamics::SkeletonPtr skeleton, const std::string& robot_name = \"robot\", bool cast_shadows = true);\nvirtual ~Robot() {}\nstd::shared_ptr<Robot> clone() const;\nstd::shared_ptr<Robot> clone_ghost(const std::string& ghost_name = \"ghost\", const Eigen::Vector4d& ghost_color = {0.3, 0.3, 0.3, 0.7}) const;\ndart::dynamics::SkeletonPtr skeleton();\ndart::dynamics::BodyNode* body_node(const std::string& body_name);\ndart::dynamics::BodyNode* body_node(size_t body_index);\ndart::dynamics::Joint* joint(const std::string& joint_name);\ndart::dynamics::Joint* joint(size_t joint_index);\ndart::dynamics::DegreeOfFreedom* dof(const std::string& dof_name);\ndart::dynamics::DegreeOfFreedom* dof(size_t dof_index);\nconst std::string& name() const;\n// to use the same urdf somewhere else\nconst std::string& model_filename() const { return _model_filename; }\nconst std::vector<std::pair<std::string, std::string>>& model_packages() const { return _packages; }\nvoid update(double t);\nvoid reinit_controllers();\nsize_t num_controllers() const;\nstd::vector<std::shared_ptr<control::RobotControl>> controllers() const;\nstd::vector<std::shared_ptr<control::RobotControl>> active_controllers() const;\nstd::shared_ptr<control::RobotControl> controller(size_t index) const;\nvoid add_controller(\nconst std::shared_ptr<control::RobotControl>& controller, double weight = 1.0);\nvoid remove_controller(const std::shared_ptr<control::RobotControl>& controller);\nvoid remove_controller(size_t index);\nvoid clear_controllers();\nvoid fix_to_world();\n// pose: Orientation-Position\nvoid free_from_world(const Eigen::Vector6d& pose = Eigen::Vector6d::Zero());\nbool fixed() const;\nbool free() const;\nvirtual void reset();\nvoid clear_external_forces();\nvoid clear_internal_forces();\nvoid reset_commands();\n// actuator type can be: torque, servo, velocity, passive, locked, mimic (only for completeness, use set_mimic to use this)\n// Be careful that actuator types are per joint and not per DoF\nvoid set_actuator_types(const std::string& type, const std::vector<std::string>& joint_names = {}, bool override_mimic = false, bool override_base = false);\nvoid set_actuator_type(const std::string& type, const std::string& joint_name, bool override_mimic = false, bool override_base = false);\nvoid set_mimic(const std::string& joint_name, const std::string& mimic_joint_name, double multiplier = 1., double offset = 0.);\nstd::string actuator_type(const std::string& joint_name) const;\nstd::vector<std::string> actuator_types(const std::vector<std::string>& joint_names = {}) const;\nvoid set_position_enforced(const std::vector<bool>& enforced, const std::vector<std::string>& dof_names = {});\nvoid set_position_enforced(bool enforced, const std::vector<std::string>& dof_names = {});\nstd::vector<bool> position_enforced(const std::vector<std::string>& dof_names = {}) const;\nvoid force_position_bounds();\nvoid set_damping_coeffs(const std::vector<double>& damps, const std::vector<std::string>& dof_names = {});\nvoid set_damping_coeffs(double damp, const std::vector<std::string>& dof_names = {});\nstd::vector<double> damping_coeffs(const std::vector<std::string>& dof_names = {}) const;\nvoid set_coulomb_coeffs(const std::vector<double>& cfrictions, const std::vector<std::string>& dof_names = {});\nvoid set_coulomb_coeffs(double cfriction, const std::vector<std::string>& dof_names = {});\nstd::vector<double> coulomb_coeffs(const std::vector<std::string>& dof_names = {}) const;\nvoid set_spring_stiffnesses(const std::vector<double>& stiffnesses, const std::vector<std::string>& dof_names = {});\nvoid set_spring_stiffnesses(double stiffness, const std::vector<std::string>& dof_names = {});\nstd::vector<double> spring_stiffnesses(const std::vector<std::string>& dof_names = {}) const;\n// the friction direction is in local frame\nvoid set_friction_dir(const std::string& body_name, const Eigen::Vector3d& direction);\nvoid set_friction_dir(size_t body_index, const Eigen::Vector3d& direction);\nEigen::Vector3d friction_dir(const std::string& body_name);\nEigen::Vector3d friction_dir(size_t body_index);\nvoid set_friction_coeff(const std::string& body_name, double value);\nvoid set_friction_coeff(size_t body_index, double value);\nvoid set_friction_coeffs(double value);\ndouble friction_coeff(const std::string& body_name);\ndouble friction_coeff(size_t body_index);\nvoid set_secondary_friction_coeff(const std::string& body_name, double value);\nvoid set_secondary_friction_coeff(size_t body_index, double value);\nvoid set_secondary_friction_coeffs(double value);\ndouble secondary_friction_coeff(const std::string& body_name);\ndouble secondary_friction_coeff(size_t body_index);\nvoid set_restitution_coeff(const std::string& body_name, double value);\nvoid set_restitution_coeff(size_t body_index, double value);\nvoid set_restitution_coeffs(double value);\ndouble restitution_coeff(const std::string& body_name);\ndouble restitution_coeff(size_t body_index);\nEigen::Isometry3d base_pose() const;\nEigen::Vector6d base_pose_vec() const;\nvoid set_base_pose(const Eigen::Isometry3d& tf);\nvoid set_base_pose(const Eigen::Vector6d& pose);\nsize_t num_dofs() const;\nsize_t num_joints() const;\nsize_t num_bodies() const;\nEigen::Vector3d com() const;\nEigen::Vector6d com_velocity() const;\nEigen::Vector6d com_acceleration() const;\nEigen::VectorXd positions(const std::vector<std::string>& dof_names = {}) const;\nvoid set_positions(const Eigen::VectorXd& positions, const std::vector<std::string>& dof_names = {});\nEigen::VectorXd position_lower_limits(const std::vector<std::string>& dof_names = {}) const;\nvoid set_position_lower_limits(const Eigen::VectorXd& positions, const std::vector<std::string>& dof_names = {});\nEigen::VectorXd position_upper_limits(const std::vector<std::string>& dof_names = {}) const;\nvoid set_position_upper_limits(const Eigen::VectorXd& positions, const std::vector<std::string>& dof_names = {});\nEigen::VectorXd velocities(const std::vector<std::string>& dof_names = {}) const;\nvoid set_velocities(const Eigen::VectorXd& velocities, const std::vector<std::string>& dof_names = {});\nEigen::VectorXd velocity_lower_limits(const std::vector<std::string>& dof_names = {}) const;\nvoid set_velocity_lower_limits(const Eigen::VectorXd& velocities, const std::vector<std::string>& dof_names = {});\nEigen::VectorXd velocity_upper_limits(const std::vector<std::string>& dof_names = {}) const;\nvoid set_velocity_upper_limits(const Eigen::VectorXd& velocities, const std::vector<std::string>& dof_names = {});\nEigen::VectorXd accelerations(const std::vector<std::string>& dof_names = {}) const;\nvoid set_accelerations(const Eigen::VectorXd& accelerations, const std::vector<std::string>& dof_names = {});\nEigen::VectorXd acceleration_lower_limits(const std::vector<std::string>& dof_names = {}) const;\nvoid set_acceleration_lower_limits(const Eigen::VectorXd& accelerations, const std::vector<std::string>& dof_names = {});\nEigen::VectorXd acceleration_upper_limits(const std::vector<std::string>& dof_names = {}) const;\nvoid set_acceleration_upper_limits(const Eigen::VectorXd& accelerations, const std::vector<std::string>& dof_names = {});\nEigen::VectorXd forces(const std::vector<std::string>& dof_names = {}) const;\nvoid set_forces(const Eigen::VectorXd& forces, const std::vector<std::string>& dof_names = {});\nEigen::VectorXd force_lower_limits(const std::vector<std::string>& dof_names = {}) const;\nvoid set_force_lower_limits(const Eigen::VectorXd& forces, const std::vector<std::string>& dof_names = {});\nEigen::VectorXd force_upper_limits(const std::vector<std::string>& dof_names = {}) const;\nvoid set_force_upper_limits(const Eigen::VectorXd& forces, const std::vector<std::string>& dof_names = {});\nEigen::VectorXd commands(const std::vector<std::string>& dof_names = {}) const;\nvoid set_commands(const Eigen::VectorXd& commands, const std::vector<std::string>& dof_names = {});\nstd::pair<Eigen::Vector6d, Eigen::Vector6d> force_torque(size_t joint_index) const;\nvoid set_external_force(const std::string& body_name, const Eigen::Vector3d& force, const Eigen::Vector3d& offset = Eigen::Vector3d::Zero(), bool force_local = false, bool offset_local = true);\nvoid set_external_force(size_t body_index, const Eigen::Vector3d& force, const Eigen::Vector3d& offset = Eigen::Vector3d::Zero(), bool force_local = false, bool offset_local = true);\nvoid add_external_force(const std::string& body_name, const Eigen::Vector3d& force, const Eigen::Vector3d& offset = Eigen::Vector3d::Zero(), bool force_local = false, bool offset_local = true);\nvoid add_external_force(size_t body_index, const Eigen::Vector3d& force, const Eigen::Vector3d& offset = Eigen::Vector3d::Zero(), bool force_local = false, bool offset_local = true);\nvoid set_external_torque(const std::string& body_name, const Eigen::Vector3d& torque, bool local = false);\nvoid set_external_torque(size_t body_index, const Eigen::Vector3d& torque, bool local = false);\nvoid add_external_torque(const std::string& body_name, const Eigen::Vector3d& torque, bool local = false);\nvoid add_external_torque(size_t body_index, const Eigen::Vector3d& torque, bool local = false);\nEigen::Vector6d external_forces(const std::string& body_name) const;\nEigen::Vector6d external_forces(size_t body_index) const;\nEigen::Isometry3d body_pose(const std::string& body_name) const;\nEigen::Isometry3d body_pose(size_t body_index) const;\nEigen::Vector6d body_pose_vec(const std::string& body_name) const;\nEigen::Vector6d body_pose_vec(size_t body_index) const;\nEigen::Vector6d body_velocity(const std::string& body_name) const;\nEigen::Vector6d body_velocity(size_t body_index) const;\nEigen::Vector6d body_acceleration(const std::string& body_name) const;\nEigen::Vector6d body_acceleration(size_t body_index) const;\nstd::vector<std::string> body_names() const;\nstd::string body_name(size_t body_index) const;\nvoid set_body_name(size_t body_index, const std::string& body_name);\nsize_t body_index(const std::string& body_name) const;\ndouble body_mass(const std::string& body_name) const;\ndouble body_mass(size_t body_index) const;\nvoid set_body_mass(const std::string& body_name, double mass);\nvoid set_body_mass(size_t body_index, double mass);\nvoid add_body_mass(const std::string& body_name, double mass);\nvoid add_body_mass(size_t body_index, double mass);\nEigen::MatrixXd jacobian(const std::string& body_name, const std::vector<std::string>& dof_names = {}) const;\nEigen::MatrixXd jacobian_deriv(const std::string& body_name, const std::vector<std::string>& dof_names = {}) const;\nEigen::MatrixXd com_jacobian(const std::vector<std::string>& dof_names = {}) const;\nEigen::MatrixXd com_jacobian_deriv(const std::vector<std::string>& dof_names = {}) const;\nEigen::MatrixXd mass_matrix(const std::vector<std::string>& dof_names = {}) const;\nEigen::MatrixXd aug_mass_matrix(const std::vector<std::string>& dof_names = {}) const;\nEigen::MatrixXd inv_mass_matrix(const std::vector<std::string>& dof_names = {}) const;\nEigen::MatrixXd inv_aug_mass_matrix(const std::vector<std::string>& dof_names = {}) const;\nEigen::VectorXd coriolis_forces(const std::vector<std::string>& dof_names = {}) const;\nEigen::VectorXd gravity_forces(const std::vector<std::string>& dof_names = {}) const;\nEigen::VectorXd coriolis_gravity_forces(const std::vector<std::string>& dof_names = {}) const;\nEigen::VectorXd constraint_forces(const std::vector<std::string>& dof_names = {}) const;\n// Get only the part of vector for DOFs in dof_names\nEigen::VectorXd vec_dof(const Eigen::VectorXd& vec, const std::vector<std::string>& dof_names) const;\nvoid update_joint_dof_maps();\nconst std::unordered_map<std::string, size_t>& dof_map() const;\nconst std::unordered_map<std::string, size_t>& joint_map() const;\nstd::vector<std::string> dof_names(bool filter_mimics = false, bool filter_locked = false, bool filter_passive = false) const;\nstd::vector<std::string> mimic_dof_names() const;\nstd::vector<std::string> locked_dof_names() const;\nstd::vector<std::string> passive_dof_names() const;\nstd::string dof_name(size_t dof_index) const;\nsize_t dof_index(const std::string& dof_name) const;\nstd::vector<std::string> joint_names() const;\nstd::string joint_name(size_t joint_index) const;\nvoid set_joint_name(size_t joint_index, const std::string& joint_name);\nsize_t joint_index(const std::string& joint_name) const;\n// MATERIAL_COLOR, COLOR_INDEX, SHAPE_COLOR\n// This applies only to MeshShapes. Color mode can be: \"material\", \"assimp\", or \"aspect\"\n// \"material\" -> uses the color of the material in the mesh file\n// \"assimp\" -> uses the color specified by aiMesh::mColor\n// \"aspect\" -> uses the color defined in the VisualAspect (if not changed, this is what read from the URDF)\nvoid set_color_mode(const std::string& color_mode);\nvoid set_color_mode(const std::string& color_mode, const std::string& body_name);\nvoid set_self_collision(bool enable_self_collisions = true, bool enable_adjacent_collisions = false);\nbool self_colliding() const;\n// This returns true if self colliding AND adjacent checks are on\nbool adjacent_colliding() const;\n// GUI options\nvoid set_cast_shadows(bool cast_shadows = true);\nbool cast_shadows() const;\nvoid set_ghost(bool ghost = true);\nbool ghost() const;\nvoid set_draw_axis(const std::string& body_name, double size = 0.25);\nvoid remove_all_drawing_axis();\nconst std::vector<std::pair<dart::dynamics::BodyNode*, double>>& drawing_axes() const;\n// helper functions\nstatic std::shared_ptr<Robot> create_box(const Eigen::Vector3d& dims,\nconst Eigen::Isometry3d& tf, const std::string& type = \"free\",\ndouble mass = 1.0, const Eigen::Vector4d& color = dart::Color::Red(1.0),\nconst std::string& box_name = \"box\");\n// pose: 6D log_map\nstatic std::shared_ptr<Robot> create_box(const Eigen::Vector3d& dims,\nconst Eigen::Vector6d& pose = Eigen::Vector6d::Zero(), const std::string& type = \"free\",\ndouble mass = 1.0, const Eigen::Vector4d& color = dart::Color::Red(1.0),\nconst std::string& box_name = \"box\");\nstatic std::shared_ptr<Robot> create_ellipsoid(const Eigen::Vector3d& dims,\nconst Eigen::Isometry3d& tf, const std::string& type = \"free\",\ndouble mass = 1.0, const Eigen::Vector4d& color = dart::Color::Red(1.0),\nconst std::string& ellipsoid_name = \"ellipsoid\");\n// pose: 6D log_map\nstatic std::shared_ptr<Robot> create_ellipsoid(const Eigen::Vector3d& dims,\nconst Eigen::Vector6d& pose = Eigen::Vector6d::Zero(), const std::string& type = \"free\",\ndouble mass = 1.0, const Eigen::Vector4d& color = dart::Color::Red(1.0),\nconst std::string& ellipsoid_name = \"ellipsoid\");\nprotected:\nstd::string _get_path(const std::string& filename) const;\ndart::dynamics::SkeletonPtr _load_model(const std::string& filename, const std::vector<std::pair<std::string, std::string>>& packages = std::vector<std::pair<std::string, std::string>>(), bool is_urdf_string = false);\nvoid _set_color_mode(dart::dynamics::MeshShape::ColorMode color_mode, dart::dynamics::SkeletonPtr skel);\nvoid _set_color_mode(dart::dynamics::MeshShape::ColorMode color_mode, dart::dynamics::ShapeNode* sn);\nvoid _set_actuator_type(size_t joint_index, dart::dynamics::Joint::ActuatorType type, bool override_mimic = false, bool override_base = false);\nvoid _set_actuator_types(const std::vector<dart::dynamics::Joint::ActuatorType>& types, bool override_mimic = false, bool override_base = false);\nvoid _set_actuator_types(dart::dynamics::Joint::ActuatorType type, bool override_mimic = false, bool override_base = false);\ndart::dynamics::Joint::ActuatorType _actuator_type(size_t joint_index) const;\nstd::vector<dart::dynamics::Joint::ActuatorType> _actuator_types() const;\nEigen::MatrixXd _jacobian(const Eigen::MatrixXd& full_jacobian, const std::vector<std::string>& dof_names) const;\nEigen::MatrixXd _mass_matrix(const Eigen::MatrixXd& full_mass_matrix, const std::vector<std::string>& dof_names) const;\nvirtual void _post_addition(RobotDARTSimu*) {}\nvirtual void _post_removal(RobotDARTSimu*) {}\nfriend class RobotDARTSimu;\nstd::string _robot_name;\nstd::string _model_filename;\nstd::vector<std::pair<std::string, std::string>> _packages;\ndart::dynamics::SkeletonPtr _skeleton;\nstd::vector<std::shared_ptr<control::RobotControl>> _controllers;\nstd::unordered_map<std::string, size_t> _dof_map, _joint_map;\nbool _cast_shadows;\nbool _is_ghost;\nstd::vector<std::pair<dart::dynamics::BodyNode*, double>> _axis_shapes;\n};\n} // namespace robot_dart\n#endif\n
"},{"location":"api/dir_1a1ccbdd0954eb7721b1a771872472c9/","title":"Dir robot_dart/control","text":"

FileList > control

"},{"location":"api/dir_1a1ccbdd0954eb7721b1a771872472c9/#files","title":"Files","text":"Type Name file pd_control.cpp file pd_control.hpp file policy_control.hpp file robot_control.cpp file robot_control.hpp file simple_control.cpp file simple_control.hpp

The documentation for this class was generated from the following file robot_dart/control/

"},{"location":"api/pd__control_8cpp/","title":"File pd_control.cpp","text":"

FileList > control > pd_control.cpp

Go to the source code of this file

"},{"location":"api/pd__control_8cpp/#namespaces","title":"Namespaces","text":"Type Name namespace robot_dart namespace control

The documentation for this class was generated from the following file robot_dart/control/pd_control.cpp

"},{"location":"api/pd__control_8cpp_source/","title":"File pd_control.cpp","text":"

File List > control > pd_control.cpp

Go to the documentation of this file

#include \"pd_control.hpp\"\n#include \"robot_dart/robot.hpp\"\n#include \"robot_dart/utils.hpp\"\n#include \"robot_dart/utils_headers_dart_dynamics.hpp\"\nnamespace robot_dart {\nnamespace control {\nPDControl::PDControl() : RobotControl() {}\nPDControl::PDControl(const Eigen::VectorXd& ctrl, bool full_control, bool use_angular_errors) : RobotControl(ctrl, full_control), _use_angular_errors(use_angular_errors) {}\nPDControl::PDControl(const Eigen::VectorXd& ctrl, const std::vector<std::string>& controllable_dofs, bool use_angular_errors) : RobotControl(ctrl, controllable_dofs), _use_angular_errors(use_angular_errors) {}\nvoid PDControl::configure()\n{\nif (_ctrl.size() == _control_dof)\n_active = true;\nif (_Kp.size() == 0)\nset_pd(10., 0.1);\n}\nEigen::VectorXd PDControl::calculate(double)\n{\nROBOT_DART_ASSERT(_control_dof == _ctrl.size(), \"PDControl: Controller parameters size is not the same as DOFs of the robot\", Eigen::VectorXd::Zero(_control_dof));\nauto robot = _robot.lock();\nEigen::VectorXd dq = robot->velocities(_controllable_dofs);\nEigen::VectorXd error;\nif (!_use_angular_errors) {\nEigen::VectorXd q = robot->positions(_controllable_dofs);\nerror = _ctrl - q;\n}\nelse {\nerror = Eigen::VectorXd::Zero(_control_dof);\nstd::unordered_map<size_t, Eigen::VectorXd> joint_vals, joint_desired, errors;\nfor (int i = 0; i < _control_dof; ++i) {\nauto dof = robot->dof(_controllable_dofs[i]);\nsize_t joint_index = dof->getJoint()->getJointIndexInSkeleton();\nif (joint_vals.find(joint_index) == joint_vals.end()) {\njoint_vals[joint_index] = dof->getJoint()->getPositions();\njoint_desired[joint_index] = dof->getJoint()->getPositions();\n}\njoint_desired[joint_index][dof->getIndexInJoint()] = _ctrl[i];\n}\nfor (int i = 0; i < _control_dof; ++i) {\nauto dof = robot->dof(_controllable_dofs[i]);\nsize_t joint_index = dof->getJoint()->getJointIndexInSkeleton();\nsize_t dof_index_in_joint = dof->getIndexInJoint();\nEigen::VectorXd val;\nif (errors.find(joint_index) == errors.end()) {\nval = Eigen::VectorXd(dof->getJoint()->getNumDofs());\nstd::string joint_type = robot->dof(_controllable_dofs[i])->getJoint()->getType();\nif (joint_type == dart::dynamics::RevoluteJoint::getStaticType()) {\nval[dof_index_in_joint] = _angle_dist(_ctrl[i], joint_vals[joint_index][dof_index_in_joint]);\n}\nelse if (joint_type == dart::dynamics::BallJoint::getStaticType()) {\nEigen::Matrix3d R_desired = dart::math::expMapRot(joint_desired[joint_index]);\nEigen::Matrix3d R_current = dart::math::expMapRot(joint_vals[joint_index]);\nval = dart::math::logMap(R_desired * R_current.transpose());\n}\nelse if (joint_type == dart::dynamics::EulerJoint::getStaticType()) {\n// TO-DO: Check if this is 100% correct\nfor (size_t d = 0; d < dof->getJoint()->getNumDofs(); d++)\nval[d] = _angle_dist(joint_desired[joint_index][d], joint_vals[joint_index][d]);\n}\nelse if (joint_type == dart::dynamics::FreeJoint::getStaticType()) {\nauto free_joint = static_cast<dart::dynamics::FreeJoint*>(dof->getJoint());\nEigen::Isometry3d tf_desired = free_joint->convertToTransform(joint_desired[joint_index]);\nEigen::Isometry3d tf_current = free_joint->convertToTransform(joint_vals[joint_index]);\nval.tail(3) = tf_desired.translation() - tf_current.translation();\nval.head(3) = dart::math::logMap(tf_desired.linear().matrix() * tf_current.linear().matrix().transpose());\n}\nelse {\nval[dof_index_in_joint] = _ctrl[i] - joint_vals[joint_index][dof_index_in_joint];\n}\nerrors[joint_index] = val;\n}\nelse\nval = errors[joint_index];\nerror(i) = val[dof_index_in_joint];\n}\n}\nEigen::VectorXd commands = _Kp.array() * error.array() - _Kd.array() * dq.array();\nreturn commands;\n}\nvoid PDControl::set_pd(double Kp, double Kd)\n{\n_Kp = Eigen::VectorXd::Constant(_control_dof, Kp);\n_Kd = Eigen::VectorXd::Constant(_control_dof, Kd);\n}\nvoid PDControl::set_pd(const Eigen::VectorXd& Kp, const Eigen::VectorXd& Kd)\n{\nROBOT_DART_ASSERT(Kp.size() == _control_dof, \"PDControl: The Kp size is not the same as the DOFs!\", );\nROBOT_DART_ASSERT(Kd.size() == _control_dof, \"PDControl: The Kd size is not the same as the DOFs!\", );\n_Kp = Kp;\n_Kd = Kd;\n}\nstd::pair<Eigen::VectorXd, Eigen::VectorXd> PDControl::pd() const\n{\nreturn std::make_pair(_Kp, _Kd);\n}\nbool PDControl::using_angular_errors() const { return _use_angular_errors; }\nvoid PDControl::set_use_angular_errors(bool enable) { _use_angular_errors = enable; }\nstd::shared_ptr<RobotControl> PDControl::clone() const\n{\nreturn std::make_shared<PDControl>(*this);\n}\ndouble PDControl::_angle_dist(double target, double current)\n{\ndouble theta = target - current;\nwhile (theta < -M_PI)\ntheta += 2 * M_PI;\nwhile (theta > M_PI)\ntheta -= 2 * M_PI;\nreturn theta;\n}\n} // namespace control\n} // namespace robot_dart\n
"},{"location":"api/pd__control_8hpp/","title":"File pd_control.hpp","text":"

FileList > control > pd_control.hpp

Go to the source code of this file

"},{"location":"api/pd__control_8hpp/#namespaces","title":"Namespaces","text":"Type Name namespace robot_dart namespace control"},{"location":"api/pd__control_8hpp/#classes","title":"Classes","text":"Type Name class PDControl

The documentation for this class was generated from the following file robot_dart/control/pd_control.hpp

"},{"location":"api/pd__control_8hpp_source/","title":"File pd_control.hpp","text":"

File List > control > pd_control.hpp

Go to the documentation of this file

#ifndef ROBOT_DART_CONTROL_PD_CONTROL\n#define ROBOT_DART_CONTROL_PD_CONTROL\n#include <utility>\n#include <robot_dart/control/robot_control.hpp>\n#include <robot_dart/robot.hpp>\nnamespace robot_dart {\nnamespace control {\nclass PDControl : public RobotControl {\npublic:\nPDControl();\nPDControl(const Eigen::VectorXd& ctrl, bool full_control = false, bool use_angular_errors = true);\nPDControl(const Eigen::VectorXd& ctrl, const std::vector<std::string>& controllable_dofs, bool use_angular_errors = true);\nvoid configure() override;\nEigen::VectorXd calculate(double) override;\nvoid set_pd(double p, double d);\nvoid set_pd(const Eigen::VectorXd& p, const Eigen::VectorXd& d);\nstd::pair<Eigen::VectorXd, Eigen::VectorXd> pd() const;\nbool using_angular_errors() const;\nvoid set_use_angular_errors(bool enable = true);\nstd::shared_ptr<RobotControl> clone() const override;\nprotected:\nEigen::VectorXd _Kp;\nEigen::VectorXd _Kd;\nbool _use_angular_errors;\nstatic double _angle_dist(double target, double current);\n};\n} // namespace control\n} // namespace robot_dart\n#endif\n
"},{"location":"api/policy__control_8hpp/","title":"File policy_control.hpp","text":"

FileList > control > policy_control.hpp

Go to the source code of this file

"},{"location":"api/policy__control_8hpp/#namespaces","title":"Namespaces","text":"Type Name namespace robot_dart namespace control"},{"location":"api/policy__control_8hpp/#classes","title":"Classes","text":"Type Name class PolicyControl <typename Policy>

The documentation for this class was generated from the following file robot_dart/control/policy_control.hpp

"},{"location":"api/policy__control_8hpp_source/","title":"File policy_control.hpp","text":"

File List > control > policy_control.hpp

Go to the documentation of this file

#ifndef ROBOT_DART_CONTROL_POLICY_CONTROL\n#define ROBOT_DART_CONTROL_POLICY_CONTROL\n#include <robot_dart/control/robot_control.hpp>\n#include <robot_dart/robot.hpp>\nnamespace robot_dart {\nnamespace control {\ntemplate <typename Policy>\nclass PolicyControl : public RobotControl {\npublic:\nPolicyControl() : RobotControl() {}\nPolicyControl(double dt, const Eigen::VectorXd& ctrl, bool full_control = false) : RobotControl(ctrl, full_control), _dt(dt), _first(true), _full_dt(false) {}\nPolicyControl(const Eigen::VectorXd& ctrl, bool full_control = false) : RobotControl(ctrl, full_control), _dt(0.), _first(true), _full_dt(true) {}\nPolicyControl(double dt, const Eigen::VectorXd& ctrl, const std::vector<std::string>& controllable_dofs) : RobotControl(ctrl, controllable_dofs), _dt(dt), _first(true), _full_dt(false) {}\nPolicyControl(const Eigen::VectorXd& ctrl, const std::vector<std::string>& controllable_dofs) : RobotControl(ctrl, controllable_dofs), _dt(0.), _first(true), _full_dt(true) {}\nvoid configure() override\n{\n_policy.set_params(_ctrl);\nif (_policy.output_size() == _control_dof)\n_active = true;\nelse\nROBOT_DART_WARNING(_policy.output_size() != _control_dof, \"Control DoF != Policy output size. Policy is not active.\");\nauto robot = _robot.lock();\nif (_full_dt)\n_dt = robot->skeleton()->getTimeStep();\n_first = true;\n_i = 0;\n_threshold = -robot->skeleton()->getTimeStep() * 0.5;\n}\nvoid set_h_params(const Eigen::VectorXd& h_params)\n{\n_policy.set_h_params(h_params);\n}\nEigen::VectorXd h_params() const\n{\nreturn _policy.h_params();\n}\nEigen::VectorXd calculate(double t) override\n{\nROBOT_DART_ASSERT(_control_dof == _policy.output_size(), \"PolicyControl: Policy output size is not the same as DOFs of the robot\", Eigen::VectorXd::Zero(_control_dof));\nif (_first || _full_dt || (t - _prev_time - _dt) >= _threshold) {\n_prev_commands = _policy.query(_robot.lock(), t);\n_first = false;\n_prev_time = t;\n_i++;\n}\nreturn _prev_commands;\n}\nstd::shared_ptr<RobotControl> clone() const override\n{\nreturn std::make_shared<PolicyControl>(*this);\n}\nprotected:\nint _i;\nPolicy _policy;\ndouble _dt, _prev_time, _threshold;\nEigen::VectorXd _prev_commands;\nbool _first, _full_dt;\n};\n} // namespace control\n} // namespace robot_dart\n#endif\n
"},{"location":"api/robot__control_8cpp/","title":"File robot_control.cpp","text":"

FileList > control > robot_control.cpp

Go to the source code of this file

"},{"location":"api/robot__control_8cpp/#namespaces","title":"Namespaces","text":"Type Name namespace robot_dart namespace control

The documentation for this class was generated from the following file robot_dart/control/robot_control.cpp

"},{"location":"api/robot__control_8cpp_source/","title":"File robot_control.cpp","text":"

File List > control > robot_control.cpp

Go to the documentation of this file

#include \"robot_control.hpp\"\n#include \"robot_dart/robot.hpp\"\n#include \"robot_dart/utils.hpp\"\n#include \"robot_dart/utils_headers_dart_dynamics.hpp\"\nnamespace robot_dart {\nnamespace control {\nRobotControl::RobotControl() : _weight(1.), _active(false), _check_free(true) {}\nRobotControl::RobotControl(const Eigen::VectorXd& ctrl, const std::vector<std::string>& controllable_dofs) : _ctrl(ctrl), _weight(1.), _active(false), _check_free(false), _controllable_dofs(controllable_dofs) {}\nRobotControl::RobotControl(const Eigen::VectorXd& ctrl, bool full_control) : _ctrl(ctrl), _weight(1.), _active(false), _check_free(!full_control) {}\nvoid RobotControl::set_parameters(const Eigen::VectorXd& ctrl)\n{\n_ctrl = ctrl;\n_active = false;\ninit();\n}\nconst Eigen::VectorXd& RobotControl::parameters() const\n{\nreturn _ctrl;\n}\nvoid RobotControl::init()\n{\nROBOT_DART_ASSERT(_robot.use_count() > 0, \"RobotControl: parent robot should be initialized; use set_robot()\", );\nauto robot = _robot.lock();\n_dof = robot->skeleton()->getNumDofs();\nif (_check_free && robot->free()) {\nauto names = robot->dof_names(true, true, true);\n_controllable_dofs = std::vector<std::string>(names.begin() + 6, names.end());\n}\nelse if (_controllable_dofs.empty()) {\n// we cannot control mimic, locked and passive joints\n_controllable_dofs = robot->dof_names(true, true, true);\n}\n_control_dof = _controllable_dofs.size();\nconfigure();\n}\nvoid RobotControl::set_robot(const std::shared_ptr<Robot>& robot)\n{\n_robot = robot;\n}\nstd::shared_ptr<Robot> RobotControl::robot() const\n{\nreturn _robot.lock();\n}\nvoid RobotControl::activate(bool enable)\n{\n_active = false;\nif (enable) {\ninit();\n}\n}\nbool RobotControl::active() const\n{\nreturn _active;\n}\nconst std::vector<std::string>& RobotControl::controllable_dofs() const { return _controllable_dofs; }\ndouble RobotControl::weight() const\n{\nreturn _weight;\n}\nvoid RobotControl::set_weight(double weight)\n{\n_weight = weight;\n}\n} // namespace control\n} // namespace robot_dart\n
"},{"location":"api/robot__control_8hpp/","title":"File robot_control.hpp","text":"

FileList > control > robot_control.hpp

Go to the source code of this file

"},{"location":"api/robot__control_8hpp/#namespaces","title":"Namespaces","text":"Type Name namespace robot_dart namespace control"},{"location":"api/robot__control_8hpp/#classes","title":"Classes","text":"Type Name class RobotControl

The documentation for this class was generated from the following file robot_dart/control/robot_control.hpp

"},{"location":"api/robot__control_8hpp_source/","title":"File robot_control.hpp","text":"

File List > control > robot_control.hpp

Go to the documentation of this file

#ifndef ROBOT_DART_CONTROL_ROBOT_CONTROL\n#define ROBOT_DART_CONTROL_ROBOT_CONTROL\n#include <robot_dart/utils.hpp>\n#include <memory>\n#include <vector>\nnamespace robot_dart {\nclass Robot;\nnamespace control {\nclass RobotControl {\npublic:\nRobotControl();\nRobotControl(const Eigen::VectorXd& ctrl, bool full_control = false);\nRobotControl(const Eigen::VectorXd& ctrl, const std::vector<std::string>& controllable_dofs);\nvirtual ~RobotControl() {}\nvoid set_parameters(const Eigen::VectorXd& ctrl);\nconst Eigen::VectorXd& parameters() const;\nvoid init();\nvoid set_robot(const std::shared_ptr<Robot>& robot);\nstd::shared_ptr<Robot> robot() const;\nvoid activate(bool enable = true);\nbool active() const;\nconst std::vector<std::string>& controllable_dofs() const;\ndouble weight() const;\nvoid set_weight(double weight);\nvirtual void configure() = 0;\n// TO-DO: Maybe make this const?\nvirtual Eigen::VectorXd calculate(double t) = 0;\nvirtual std::shared_ptr<RobotControl> clone() const = 0;\nprotected:\nstd::weak_ptr<Robot> _robot;\nEigen::VectorXd _ctrl;\ndouble _weight;\nbool _active, _check_free = false;\nint _dof, _control_dof;\nstd::vector<std::string> _controllable_dofs;\n};\n} // namespace control\n} // namespace robot_dart\n#endif\n
"},{"location":"api/simple__control_8cpp/","title":"File simple_control.cpp","text":"

FileList > control > simple_control.cpp

Go to the source code of this file

"},{"location":"api/simple__control_8cpp/#namespaces","title":"Namespaces","text":"Type Name namespace robot_dart namespace control

The documentation for this class was generated from the following file robot_dart/control/simple_control.cpp

"},{"location":"api/simple__control_8cpp_source/","title":"File simple_control.cpp","text":"

File List > control > simple_control.cpp

Go to the documentation of this file

#include \"simple_control.hpp\"\n#include \"robot_dart/robot.hpp\"\n#include \"robot_dart/utils.hpp\"\nnamespace robot_dart {\nnamespace control {\nSimpleControl::SimpleControl() : RobotControl() {}\nSimpleControl::SimpleControl(const Eigen::VectorXd& ctrl, bool full_control) : RobotControl(ctrl, full_control) {}\nSimpleControl::SimpleControl(const Eigen::VectorXd& ctrl, const std::vector<std::string>& controllable_dofs) : RobotControl(ctrl, controllable_dofs) {}\nvoid SimpleControl::configure()\n{\nif (_ctrl.size() == _control_dof)\n_active = true;\n}\nEigen::VectorXd SimpleControl::calculate(double)\n{\nROBOT_DART_ASSERT(_control_dof == _ctrl.size(), \"SimpleControl: Controller parameters size is not the same as DOFs of the robot\", Eigen::VectorXd::Zero(_control_dof));\nreturn _ctrl;\n}\nstd::shared_ptr<RobotControl> SimpleControl::clone() const\n{\nreturn std::make_shared<SimpleControl>(*this);\n}\n} // namespace control\n} // namespace robot_dart\n
"},{"location":"api/simple__control_8hpp/","title":"File simple_control.hpp","text":"

FileList > control > simple_control.hpp

Go to the source code of this file

"},{"location":"api/simple__control_8hpp/#namespaces","title":"Namespaces","text":"Type Name namespace robot_dart namespace control"},{"location":"api/simple__control_8hpp/#classes","title":"Classes","text":"Type Name class SimpleControl

The documentation for this class was generated from the following file robot_dart/control/simple_control.hpp

"},{"location":"api/simple__control_8hpp_source/","title":"File simple_control.hpp","text":"

File List > control > simple_control.hpp

Go to the documentation of this file

#ifndef ROBOT_DART_CONTROL_SIMPLE_CONTROL\n#define ROBOT_DART_CONTROL_SIMPLE_CONTROL\n#include <robot_dart/control/robot_control.hpp>\nnamespace robot_dart {\nnamespace control {\nclass SimpleControl : public RobotControl {\npublic:\nSimpleControl();\nSimpleControl(const Eigen::VectorXd& ctrl, bool full_control = false);\nSimpleControl(const Eigen::VectorXd& ctrl, const std::vector<std::string>& controllable_dofs);\nvoid configure() override;\nEigen::VectorXd calculate(double) override;\nstd::shared_ptr<RobotControl> clone() const override;\n};\n} // namespace control\n} // namespace robot_dart\n#endif\n
"},{"location":"api/dir_6a9d4b7ec29c938d1d9a486c655cfc8a/","title":"Dir robot_dart/gui","text":"

FileList > gui

"},{"location":"api/dir_6a9d4b7ec29c938d1d9a486c655cfc8a/#files","title":"Files","text":"Type Name file base.hpp file helper.cpp file helper.hpp file stb_image_write.h"},{"location":"api/dir_6a9d4b7ec29c938d1d9a486c655cfc8a/#directories","title":"Directories","text":"Type Name dir magnum

The documentation for this class was generated from the following file robot_dart/gui/

"},{"location":"api/base_8hpp/","title":"File base.hpp","text":"

FileList > gui > base.hpp

Go to the source code of this file

"},{"location":"api/base_8hpp/#namespaces","title":"Namespaces","text":"Type Name namespace robot_dart namespace gui"},{"location":"api/base_8hpp/#classes","title":"Classes","text":"Type Name class Base

The documentation for this class was generated from the following file robot_dart/gui/base.hpp

"},{"location":"api/base_8hpp_source/","title":"File base.hpp","text":"

File List > gui > base.hpp

Go to the documentation of this file

#ifndef ROBOT_DART_GUI_BASE_HPP\n#define ROBOT_DART_GUI_BASE_HPP\n#include <robot_dart/gui/helper.hpp>\nnamespace robot_dart {\nclass RobotDARTSimu;\nnamespace gui {\nclass Base {\npublic:\nBase() {}\nvirtual ~Base() {}\nvirtual void set_simu(RobotDARTSimu* simu) { _simu = simu; }\nconst RobotDARTSimu* simu() const { return _simu; }\nvirtual bool done() const { return false; }\nvirtual void refresh() {}\nvirtual void set_render_period(double) {}\nvirtual void set_enable(bool) {}\nvirtual void set_fps(int) {}\nvirtual Image image() { return Image(); }\nvirtual GrayscaleImage depth_image() { return GrayscaleImage(); }\nvirtual GrayscaleImage raw_depth_image() { return GrayscaleImage(); }\nvirtual DepthImage depth_array() { return DepthImage(); }\nvirtual size_t width() const { return 0; }\nvirtual size_t height() const { return 0; }\nprotected:\nRobotDARTSimu* _simu = nullptr;\n};\n} // namespace gui\n} // namespace robot_dart\n#endif\n
"},{"location":"api/helper_8cpp/","title":"File helper.cpp","text":"

FileList > gui > helper.cpp

Go to the source code of this file

"},{"location":"api/helper_8cpp/#namespaces","title":"Namespaces","text":"Type Name namespace robot_dart namespace gui"},{"location":"api/helper_8cpp/#macros","title":"Macros","text":"Type Name define STB_IMAGE_WRITE_IMPLEMENTATION"},{"location":"api/helper_8cpp/#macro-definition-documentation","title":"Macro Definition Documentation","text":""},{"location":"api/helper_8cpp/#define-stb_image_write_implementation","title":"define STB_IMAGE_WRITE_IMPLEMENTATION","text":"
#define STB_IMAGE_WRITE_IMPLEMENTATION \n

The documentation for this class was generated from the following file robot_dart/gui/helper.cpp

"},{"location":"api/helper_8cpp_source/","title":"File helper.cpp","text":"

File List > gui > helper.cpp

Go to the documentation of this file

#include \"helper.hpp\"\n#define STB_IMAGE_WRITE_IMPLEMENTATION\n#include \"stb_image_write.h\"\nnamespace robot_dart {\nnamespace gui {\nvoid save_png_image(const std::string& filename, const Image& rgb)\n{\nauto ends_with = [](const std::string& value, const std::string& ending) {\nif (ending.size() > value.size())\nreturn false;\nreturn std::equal(ending.rbegin(), ending.rend(), value.rbegin());\n};\nstd::string png = \".png\";\nif (ends_with(filename, png))\npng = \"\";\nstbi_write_png((filename + png).c_str(), rgb.width, rgb.height, rgb.channels, rgb.data.data(), rgb.width * rgb.channels);\n}\nvoid save_png_image(const std::string& filename, const GrayscaleImage& gray)\n{\nauto ends_with = [](const std::string& value, const std::string& ending) {\nif (ending.size() > value.size())\nreturn false;\nreturn std::equal(ending.rbegin(), ending.rend(), value.rbegin());\n};\nstd::string png = \".png\";\nif (ends_with(filename, png))\npng = \"\";\nstbi_write_png((filename + png).c_str(), gray.width, gray.height, 1, gray.data.data(), gray.width);\n}\nGrayscaleImage convert_rgb_to_grayscale(const Image& rgb)\n{\nassert(rgb.channels == 3);\nsize_t width = rgb.width;\nsize_t height = rgb.height;\nGrayscaleImage gray;\ngray.width = width;\ngray.height = height;\ngray.data.resize(width * height);\nfor (size_t h = 0; h < height; h++) {\nfor (size_t w = 0; w < width; w++) {\nint id = w + h * width;\nint id_rgb = w * rgb.channels + h * (width * rgb.channels);\nuint8_t color = 0.3 * rgb.data[id_rgb + 0] + 0.59 * rgb.data[id_rgb + 1] + 0.11 * rgb.data[id_rgb + 2];\ngray.data[id] = color;\n}\n}\nreturn gray;\n}\nstd::vector<Eigen::Vector3d> point_cloud_from_depth_array(const DepthImage& depth_image, const Eigen::Matrix3d& intrinsic_matrix, const Eigen::Matrix4d& tf, double far_plane)\n{\n// This is assuming that K is normal intrisinc matrix (i.e., camera pointing to +Z),\n// but an OpenGL camera (i.e., pointing to -Z). Thus it transforms the points accordingly\n// TO-DO: Format the intrinsic matrix correctly, and take as an argument the camera orientation\n// with respect to the normal cameras. See http://ksimek.github.io/2013/06/03/calibrated_cameras_in_opengl/.\nauto point_3d = [](const Eigen::Matrix3d& K, size_t u, size_t v, double depth) {\ndouble fx = K(0, 0);\ndouble fy = K(1, 1);\ndouble cx = K(0, 2);\ndouble cy = K(1, 2);\ndouble gamma = K(0, 1);\nEigen::Vector3d p;\np << 0., 0., -depth;\np(1) = (cy - v) * depth / fy;\np(0) = -((cx - u) * depth - gamma * p(1)) / fx;\nreturn p;\n};\nstd::vector<Eigen::Vector3d> point_cloud;\nsize_t height = depth_image.height;\nsize_t width = depth_image.width;\nfor (size_t h = 0; h < height; h++) {\nfor (size_t w = 0; w < width; w++) {\nint id = w + h * width;\nif (depth_image.data[id] >= 0.99 * far_plane) // close to far plane\ncontinue;\nEigen::Vector4d pp;\npp.head(3) = point_3d(intrinsic_matrix, w, h, depth_image.data[id]);\npp.tail(1) << 1.;\npp = tf.inverse() * pp;\npoint_cloud.push_back(pp.head(3));\n}\n}\nreturn point_cloud;\n}\n} // namespace gui\n} // namespace robot_dart\n
"},{"location":"api/helper_8hpp/","title":"File helper.hpp","text":"

FileList > gui > helper.hpp

Go to the source code of this file

"},{"location":"api/helper_8hpp/#namespaces","title":"Namespaces","text":"Type Name namespace robot_dart namespace gui"},{"location":"api/helper_8hpp/#classes","title":"Classes","text":"Type Name struct DepthImage struct GrayscaleImage struct Image

The documentation for this class was generated from the following file robot_dart/gui/helper.hpp

"},{"location":"api/helper_8hpp_source/","title":"File helper.hpp","text":"

File List > gui > helper.hpp

Go to the documentation of this file

#ifndef ROBOT_DART_GUI_HELPER_HPP\n#define ROBOT_DART_GUI_HELPER_HPP\n#include <string>\n#include <vector>\n#include <robot_dart/utils.hpp>\nnamespace robot_dart {\nnamespace gui {\nstruct Image {\nsize_t width = 0, height = 0;\nsize_t channels = 3;\nstd::vector<uint8_t> data;\n};\nstruct GrayscaleImage {\nsize_t width = 0, height = 0;\nstd::vector<uint8_t> data;\n};\nstruct DepthImage {\nsize_t width = 0, height = 0;\nstd::vector<double> data;\n};\nvoid save_png_image(const std::string& filename, const Image& rgb);\nvoid save_png_image(const std::string& filename, const GrayscaleImage& gray);\nGrayscaleImage convert_rgb_to_grayscale(const Image& rgb);\nstd::vector<Eigen::Vector3d> point_cloud_from_depth_array(const DepthImage& depth_image, const Eigen::Matrix3d& intrinsic_matrix, const Eigen::Matrix4d& tf, double far_plane = 1000.);\n} // namespace gui\n} // namespace robot_dart\n#endif\n
"},{"location":"api/dir_5d18adecbc10cabf3ca51da31f2acdd1/","title":"Dir robot_dart/gui/magnum","text":"

FileList > gui > magnum

"},{"location":"api/dir_5d18adecbc10cabf3ca51da31f2acdd1/#files","title":"Files","text":"Type Name file base_application.cpp file base_application.hpp file base_graphics.hpp file drawables.cpp file drawables.hpp file glfw_application.cpp file glfw_application.hpp file graphics.cpp file graphics.hpp file types.hpp file utils_headers_eigen.hpp file windowless_gl_application.cpp file windowless_gl_application.hpp file windowless_graphics.cpp file windowless_graphics.hpp"},{"location":"api/dir_5d18adecbc10cabf3ca51da31f2acdd1/#directories","title":"Directories","text":"Type Name dir gs dir sensor

The documentation for this class was generated from the following file robot_dart/gui/magnum/

"},{"location":"api/base__application_8cpp/","title":"File base_application.cpp","text":"

FileList > gui > magnum > base_application.cpp

Go to the source code of this file

"},{"location":"api/base__application_8cpp/#namespaces","title":"Namespaces","text":"Type Name namespace robot_dart namespace gui namespace magnum

The documentation for this class was generated from the following file robot_dart/gui/magnum/base_application.cpp

"},{"location":"api/base__application_8cpp_source/","title":"Macro Syntax Error","text":"

Line 88 in Markdown file: Expected an expression, got 'end of print statement'

                    _gl_contexts.emplace_back(Magnum::Platform::WindowlessGLContext{{}});\n

"},{"location":"api/base__application_8hpp/","title":"File base_application.hpp","text":"

FileList > gui > magnum > base_application.hpp

Go to the source code of this file

"},{"location":"api/base__application_8hpp/#namespaces","title":"Namespaces","text":"Type Name namespace robot_dart namespace gui namespace magnum"},{"location":"api/base__application_8hpp/#classes","title":"Classes","text":"Type Name class BaseApplication struct DebugDrawData struct GlobalData struct GraphicsConfiguration"},{"location":"api/base__application_8hpp/#macros","title":"Macros","text":"Type Name define get_gl_context (name) get_gl_context_with_sleep(name, 0) define get_gl_context_with_sleep (name, ms_sleep) define release_gl_context (name) robot_dart::gui::magnum::GlobalData::instance()->free_gl_context(name);"},{"location":"api/base__application_8hpp/#macro-definition-documentation","title":"Macro Definition Documentation","text":""},{"location":"api/base__application_8hpp/#define-get_gl_context","title":"define get_gl_context","text":"
#define get_gl_context (\nname\n) get_gl_context_with_sleep(name, 0)\n
"},{"location":"api/base__application_8hpp/#define-get_gl_context_with_sleep","title":"define get_gl_context_with_sleep","text":"
#define get_gl_context_with_sleep (\nname,\nms_sleep\n) /* Create/Get GLContext */                                                \\\n    Corrade::Utility::Debug name##_magnum_silence_output{nullptr};            \\\n    Magnum::Platform::WindowlessGLContext* name = nullptr;                    \\\n    while (name == nullptr) {                                                 \\\n        name = robot_dart::gui::magnum::GlobalData::instance()->gl_context(); \\\n        /* Sleep for some ms */                                               \\\n        usleep(ms_sleep * 1000);                                              \\\n    }                                                                         \\\n    while (!name->makeCurrent()) {                                            \\\n        /* Sleep for some ms */                                               \\\n        usleep(ms_sleep * 1000);                                              \\\n    }                                                                         \\\n                                                                              \\\n    Magnum::Platform::GLContext name##_magnum_context;\n
"},{"location":"api/base__application_8hpp/#define-release_gl_context","title":"define release_gl_context","text":"
#define release_gl_context (\nname\n) robot_dart::gui::magnum::GlobalData::instance()->free_gl_context(name);\n

The documentation for this class was generated from the following file robot_dart/gui/magnum/base_application.hpp

"},{"location":"api/base__application_8hpp_source/","title":"File base_application.hpp","text":"

File List > gui > magnum > base_application.hpp

Go to the documentation of this file

#ifndef ROBOT_DART_GUI_MAGNUM_BASE_APPLICATION_HPP\n#define ROBOT_DART_GUI_MAGNUM_BASE_APPLICATION_HPP\n#include <mutex>\n#include <unistd.h>\n#include <unordered_map>\n#include <robot_dart/gui/helper.hpp>\n#include <robot_dart/gui/magnum/drawables.hpp>\n#include <robot_dart/gui/magnum/gs/camera.hpp>\n#include <robot_dart/gui/magnum/gs/cube_map.hpp>\n#include <robot_dart/gui/magnum/gs/cube_map_color.hpp>\n#include <robot_dart/gui/magnum/gs/phong_multi_light.hpp>\n#include <robot_dart/gui/magnum/gs/shadow_map.hpp>\n#include <robot_dart/gui/magnum/gs/shadow_map_color.hpp>\n#include <robot_dart/gui/magnum/types.hpp>\n#include <robot_dart/utils_headers_external_gui.hpp>\n#include <Magnum/GL/CubeMapTextureArray.h>\n#include <Magnum/GL/Framebuffer.h>\n#include <Magnum/GL/Mesh.h>\n#include <Magnum/GL/TextureArray.h>\n#include <Magnum/Platform/GLContext.h>\n#ifndef MAGNUM_MAC_OSX\n#include <Magnum/Platform/WindowlessEglApplication.h>\n#else\n#include <Magnum/Platform/WindowlessCglApplication.h>\n#endif\n#include <Magnum/Shaders/DistanceFieldVector.h>\n#include <Magnum/Shaders/Flat.h>\n#include <Magnum/Shaders/VertexColor.h>\n#include <Magnum/Text/AbstractFont.h>\n#include <Magnum/Text/DistanceFieldGlyphCache.h>\n#include <Magnum/Text/Renderer.h>\n#define get_gl_context_with_sleep(name, ms_sleep)                             \\\n/* Create/Get GLContext */                                                \\\n    Corrade::Utility::Debug name##_magnum_silence_output{nullptr};            \\\n    Magnum::Platform::WindowlessGLContext* name = nullptr;                    \\\n    while (name == nullptr) {                                                 \\\n        name = robot_dart::gui::magnum::GlobalData::instance()->gl_context(); \\\n/* Sleep for some ms */                                               \\\n        usleep(ms_sleep * 1000);                                              \\\n    }                                                                         \\\n    while (!name->makeCurrent()) {                                            \\\n/* Sleep for some ms */                                               \\\n        usleep(ms_sleep * 1000);                                              \\\n    }                                                                         \\\n                                                                              \\\n    Magnum::Platform::GLContext name##_magnum_context;\n#define get_gl_context(name) get_gl_context_with_sleep(name, 0)\n#define release_gl_context(name) robot_dart::gui::magnum::GlobalData::instance()->free_gl_context(name);\nnamespace robot_dart {\nnamespace gui {\nnamespace magnum {\nstruct GlobalData {\npublic:\nstatic GlobalData* instance()\n{\nstatic GlobalData gdata;\nreturn &gdata;\n}\nGlobalData(const GlobalData&) = delete;\nvoid operator=(const GlobalData&) = delete;\nMagnum::Platform::WindowlessGLContext* gl_context();\nvoid free_gl_context(Magnum::Platform::WindowlessGLContext* context);\n/* You should call this before starting to draw or after finished */\nvoid set_max_contexts(size_t N);\nprivate:\nGlobalData() = default;\n~GlobalData() = default;\nvoid _create_contexts();\nstd::vector<Magnum::Platform::WindowlessGLContext> _gl_contexts;\nstd::vector<bool> _used;\nstd::mutex _context_mutex;\nsize_t _max_contexts = 4;\n};\nstruct GraphicsConfiguration {\n// General\nsize_t width = 640;\nsize_t height = 480;\nstd::string title = \"DART\";\n// Shadows\nbool shadowed = true;\nbool transparent_shadows = true;\nsize_t shadow_map_size = 1024;\n// Lights\nsize_t max_lights = 3;\ndouble specular_strength = 0.25; // strength of the specular component\n// These options are only for the main camera\nbool draw_main_camera = true;\nbool draw_debug = true;\nbool draw_text = true;\n// Background (default = black)\nEigen::Vector4d bg_color{0.0, 0.0, 0.0, 1.0};\n};\nstruct DebugDrawData {\nMagnum::Shaders::VertexColorGL3D* axes_shader;\nMagnum::GL::Mesh* axes_mesh;\nMagnum::Shaders::FlatGL2D* background_shader;\nMagnum::GL::Mesh* background_mesh;\nMagnum::Shaders::DistanceFieldVectorGL2D* text_shader;\nMagnum::GL::Buffer* text_vertices;\nMagnum::GL::Buffer* text_indices;\nMagnum::Text::AbstractFont* font;\nMagnum::Text::DistanceFieldGlyphCache* cache;\n};\nclass BaseApplication {\npublic:\nBaseApplication(const GraphicsConfiguration& configuration = GraphicsConfiguration());\nvirtual ~BaseApplication() {}\nvoid init(RobotDARTSimu* simu, const GraphicsConfiguration& configuration);\nvoid clear_lights();\nvoid add_light(const gs::Light& light);\ngs::Light& light(size_t i);\nstd::vector<gs::Light>& lights();\nsize_t num_lights() const;\nMagnum::SceneGraph::DrawableGroup3D& drawables() { return _drawables; }\nScene3D& scene() { return _scene; }\ngs::Camera& camera() { return *_camera; }\nconst gs::Camera& camera() const { return *_camera; }\nbool done() const;\nvoid look_at(const Eigen::Vector3d& camera_pos,\nconst Eigen::Vector3d& look_at,\nconst Eigen::Vector3d& up);\nvirtual void render() {}\nvoid update_lights(const gs::Camera& camera);\nvoid update_graphics();\nvoid render_shadows();\nbool attach_camera(gs::Camera& camera, dart::dynamics::BodyNode* body);\n// video (FPS is mandatory here, see the Graphics class for automatic computation)\nvoid record_video(const std::string& video_fname, int fps) { _camera->record_video(video_fname, fps); }\nbool shadowed() const { return _shadowed; }\nbool transparent_shadows() const { return _transparent_shadows; }\nvoid enable_shadows(bool enable = true, bool drawTransparentShadows = false);\nCorrade::Containers::Optional<Magnum::Image2D>& image() { return _camera->image(); }\n// This is for visualization purposes\nGrayscaleImage depth_image();\n// Image filled with depth buffer values\nGrayscaleImage raw_depth_image();\n// \"Image\" filled with depth buffer values (this returns an array of doubles)\nDepthImage depth_array();\n// Access to debug data\nDebugDrawData debug_draw_data()\n{\nDebugDrawData data;\ndata.axes_shader = _3D_axis_shader.get();\ndata.background_shader = _background_shader.get();\ndata.axes_mesh = _3D_axis_mesh.get();\ndata.background_mesh = _background_mesh.get();\ndata.text_shader = _text_shader.get();\ndata.text_vertices = _text_vertices.get();\ndata.text_indices = _text_indices.get();\ndata.font = _font.get();\ndata.cache = _glyph_cache.get();\nreturn data;\n}\nprotected:\n/* Magnum */\nScene3D _scene;\nMagnum::SceneGraph::DrawableGroup3D _drawables, _shadowed_drawables, _shadowed_color_drawables, _cubemap_drawables, _cubemap_color_drawables;\nstd::unique_ptr<gs::PhongMultiLight> _color_shader, _texture_shader;\nstd::unique_ptr<gs::Camera> _camera;\nbool _done = false;\n/* GUI Config */\nGraphicsConfiguration _configuration;\n/* DART */\nRobotDARTSimu* _simu;\nstd::unique_ptr<Magnum::DartIntegration::World> _dart_world;\nstd::unordered_map<Magnum::DartIntegration::Object*, ObjectStruct*> _drawable_objects;\nstd::vector<gs::Light> _lights;\n/* Shadows */\nbool _shadowed = true, _transparent_shadows = false;\nint _transparentSize = 0;\nstd::unique_ptr<gs::ShadowMap> _shadow_shader, _shadow_texture_shader;\nstd::unique_ptr<gs::ShadowMapColor> _shadow_color_shader, _shadow_texture_color_shader;\nstd::unique_ptr<gs::CubeMap> _cubemap_shader, _cubemap_texture_shader;\nstd::unique_ptr<gs::CubeMapColor> _cubemap_color_shader, _cubemap_texture_color_shader;\nstd::vector<ShadowData> _shadow_data;\nstd::unique_ptr<Magnum::GL::Texture2DArray> _shadow_texture, _shadow_color_texture;\nstd::unique_ptr<Magnum::GL::CubeMapTextureArray> _shadow_cube_map, _shadow_color_cube_map;\nint _max_lights = 5;\nint _shadow_map_size = 512;\nstd::unique_ptr<Camera3D> _shadow_camera;\nObject3D* _shadow_camera_object;\n/* Debug visualization */\nstd::unique_ptr<Magnum::GL::Mesh> _3D_axis_mesh;\nstd::unique_ptr<Magnum::Shaders::VertexColorGL3D> _3D_axis_shader;\nstd::unique_ptr<Magnum::GL::Mesh> _background_mesh;\nstd::unique_ptr<Magnum::Shaders::FlatGL2D> _background_shader;\n/* Text visualization */\nstd::unique_ptr<Magnum::Shaders::DistanceFieldVectorGL2D> _text_shader;\nCorrade::PluginManager::Manager<Magnum::Text::AbstractFont> _font_manager;\nCorrade::Containers::Pointer<Magnum::Text::DistanceFieldGlyphCache> _glyph_cache;\nCorrade::Containers::Pointer<Magnum::Text::AbstractFont> _font;\nCorrade::Containers::Pointer<Magnum::GL::Buffer> _text_vertices;\nCorrade::Containers::Pointer<Magnum::GL::Buffer> _text_indices;\n/* Importer */\nCorrade::PluginManager::Manager<Magnum::Trade::AbstractImporter> _importer_manager;\nvoid _gl_clean_up();\nvoid _prepare_shadows();\n};\ntemplate <typename T>\ninline BaseApplication* make_application(RobotDARTSimu* simu, const GraphicsConfiguration& configuration = GraphicsConfiguration())\n{\nint argc = 0;\nchar** argv = NULL;\nreturn new T(argc, argv, simu, configuration);\n// configuration.width, configuration.height, configuration.shadowed, configuration.transparent_shadows, configuration.max_lights, configuration.shadow_map_size);\n}\n} // namespace magnum\n} // namespace gui\n} // namespace robot_dart\n#endif\n
"},{"location":"api/base__graphics_8hpp/","title":"File base_graphics.hpp","text":"

FileList > gui > magnum > base_graphics.hpp

Go to the source code of this file

"},{"location":"api/base__graphics_8hpp/#namespaces","title":"Namespaces","text":"Type Name namespace robot_dart namespace gui namespace magnum"},{"location":"api/base__graphics_8hpp/#classes","title":"Classes","text":"Type Name class BaseGraphics <typename T>"},{"location":"api/base__graphics_8hpp/#public-static-functions","title":"Public Static Functions","text":"Type Name void robot_dart_initialize_magnum_resources ()"},{"location":"api/base__graphics_8hpp/#public-static-functions-documentation","title":"Public Static Functions Documentation","text":""},{"location":"api/base__graphics_8hpp/#function-robot_dart_initialize_magnum_resources","title":"function robot_dart_initialize_magnum_resources","text":"
static inline void robot_dart_initialize_magnum_resources () 

The documentation for this class was generated from the following file robot_dart/gui/magnum/base_graphics.hpp

"},{"location":"api/base__graphics_8hpp_source/","title":"File base_graphics.hpp","text":"

File List > gui > magnum > base_graphics.hpp

Go to the documentation of this file

#ifndef ROBOT_DART_GUI_MAGNUM_BASE_GRAPHICS_HPP\n#define ROBOT_DART_GUI_MAGNUM_BASE_GRAPHICS_HPP\n#include <robot_dart/gui/base.hpp>\n#include <robot_dart/gui/magnum/glfw_application.hpp>\n#include <robot_dart/gui/magnum/gs/helper.hpp>\n#include <robot_dart/gui/magnum/utils_headers_eigen.hpp>\n#include <robot_dart/robot_dart_simu.hpp>\n// We need this for CORRADE_RESOURCE_INITIALIZE\n#include <Corrade/Utility/Resource.h>\ninline static void robot_dart_initialize_magnum_resources()\n{\nCORRADE_RESOURCE_INITIALIZE(RobotDARTShaders);\n}\nnamespace robot_dart {\nnamespace gui {\nnamespace magnum {\ntemplate <typename T = GlfwApplication>\nclass BaseGraphics : public Base {\npublic:\nBaseGraphics(const GraphicsConfiguration& configuration = GraphicsConfiguration())\n: _configuration(configuration), _enabled(true)\n{\nrobot_dart_initialize_magnum_resources();\n}\nvirtual ~BaseGraphics() {}\nvirtual void set_simu(RobotDARTSimu* simu) override\n{\nROBOT_DART_EXCEPTION_ASSERT(simu, \"Simulation pointer is null!\");\n_simu = simu;\n_magnum_app.reset(make_application<T>(simu, _configuration));\n}\nsize_t width() const override\n{\nROBOT_DART_EXCEPTION_ASSERT(_magnum_app, \"MagnumApp pointer is null!\");\nreturn _magnum_app->camera().width();\n}\nsize_t height() const override\n{\nROBOT_DART_EXCEPTION_ASSERT(_magnum_app, \"MagnumApp pointer is null!\");\nreturn _magnum_app->camera().height();\n}\nbool done() const override\n{\nROBOT_DART_EXCEPTION_ASSERT(_magnum_app, \"MagnumApp pointer is null!\");\nreturn _magnum_app->done();\n}\nvoid refresh() override\n{\nif (!_enabled)\nreturn;\nROBOT_DART_EXCEPTION_ASSERT(_magnum_app, \"MagnumApp pointer is null!\");\n_magnum_app->render();\n}\nvoid set_enable(bool enable) override\n{\n_enabled = enable;\n}\nvoid set_fps(int fps) override { _fps = fps; }\nvoid look_at(const Eigen::Vector3d& camera_pos,\nconst Eigen::Vector3d& look_at = Eigen::Vector3d(0, 0, 0),\nconst Eigen::Vector3d& up = Eigen::Vector3d(0, 0, 1))\n{\nROBOT_DART_EXCEPTION_ASSERT(_magnum_app, \"MagnumApp pointer is null!\");\n_magnum_app->look_at(camera_pos, look_at, up);\n}\nvoid clear_lights()\n{\nROBOT_DART_EXCEPTION_ASSERT(_magnum_app, \"MagnumApp pointer is null!\");\n_magnum_app->clear_lights();\n}\nvoid add_light(const magnum::gs::Light& light)\n{\nROBOT_DART_EXCEPTION_ASSERT(_magnum_app, \"MagnumApp pointer is null!\");\n_magnum_app->add_light(light);\n}\nstd::vector<gs::Light>& lights()\n{\nROBOT_DART_EXCEPTION_ASSERT(_magnum_app, \"MagnumApp pointer is null!\");\nreturn _magnum_app->lights();\n}\nsize_t num_lights() const\n{\nROBOT_DART_EXCEPTION_ASSERT(_magnum_app, \"MagnumApp pointer is null!\");\nreturn _magnum_app->num_lights();\n}\nmagnum::gs::Light& light(size_t i)\n{\nROBOT_DART_EXCEPTION_ASSERT(_magnum_app, \"MagnumApp pointer is null!\");\nreturn _magnum_app->light(i);\n}\nvoid record_video(const std::string& video_fname, int fps = -1)\n{\nint fps_computed = (fps == -1) ? _fps : fps;\nROBOT_DART_EXCEPTION_ASSERT(fps_computed != -1, \"Video FPS not set!\");\nROBOT_DART_EXCEPTION_ASSERT(_magnum_app, \"MagnumApp pointer is null!\");\n_magnum_app->record_video(video_fname, fps_computed);\n}\nbool shadowed() const\n{\nROBOT_DART_EXCEPTION_ASSERT(_magnum_app, \"MagnumApp pointer is null!\");\nreturn _magnum_app->shadowed();\n}\nbool transparent_shadows() const\n{\nROBOT_DART_EXCEPTION_ASSERT(_magnum_app, \"MagnumApp pointer is null!\");\nreturn _magnum_app->transparent_shadows();\n}\nvoid enable_shadows(bool enable = true, bool transparent = true)\n{\nROBOT_DART_EXCEPTION_ASSERT(_magnum_app, \"MagnumApp pointer is null!\");\n_magnum_app->enable_shadows(enable, transparent);\n}\nMagnum::Image2D* magnum_image()\n{\nROBOT_DART_EXCEPTION_ASSERT(_magnum_app, \"MagnumApp pointer is null!\");\nif (_magnum_app->image())\nreturn &(*_magnum_app->image());\nreturn nullptr;\n}\nImage image() override\n{\nauto image = magnum_image();\nif (image)\nreturn gs::rgb_from_image(image);\nreturn Image();\n}\nGrayscaleImage depth_image() override\n{\nROBOT_DART_EXCEPTION_ASSERT(_magnum_app, \"MagnumApp pointer is null!\");\nreturn _magnum_app->depth_image();\n}\nGrayscaleImage raw_depth_image() override\n{\nROBOT_DART_EXCEPTION_ASSERT(_magnum_app, \"MagnumApp pointer is null!\");\nreturn _magnum_app->raw_depth_image();\n}\nDepthImage depth_array() override\n{\nROBOT_DART_EXCEPTION_ASSERT(_magnum_app, \"MagnumApp pointer is null!\");\nreturn _magnum_app->depth_array();\n}\ngs::Camera& camera()\n{\nROBOT_DART_EXCEPTION_ASSERT(_magnum_app, \"MagnumApp pointer is null!\");\nreturn _magnum_app->camera();\n}\nconst gs::Camera& camera() const\n{\nROBOT_DART_EXCEPTION_ASSERT(_magnum_app, \"MagnumApp pointer is null!\");\nreturn _magnum_app->camera();\n}\nEigen::Matrix3d camera_intrinsic_matrix() const\n{\nROBOT_DART_EXCEPTION_ASSERT(_magnum_app, \"MagnumApp pointer is null!\");\nreturn Magnum::EigenIntegration::cast<Eigen::Matrix3d>(Magnum::Matrix3d(_magnum_app->camera().intrinsic_matrix()));\n}\nEigen::Matrix4d camera_extrinsic_matrix() const\n{\nROBOT_DART_EXCEPTION_ASSERT(_magnum_app, \"MagnumApp pointer is null!\");\nreturn Magnum::EigenIntegration::cast<Eigen::Matrix4d>(Magnum::Matrix4d(_magnum_app->camera().extrinsic_matrix()));\n}\nBaseApplication* magnum_app()\n{\nROBOT_DART_EXCEPTION_ASSERT(_magnum_app, \"MagnumApp pointer is null!\");\nreturn &*_magnum_app;\n}\nconst BaseApplication* magnum_app() const\n{\nROBOT_DART_EXCEPTION_ASSERT(_magnum_app, \"MagnumApp pointer is null!\");\nreturn &*_magnum_app;\n}\nprotected:\nGraphicsConfiguration _configuration;\nbool _enabled;\nint _fps;\nstd::unique_ptr<BaseApplication> _magnum_app;\nCorrade::Utility::Debug _magnum_silence_output{nullptr};\n};\n} // namespace magnum\n} // namespace gui\n} // namespace robot_dart\n#endif\n
"},{"location":"api/drawables_8cpp/","title":"File drawables.cpp","text":"

FileList > gui > magnum > drawables.cpp

Go to the source code of this file

"},{"location":"api/drawables_8cpp/#namespaces","title":"Namespaces","text":"Type Name namespace robot_dart namespace gui namespace magnum

The documentation for this class was generated from the following file robot_dart/gui/magnum/drawables.cpp

"},{"location":"api/drawables_8cpp_source/","title":"File drawables.cpp","text":"

File List > gui > magnum > drawables.cpp

Go to the documentation of this file

#include <robot_dart/gui/magnum/drawables.hpp>\n#include <robot_dart/gui_data.hpp>\n#include <robot_dart/robot_dart_simu.hpp>\n#include <robot_dart/utils.hpp>\n#include <Magnum/GL/CubeMapTexture.h>\n#include <Magnum/GL/DefaultFramebuffer.h>\n#include <Magnum/GL/Mesh.h>\n#include <Magnum/GL/Renderer.h>\n#include <Magnum/GL/AbstractFramebuffer.h>\n#include <Magnum/GL/GL.h>\nnamespace robot_dart {\nnamespace gui {\nnamespace magnum {\n// DrawableObject\nDrawableObject::DrawableObject(\nRobotDARTSimu* simu,\ndart::dynamics::ShapeNode* shape,\nconst std::vector<std::reference_wrapper<Magnum::GL::Mesh>>& meshes,\nconst std::vector<gs::Material>& materials,\ngs::PhongMultiLight& color,\ngs::PhongMultiLight& texture,\nObject3D* parent,\nMagnum::SceneGraph::DrawableGroup3D* group)\n: Object3D{parent},\nMagnum::SceneGraph::Drawable3D{*this, group},\n_simu(simu),\n_shape(shape),\n_meshes{meshes},\n_color_shader{color},\n_texture_shader{texture},\n_materials(materials)\n{\n_is_soft_body.resize(_meshes.size(), false);\n}\nDrawableObject& DrawableObject::set_meshes(const std::vector<std::reference_wrapper<Magnum::GL::Mesh>>& meshes)\n{\n_meshes = meshes;\nreturn *this;\n}\nDrawableObject& DrawableObject::set_materials(const std::vector<gs::Material>& materials)\n{\n_materials = materials;\nreturn *this;\n}\nDrawableObject& DrawableObject::set_soft_bodies(const std::vector<bool>& softBody)\n{\n_is_soft_body = softBody;\nreturn *this;\n}\nDrawableObject& DrawableObject::set_scalings(const std::vector<Magnum::Vector3>& scalings)\n{\n_scalings = scalings;\n_has_negative_scaling.resize(_scalings.size());\nfor (size_t i = 0; i < scalings.size(); i++) {\n_has_negative_scaling[i] = false;\nfor (size_t j = 0; j < 3; j++)\nif (_scalings[i][j] < 0.f) {\n_has_negative_scaling[i] = true;\nbreak;\n}\n}\nreturn *this;\n}\nDrawableObject& DrawableObject::set_transparent(bool transparent)\n{\n_isTransparent = transparent;\nreturn *this;\n}\nDrawableObject& DrawableObject::set_color_shader(std::reference_wrapper<gs::PhongMultiLight> shader)\n{\n_color_shader = shader;\nreturn *this;\n}\nDrawableObject& DrawableObject::set_texture_shader(std::reference_wrapper<gs::PhongMultiLight> shader)\n{\n_texture_shader = shader;\nreturn *this;\n}\nvoid DrawableObject::draw(const Magnum::Matrix4& transformationMatrix, Magnum::SceneGraph::Camera3D& camera)\n{\nfor (size_t i = 0; i < _meshes.size(); i++) {\nMagnum::GL::Mesh& mesh = _meshes[i];\nMagnum::Matrix4 scalingMatrix = Magnum::Matrix4::scaling(_scalings[i]);\nbool isColor = !_materials[i].has_diffuse_texture();\nif (_is_soft_body[i])\nMagnum::GL::Renderer::disable(Magnum::GL::Renderer::Feature::FaceCulling);\nelse if (_has_negative_scaling[i])\nMagnum::GL::Renderer::setFaceCullingMode(Magnum::GL::Renderer::PolygonFacing::Front);\nif (isColor) {\n_color_shader.get()\n.set_material(_materials[i])\n.set_transformation_matrix(absoluteTransformationMatrix() * scalingMatrix)\n.set_normal_matrix((transformationMatrix * scalingMatrix).rotationScaling())\n.set_camera_matrix(camera.cameraMatrix())\n.set_projection_matrix(camera.projectionMatrix())\n.draw(mesh);\n}\nelse {\n_texture_shader.get()\n.set_material(_materials[i])\n.set_transformation_matrix(absoluteTransformationMatrix() * scalingMatrix)\n.set_normal_matrix((transformationMatrix * scalingMatrix).rotationScaling())\n.set_camera_matrix(camera.cameraMatrix())\n.set_projection_matrix(camera.projectionMatrix())\n.draw(mesh);\n}\nif (_is_soft_body[i])\nMagnum::GL::Renderer::enable(Magnum::GL::Renderer::Feature::FaceCulling);\nelse if (_has_negative_scaling[i])\nMagnum::GL::Renderer::setFaceCullingMode(Magnum::GL::Renderer::PolygonFacing::Back);\n}\n}\n// ShadowedObject\nShadowedObject::ShadowedObject(\nRobotDARTSimu* simu,\ndart::dynamics::ShapeNode* shape,\nconst std::vector<std::reference_wrapper<Magnum::GL::Mesh>>& meshes,\ngs::ShadowMap& shader,\ngs::ShadowMap& texture_shader,\nObject3D* parent,\nMagnum::SceneGraph::DrawableGroup3D* group)\n: Object3D{parent},\nMagnum::SceneGraph::Drawable3D{*this, group},\n_simu(simu),\n_shape(shape),\n_meshes{meshes},\n_shader{shader},\n_texture_shader(texture_shader) {}\nShadowedObject& ShadowedObject::set_meshes(const std::vector<std::reference_wrapper<Magnum::GL::Mesh>>& meshes)\n{\n_meshes = meshes;\nreturn *this;\n}\nShadowedObject& ShadowedObject::set_materials(const std::vector<gs::Material>& materials)\n{\n_materials = materials;\nreturn *this;\n}\nShadowedObject& ShadowedObject::set_scalings(const std::vector<Magnum::Vector3>& scalings)\n{\n_scalings = scalings;\nreturn *this;\n}\nvoid ShadowedObject::draw(const Magnum::Matrix4& transformationMatrix, Magnum::SceneGraph::Camera3D& camera)\n{\nif (!_simu->gui_data()->cast_shadows(_shape))\nreturn;\nfor (size_t i = 0; i < _meshes.size(); i++) {\nMagnum::GL::Mesh& mesh = _meshes[i];\nMagnum::Matrix4 scalingMatrix = Magnum::Matrix4::scaling(_scalings[i]);\nbool isColor = !_materials[i].has_diffuse_texture();\nif (isColor) {\n(_shader.get())\n.set_transformation_matrix(transformationMatrix * scalingMatrix)\n.set_projection_matrix(camera.projectionMatrix())\n.set_material(_materials[i])\n.draw(mesh);\n}\nelse {\n(_texture_shader.get())\n.set_transformation_matrix(transformationMatrix * scalingMatrix)\n.set_projection_matrix(camera.projectionMatrix())\n.set_material(_materials[i])\n.draw(mesh);\n}\n}\n}\n// ShadowedColorObject\nShadowedColorObject::ShadowedColorObject(\nRobotDARTSimu* simu,\ndart::dynamics::ShapeNode* shape,\nconst std::vector<std::reference_wrapper<Magnum::GL::Mesh>>& meshes,\ngs::ShadowMapColor& shader,\ngs::ShadowMapColor& texture_shader,\nObject3D* parent,\nMagnum::SceneGraph::DrawableGroup3D* group)\n: Object3D{parent},\nMagnum::SceneGraph::Drawable3D{*this, group},\n_simu(simu),\n_shape(shape),\n_meshes{meshes},\n_shader{shader},\n_texture_shader(texture_shader) {}\nShadowedColorObject& ShadowedColorObject::set_meshes(const std::vector<std::reference_wrapper<Magnum::GL::Mesh>>& meshes)\n{\n_meshes = meshes;\nreturn *this;\n}\nShadowedColorObject& ShadowedColorObject::set_materials(const std::vector<gs::Material>& materials)\n{\n_materials = materials;\nreturn *this;\n}\nShadowedColorObject& ShadowedColorObject::set_scalings(const std::vector<Magnum::Vector3>& scalings)\n{\n_scalings = scalings;\nreturn *this;\n}\nvoid ShadowedColorObject::draw(const Magnum::Matrix4& transformationMatrix, Magnum::SceneGraph::Camera3D& camera)\n{\nif (!_simu->gui_data()->cast_shadows(_shape))\nreturn;\nfor (size_t i = 0; i < _meshes.size(); i++) {\nMagnum::GL::Mesh& mesh = _meshes[i];\nMagnum::Matrix4 scalingMatrix = Magnum::Matrix4::scaling(_scalings[i]);\nbool isColor = !_materials[i].has_diffuse_texture();\nif (isColor) {\n(_shader.get())\n.set_transformation_matrix(transformationMatrix * scalingMatrix)\n.set_projection_matrix(camera.projectionMatrix())\n.set_material(_materials[i])\n.draw(mesh);\n}\nelse {\n(_texture_shader.get())\n.set_transformation_matrix(transformationMatrix * scalingMatrix)\n.set_projection_matrix(camera.projectionMatrix())\n.set_material(_materials[i])\n.draw(mesh);\n}\n}\n}\n// CubeMapShadowedObject\nCubeMapShadowedObject::CubeMapShadowedObject(\nRobotDARTSimu* simu,\ndart::dynamics::ShapeNode* shape,\nconst std::vector<std::reference_wrapper<Magnum::GL::Mesh>>& meshes,\ngs::CubeMap& shader,\ngs::CubeMap& texture_shader,\nObject3D* parent,\nMagnum::SceneGraph::DrawableGroup3D* group)\n: Object3D{parent},\nMagnum::SceneGraph::Drawable3D{*this, group},\n_simu(simu),\n_shape(shape),\n_meshes{meshes},\n_shader{shader},\n_texture_shader(texture_shader) {}\nCubeMapShadowedObject& CubeMapShadowedObject::set_meshes(const std::vector<std::reference_wrapper<Magnum::GL::Mesh>>& meshes)\n{\n_meshes = meshes;\nreturn *this;\n}\nCubeMapShadowedObject& CubeMapShadowedObject::set_materials(const std::vector<gs::Material>& materials)\n{\n_materials = materials;\nreturn *this;\n}\nCubeMapShadowedObject& CubeMapShadowedObject::set_scalings(const std::vector<Magnum::Vector3>& scalings)\n{\n_scalings = scalings;\nreturn *this;\n}\nvoid CubeMapShadowedObject::draw(const Magnum::Matrix4&, Magnum::SceneGraph::Camera3D&)\n{\nfor (size_t i = 0; i < _meshes.size(); i++) {\nMagnum::GL::Mesh& mesh = _meshes[i];\nMagnum::Matrix4 scalingMatrix = Magnum::Matrix4::scaling(_scalings[i]);\nbool isColor = !_materials[i].has_diffuse_texture();\nif (isColor) {\n(_shader.get())\n.set_transformation_matrix(absoluteTransformation() * scalingMatrix)\n.set_material(_materials[i])\n.draw(mesh);\n}\nelse {\n(_texture_shader.get())\n.set_transformation_matrix(absoluteTransformation() * scalingMatrix)\n.set_material(_materials[i])\n.draw(mesh);\n}\n}\n}\n// CubeMapShadowedColorObject\nCubeMapShadowedColorObject::CubeMapShadowedColorObject(\nRobotDARTSimu* simu,\ndart::dynamics::ShapeNode* shape,\nconst std::vector<std::reference_wrapper<Magnum::GL::Mesh>>& meshes,\ngs::CubeMapColor& shader,\ngs::CubeMapColor& texture_shader,\nObject3D* parent,\nMagnum::SceneGraph::DrawableGroup3D* group)\n: Object3D{parent},\nMagnum::SceneGraph::Drawable3D{*this, group},\n_simu(simu),\n_shape(shape),\n_meshes{meshes},\n_shader{shader},\n_texture_shader(texture_shader) {}\nCubeMapShadowedColorObject& CubeMapShadowedColorObject::set_meshes(const std::vector<std::reference_wrapper<Magnum::GL::Mesh>>& meshes)\n{\n_meshes = meshes;\nreturn *this;\n}\nCubeMapShadowedColorObject& CubeMapShadowedColorObject::set_materials(const std::vector<gs::Material>& materials)\n{\n_materials = materials;\nreturn *this;\n}\nCubeMapShadowedColorObject& CubeMapShadowedColorObject::set_scalings(const std::vector<Magnum::Vector3>& scalings)\n{\n_scalings = scalings;\nreturn *this;\n}\nvoid CubeMapShadowedColorObject::draw(const Magnum::Matrix4&, Magnum::SceneGraph::Camera3D&)\n{\nif (!_simu->gui_data()->cast_shadows(_shape))\nreturn;\nfor (size_t i = 0; i < _meshes.size(); i++) {\nMagnum::GL::Mesh& mesh = _meshes[i];\nMagnum::Matrix4 scalingMatrix = Magnum::Matrix4::scaling(_scalings[i]);\nbool isColor = !_materials[i].has_diffuse_texture();\nif (isColor) {\n(_shader.get())\n.set_transformation_matrix(absoluteTransformation() * scalingMatrix)\n.set_material(_materials[i])\n.draw(mesh);\n}\nelse {\n(_texture_shader.get())\n.set_transformation_matrix(absoluteTransformation() * scalingMatrix)\n.set_material(_materials[i])\n.draw(mesh);\n}\n}\n}\n} // namespace magnum\n} // namespace gui\n} // namespace robot_dart\n
"},{"location":"api/drawables_8hpp/","title":"File drawables.hpp","text":"

FileList > gui > magnum > drawables.hpp

Go to the source code of this file

"},{"location":"api/drawables_8hpp/#namespaces","title":"Namespaces","text":"Type Name namespace dart namespace dynamics namespace robot_dart namespace gui namespace magnum"},{"location":"api/drawables_8hpp/#classes","title":"Classes","text":"Type Name class CubeMapShadowedColorObject class CubeMapShadowedObject class DrawableObject struct ObjectStruct struct ShadowData class ShadowedColorObject class ShadowedObject

The documentation for this class was generated from the following file robot_dart/gui/magnum/drawables.hpp

"},{"location":"api/drawables_8hpp_source/","title":"File drawables.hpp","text":"

File List > gui > magnum > drawables.hpp

Go to the documentation of this file

#ifndef ROBOT_DART_GUI_MAGNUM_DRAWABLES_HPP\n#define ROBOT_DART_GUI_MAGNUM_DRAWABLES_HPP\n#include <robot_dart/gui/helper.hpp>\n#include <robot_dart/gui/magnum/gs/cube_map.hpp>\n#include <robot_dart/gui/magnum/gs/cube_map_color.hpp>\n#include <robot_dart/gui/magnum/gs/phong_multi_light.hpp>\n#include <robot_dart/gui/magnum/gs/shadow_map.hpp>\n#include <robot_dart/gui/magnum/gs/shadow_map_color.hpp>\n#include <robot_dart/gui/magnum/types.hpp>\n#include <Magnum/GL/Framebuffer.h>\n#include <Magnum/SceneGraph/Drawable.h>\nnamespace dart {\nnamespace dynamics {\nclass ShapeNode;\n}\n} // namespace dart\nnamespace robot_dart {\nclass RobotDARTSimu;\nnamespace gui {\nnamespace magnum {\nclass DrawableObject : public Object3D, public Magnum::SceneGraph::Drawable3D {\npublic:\nexplicit DrawableObject(\nRobotDARTSimu* simu,\ndart::dynamics::ShapeNode* shape,\nconst std::vector<std::reference_wrapper<Magnum::GL::Mesh>>& meshes,\nconst std::vector<gs::Material>& materials,\ngs::PhongMultiLight& color,\ngs::PhongMultiLight& texture,\nObject3D* parent,\nMagnum::SceneGraph::DrawableGroup3D* group);\nDrawableObject& set_meshes(const std::vector<std::reference_wrapper<Magnum::GL::Mesh>>& meshes);\nDrawableObject& set_materials(const std::vector<gs::Material>& materials);\nDrawableObject& set_soft_bodies(const std::vector<bool>& softBody);\nDrawableObject& set_scalings(const std::vector<Magnum::Vector3>& scalings);\nDrawableObject& set_transparent(bool transparent = true);\nDrawableObject& set_color_shader(std::reference_wrapper<gs::PhongMultiLight> shader);\nDrawableObject& set_texture_shader(std::reference_wrapper<gs::PhongMultiLight> shader);\nconst std::vector<gs::Material>& materials() const { return _materials; }\nbool transparent() const { return _isTransparent; }\nRobotDARTSimu* simu() const { return _simu; }\ndart::dynamics::ShapeNode* shape() const { return _shape; }\nprivate:\nvoid draw(const Magnum::Matrix4& transformationMatrix, Magnum::SceneGraph::Camera3D& camera) override;\nRobotDARTSimu* _simu;\ndart::dynamics::ShapeNode* _shape;\nstd::vector<std::reference_wrapper<Magnum::GL::Mesh>> _meshes;\nstd::reference_wrapper<gs::PhongMultiLight> _color_shader;\nstd::reference_wrapper<gs::PhongMultiLight> _texture_shader;\nstd::vector<gs::Material> _materials;\nstd::vector<Magnum::Vector3> _scalings;\nstd::vector<bool> _has_negative_scaling;\nstd::vector<bool> _is_soft_body;\nbool _isTransparent;\n};\nclass ShadowedObject : public Object3D, public Magnum::SceneGraph::Drawable3D {\npublic:\nexplicit ShadowedObject(\nRobotDARTSimu* simu,\ndart::dynamics::ShapeNode* shape,\nconst std::vector<std::reference_wrapper<Magnum::GL::Mesh>>& meshes,\ngs::ShadowMap& shader,\ngs::ShadowMap& texture_shader,\nObject3D* parent,\nMagnum::SceneGraph::DrawableGroup3D* group);\nShadowedObject& set_meshes(const std::vector<std::reference_wrapper<Magnum::GL::Mesh>>& meshes);\nShadowedObject& set_materials(const std::vector<gs::Material>& materials);\nShadowedObject& set_scalings(const std::vector<Magnum::Vector3>& scalings);\nRobotDARTSimu* simu() const { return _simu; }\ndart::dynamics::ShapeNode* shape() const { return _shape; }\nprivate:\nvoid draw(const Magnum::Matrix4& transformationMatrix, Magnum::SceneGraph::Camera3D& camera) override;\nRobotDARTSimu* _simu;\ndart::dynamics::ShapeNode* _shape;\nstd::vector<std::reference_wrapper<Magnum::GL::Mesh>> _meshes;\nstd::reference_wrapper<gs::ShadowMap> _shader, _texture_shader;\nstd::vector<gs::Material> _materials;\nstd::vector<Magnum::Vector3> _scalings;\n};\nclass ShadowedColorObject : public Object3D, public Magnum::SceneGraph::Drawable3D {\npublic:\nexplicit ShadowedColorObject(\nRobotDARTSimu* simu,\ndart::dynamics::ShapeNode* shape,\nconst std::vector<std::reference_wrapper<Magnum::GL::Mesh>>& meshes,\ngs::ShadowMapColor& shader,\ngs::ShadowMapColor& texture_shader,\nObject3D* parent,\nMagnum::SceneGraph::DrawableGroup3D* group);\nShadowedColorObject& set_meshes(const std::vector<std::reference_wrapper<Magnum::GL::Mesh>>& meshes);\nShadowedColorObject& set_materials(const std::vector<gs::Material>& materials);\nShadowedColorObject& set_scalings(const std::vector<Magnum::Vector3>& scalings);\nRobotDARTSimu* simu() const { return _simu; }\ndart::dynamics::ShapeNode* shape() const { return _shape; }\nprivate:\nvoid draw(const Magnum::Matrix4& transformationMatrix, Magnum::SceneGraph::Camera3D& camera) override;\nRobotDARTSimu* _simu;\ndart::dynamics::ShapeNode* _shape;\nstd::vector<std::reference_wrapper<Magnum::GL::Mesh>> _meshes;\nstd::reference_wrapper<gs::ShadowMapColor> _shader, _texture_shader;\nstd::vector<gs::Material> _materials;\nstd::vector<Magnum::Vector3> _scalings;\n};\nclass CubeMapShadowedObject : public Object3D, public Magnum::SceneGraph::Drawable3D {\npublic:\nexplicit CubeMapShadowedObject(\nRobotDARTSimu* simu,\ndart::dynamics::ShapeNode* shape,\nconst std::vector<std::reference_wrapper<Magnum::GL::Mesh>>& meshes,\ngs::CubeMap& shader,\ngs::CubeMap& texture_shader,\nObject3D* parent,\nMagnum::SceneGraph::DrawableGroup3D* group);\nCubeMapShadowedObject& set_meshes(const std::vector<std::reference_wrapper<Magnum::GL::Mesh>>& meshes);\nCubeMapShadowedObject& set_materials(const std::vector<gs::Material>& materials);\nCubeMapShadowedObject& set_scalings(const std::vector<Magnum::Vector3>& scalings);\nRobotDARTSimu* simu() const { return _simu; }\ndart::dynamics::ShapeNode* shape() const { return _shape; }\nprivate:\nvoid draw(const Magnum::Matrix4& transformationMatrix, Magnum::SceneGraph::Camera3D& camera) override;\nRobotDARTSimu* _simu;\ndart::dynamics::ShapeNode* _shape;\nstd::vector<std::reference_wrapper<Magnum::GL::Mesh>> _meshes;\nstd::reference_wrapper<gs::CubeMap> _shader, _texture_shader;\nstd::vector<gs::Material> _materials;\nstd::vector<Magnum::Vector3> _scalings;\n};\nclass CubeMapShadowedColorObject : public Object3D, public Magnum::SceneGraph::Drawable3D {\npublic:\nexplicit CubeMapShadowedColorObject(\nRobotDARTSimu* simu,\ndart::dynamics::ShapeNode* shape,\nconst std::vector<std::reference_wrapper<Magnum::GL::Mesh>>& meshes,\ngs::CubeMapColor& shader,\ngs::CubeMapColor& texture_shader,\nObject3D* parent,\nMagnum::SceneGraph::DrawableGroup3D* group);\nCubeMapShadowedColorObject& set_meshes(const std::vector<std::reference_wrapper<Magnum::GL::Mesh>>& meshes);\nCubeMapShadowedColorObject& set_materials(const std::vector<gs::Material>& materials);\nCubeMapShadowedColorObject& set_scalings(const std::vector<Magnum::Vector3>& scalings);\nRobotDARTSimu* simu() const { return _simu; }\ndart::dynamics::ShapeNode* shape() const { return _shape; }\nprivate:\nvoid draw(const Magnum::Matrix4& transformationMatrix, Magnum::SceneGraph::Camera3D& camera) override;\nRobotDARTSimu* _simu;\ndart::dynamics::ShapeNode* _shape;\nstd::vector<std::reference_wrapper<Magnum::GL::Mesh>> _meshes;\nstd::reference_wrapper<gs::CubeMapColor> _shader, _texture_shader;\nstd::vector<gs::Material> _materials;\nstd::vector<Magnum::Vector3> _scalings;\n};\nstruct ShadowData {\nMagnum::GL::Framebuffer shadow_framebuffer{Magnum::NoCreate};\nMagnum::GL::Framebuffer shadow_color_framebuffer{Magnum::NoCreate};\n};\nstruct ObjectStruct {\nDrawableObject* drawable;\nShadowedObject* shadowed;\nShadowedColorObject* shadowed_color;\nCubeMapShadowedObject* cubemapped;\nCubeMapShadowedColorObject* cubemapped_color;\n};\n} // namespace magnum\n} // namespace gui\n} // namespace robot_dart\n#endif\n
"},{"location":"api/glfw__application_8cpp/","title":"File glfw_application.cpp","text":"

FileList > gui > magnum > glfw_application.cpp

Go to the source code of this file

"},{"location":"api/glfw__application_8cpp/#namespaces","title":"Namespaces","text":"Type Name namespace robot_dart namespace gui namespace magnum

The documentation for this class was generated from the following file robot_dart/gui/magnum/glfw_application.cpp

"},{"location":"api/glfw__application_8cpp_source/","title":"Macro Syntax Error","text":"

Line 69 in Markdown file: unexpected '}'

                Magnum::GL::defaultFramebuffer.setViewport({{}, event.framebufferSize()});\n

"},{"location":"api/glfw__application_8hpp/","title":"File glfw_application.hpp","text":"

FileList > gui > magnum > glfw_application.hpp

Go to the source code of this file

"},{"location":"api/glfw__application_8hpp/#namespaces","title":"Namespaces","text":"Type Name namespace robot_dart namespace gui namespace magnum"},{"location":"api/glfw__application_8hpp/#classes","title":"Classes","text":"Type Name class GlfwApplication

The documentation for this class was generated from the following file robot_dart/gui/magnum/glfw_application.hpp

"},{"location":"api/glfw__application_8hpp_source/","title":"File glfw_application.hpp","text":"

File List > gui > magnum > glfw_application.hpp

Go to the documentation of this file

#ifndef ROBOT_DART_GUI_MAGNUM_GLFW_APPLICATION_HPP\n#define ROBOT_DART_GUI_MAGNUM_GLFW_APPLICATION_HPP\n#include <robot_dart/gui/magnum/base_application.hpp>\n// Workaround for X11lib defines\n#undef Button1\n#undef Button2\n#undef Button3\n#undef Button4\n#undef Button5\n#include <Magnum/Platform/GlfwApplication.h>\nnamespace robot_dart {\nnamespace gui {\nnamespace magnum {\nclass GlfwApplication : public BaseApplication, public Magnum::Platform::Application {\npublic:\nexplicit GlfwApplication(int argc, char** argv, RobotDARTSimu* simu, const GraphicsConfiguration& configuration = GraphicsConfiguration());\n~GlfwApplication();\nvoid render() override;\nprotected:\nRobotDARTSimu* _simu;\nMagnum::Float _speed_move, _speed_strafe;\nbool _draw_main_camera, _draw_debug;\nMagnum::Color4 _bg_color;\nstatic constexpr Magnum::Float _speed = 0.05f;\nvoid viewportEvent(ViewportEvent& event) override;\nvoid drawEvent() override;\nvirtual void keyReleaseEvent(KeyEvent& event) override;\nvirtual void keyPressEvent(KeyEvent& event) override;\nvirtual void mouseScrollEvent(MouseScrollEvent& event) override;\nvirtual void mouseMoveEvent(MouseMoveEvent& event) override;\nvoid exitEvent(ExitEvent& event) override;\n};\n} // namespace magnum\n} // namespace gui\n} // namespace robot_dart\n#endif\n
"},{"location":"api/graphics_8cpp/","title":"File graphics.cpp","text":"

FileList > gui > magnum > graphics.cpp

Go to the source code of this file

"},{"location":"api/graphics_8cpp/#namespaces","title":"Namespaces","text":"Type Name namespace robot_dart namespace gui namespace magnum

The documentation for this class was generated from the following file robot_dart/gui/magnum/graphics.cpp

"},{"location":"api/graphics_8cpp_source/","title":"File graphics.cpp","text":"

File List > gui > magnum > graphics.cpp

Go to the documentation of this file

#include <robot_dart/gui/magnum/graphics.hpp>\nnamespace robot_dart {\nnamespace gui {\nnamespace magnum {\nvoid Graphics::set_simu(RobotDARTSimu* simu)\n{\nBaseGraphics<GlfwApplication>::set_simu(simu);\n// we synchronize by default if we have the graphics activated\nsimu->scheduler().set_sync(true);\n// enable summary text when graphics activated\nsimu->enable_text_panel(true);\nsimu->enable_status_bar(true);\n}\nGraphicsConfiguration Graphics::default_configuration()\n{\nreturn GraphicsConfiguration();\n}\n} // namespace magnum\n} // namespace gui\n} // namespace robot_dart\n
"},{"location":"api/graphics_8hpp/","title":"File graphics.hpp","text":"

FileList > gui > magnum > graphics.hpp

Go to the source code of this file

"},{"location":"api/graphics_8hpp/#namespaces","title":"Namespaces","text":"Type Name namespace robot_dart namespace gui namespace magnum"},{"location":"api/graphics_8hpp/#classes","title":"Classes","text":"Type Name class Graphics

The documentation for this class was generated from the following file robot_dart/gui/magnum/graphics.hpp

"},{"location":"api/graphics_8hpp_source/","title":"File graphics.hpp","text":"

File List > gui > magnum > graphics.hpp

Go to the documentation of this file

#ifndef ROBOT_DART_GUI_MAGNUM_GRAPHICS_HPP\n#define ROBOT_DART_GUI_MAGNUM_GRAPHICS_HPP\n#include <robot_dart/gui/magnum/base_graphics.hpp>\nnamespace robot_dart {\nnamespace gui {\nnamespace magnum {\nclass Graphics : public BaseGraphics<GlfwApplication> {\npublic:\nGraphics(const GraphicsConfiguration& configuration = default_configuration()) : BaseGraphics<GlfwApplication>(configuration) {}\n~Graphics() {}\nvoid set_simu(RobotDARTSimu* simu) override;\nstatic GraphicsConfiguration default_configuration();\n};\n} // namespace magnum\n} // namespace gui\n} // namespace robot_dart\n#endif\n
"},{"location":"api/dir_2f8612d80f6bb57c97efd4c82e0df286/","title":"Dir robot_dart/gui/magnum/gs","text":"

FileList > gs

"},{"location":"api/dir_2f8612d80f6bb57c97efd4c82e0df286/#files","title":"Files","text":"Type Name file camera.cpp file camera.hpp file create_compatibility_shader.hpp file cube_map.cpp file cube_map.hpp file cube_map_color.cpp file cube_map_color.hpp file helper.cpp file helper.hpp file light.cpp file light.hpp file material.cpp file material.hpp file phong_multi_light.cpp file phong_multi_light.hpp file shadow_map.cpp file shadow_map.hpp file shadow_map_color.cpp file shadow_map_color.hpp

The documentation for this class was generated from the following file robot_dart/gui/magnum/gs/

"},{"location":"api/gs_2camera_8cpp/","title":"File camera.cpp","text":"

FileList > gs > camera.cpp

Go to the source code of this file

"},{"location":"api/gs_2camera_8cpp/#namespaces","title":"Namespaces","text":"Type Name namespace robot_dart namespace gui namespace magnum namespace gs

The documentation for this class was generated from the following file robot_dart/gui/magnum/gs/camera.cpp

"},{"location":"api/gs_2camera_8cpp_source/","title":"Macro Syntax Error","text":"

Line 204 in Markdown file: expected name or number

                    return {{projection[0][0], 0., 0.},\n

"},{"location":"api/gs_2camera_8hpp/","title":"File camera.hpp","text":"

FileList > gs > camera.hpp

Go to the source code of this file

"},{"location":"api/gs_2camera_8hpp/#namespaces","title":"Namespaces","text":"Type Name namespace robot_dart namespace gui namespace magnum namespace gs namespace subprocess"},{"location":"api/gs_2camera_8hpp/#classes","title":"Classes","text":"Type Name class Camera

The documentation for this class was generated from the following file robot_dart/gui/magnum/gs/camera.hpp

"},{"location":"api/gs_2camera_8hpp_source/","title":"File camera.hpp","text":"

File List > gs > camera.hpp

Go to the documentation of this file

#ifndef ROBOT_DART_GUI_MAGNUM_GS_CAMERA_HPP\n#define ROBOT_DART_GUI_MAGNUM_GS_CAMERA_HPP\n#include <robot_dart/gui/magnum/gs/light.hpp>\n#include <robot_dart/gui/magnum/types.hpp>\n#include <robot_dart/robot_dart_simu.hpp>\n#include <Corrade/Containers/Optional.h>\n#include <Magnum/GL/Mesh.h>\n#include <Magnum/Image.h>\n#include <Magnum/Shaders/DistanceFieldVector.h>\n#include <Magnum/Shaders/VertexColor.h>\n#include <Magnum/Text/Renderer.h>\nnamespace subprocess {\nclass popen;\n}\nnamespace robot_dart {\nnamespace gui {\nnamespace magnum {\nstruct DebugDrawData;\nnamespace gs {\n// This is partly code from the ThirdPersonCameraController of https://github.com/alexesDev/magnum-tips\nclass Camera : public Object3D {\npublic:\nexplicit Camera(Object3D& object, Magnum::Int width, Magnum::Int height);\n~Camera();\nCamera3D& camera() const;\nObject3D& root_object();\nObject3D& camera_object() const;\nCamera& set_viewport(const Magnum::Vector2i& size);\nCamera& move(const Magnum::Vector2i& shift);\nCamera& forward(Magnum::Float speed);\nCamera& strafe(Magnum::Float speed);\nCamera& set_speed(const Magnum::Vector2& speed);\nCamera& set_near_plane(Magnum::Float near_plane);\nCamera& set_far_plane(Magnum::Float far_plane);\nCamera& set_fov(Magnum::Float fov);\nCamera& set_camera_params(Magnum::Float near_plane, Magnum::Float far_plane, Magnum::Float fov, Magnum::Int width, Magnum::Int height);\nMagnum::Vector2 speed() const { return _speed; }\nMagnum::Float near_plane() const { return _near_plane; }\nMagnum::Float far_plane() const { return _far_plane; }\nMagnum::Float fov() const { return static_cast<Magnum::Float>(_fov); }\nMagnum::Int width() const { return _camera->viewport()[0]; }\nMagnum::Int height() const { return _camera->viewport()[1]; }\nMagnum::Matrix3 intrinsic_matrix() const;\nMagnum::Matrix4 extrinsic_matrix() const;\nCamera& look_at(const Magnum::Vector3& camera, const Magnum::Vector3& center, const Magnum::Vector3& up = Magnum::Vector3::zAxis());\nvoid transform_lights(std::vector<gs::Light>& lights) const;\nvoid record(bool recording, bool recording_depth = false)\n{\n_recording = recording;\n_recording_depth = recording_depth;\n}\n// FPS is mandatory here (compared to Graphics and CameraOSR)\nvoid record_video(const std::string& video_fname, int fps);\nbool recording() { return _recording; }\nbool recording_depth() { return _recording_depth; }\nCorrade::Containers::Optional<Magnum::Image2D>& image() { return _image; }\nCorrade::Containers::Optional<Magnum::Image2D>& depth_image() { return _depth_image; }\nvoid draw(Magnum::SceneGraph::DrawableGroup3D& drawables, Magnum::GL::AbstractFramebuffer& framebuffer, Magnum::PixelFormat format, RobotDARTSimu* simu, const DebugDrawData& debug_data, bool draw_debug = true);\nprivate:\nObject3D* _yaw_object;\nObject3D* _pitch_object;\nObject3D* _camera_object;\nCamera3D* _camera;\nMagnum::Vector2 _speed{-0.01f, 0.01f};\nMagnum::Vector3 _up, _front, _right;\nMagnum::Float _aspect_ratio, _near_plane, _far_plane;\nMagnum::Rad _fov;\nMagnum::Int _width, _height;\nbool _recording = false, _recording_depth = false;\nbool _recording_video = false;\nCorrade::Containers::Optional<Magnum::Image2D> _image, _depth_image;\nsubprocess::popen* _ffmpeg_process = nullptr;\nvoid _clean_up_subprocess();\n};\n} // namespace gs\n} // namespace magnum\n} // namespace gui\n} // namespace robot_dart\n#endif\n
"},{"location":"api/create__compatibility__shader_8hpp/","title":"File create_compatibility_shader.hpp","text":"

FileList > gs > create_compatibility_shader.hpp

Go to the source code of this file

"},{"location":"api/create__compatibility__shader_8hpp/#namespaces","title":"Namespaces","text":"Type Name namespace Magnum namespace Shaders namespace Implementation namespace robot_dart namespace gui namespace magnum namespace gs

The documentation for this class was generated from the following file robot_dart/gui/magnum/gs/create_compatibility_shader.hpp

"},{"location":"api/create__compatibility__shader_8hpp_source/","title":"File create_compatibility_shader.hpp","text":"

File List > gs > create_compatibility_shader.hpp

Go to the documentation of this file

#ifndef Magnum_Shaders_Implementation_CreateCompatibilityShader_h\n#define Magnum_Shaders_Implementation_CreateCompatibilityShader_h\n/*\n    This file is part of Magnum.\n    Copyright \u00a9 2010, 2011, 2012, 2013, 2014, 2015, 2016, 2017, 2018\n              Vladim\u00edr Vondru\u0161 <mosra@centrum.cz>\n    Permission is hereby granted, free of charge, to any person obtaining a\n    copy of this software and associated documentation files (the \"Software\"),\n    to deal in the Software without restriction, including without limitation\n    the rights to use, copy, modify, merge, publish, distribute, sublicense,\n    and/or sell copies of the Software, and to permit persons to whom the\n    Software is furnished to do so, subject to the following conditions:\n    The above copyright notice and this permission notice shall be included\n    in all copies or substantial portions of the Software.\n    THE SOFTWARE IS PROVIDED \"AS IS\", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR\n    IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,\n    FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL\n    THE AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER\n    LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING\n    FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER\n    DEALINGS IN THE SOFTWARE.\n*/\n#include <Corrade/Utility/Resource.h>\n#include <Magnum/GL/Context.h>\n#include <Magnum/GL/Extensions.h>\n#include <Magnum/GL/Shader.h>\n#include <string>\nnamespace robot_dart {\nnamespace gui {\nnamespace magnum {\nnamespace gs {\nnamespace {\nenum : Magnum::Int { AmbientTextureLayer = 0,\nDiffuseTextureLayer = 1,\nSpecularTextureLayer = 2 };\n}\n} // namespace gs\n} // namespace magnum\n} // namespace gui\n} // namespace robot_dart\nnamespace Magnum {\nnamespace Shaders {\nnamespace Implementation {\ninline GL::Shader createCompatibilityShader(const Utility::Resource& rs, GL::Version version, GL::Shader::Type type)\n{\nGL::Shader shader(version, type);\n#ifndef MAGNUM_TARGET_GLES\nif (GL::Context::current().isExtensionDisabled<GL::Extensions::ARB::explicit_attrib_location>(version))\nshader.addSource(\"#define DISABLE_GL_ARB_explicit_attrib_location\\n\");\nif (GL::Context::current().isExtensionDisabled<GL::Extensions::ARB::shading_language_420pack>(version))\nshader.addSource(\"#define DISABLE_GL_ARB_shading_language_420pack\\n\");\nif (GL::Context::current().isExtensionDisabled<GL::Extensions::ARB::explicit_uniform_location>(version))\nshader.addSource(\"#define DISABLE_GL_ARB_explicit_uniform_location\\n\");\n#endif\n#ifndef MAGNUM_TARGET_GLES2\nif (type == GL::Shader::Type::Vertex && GL::Context::current().isExtensionDisabled<GL::Extensions::MAGNUM::shader_vertex_id>(version))\nshader.addSource(\"#define DISABLE_GL_MAGNUM_shader_vertex_id\\n\");\n#endif\n/* My Android emulator (running on NVidia) doesn't define GL_ES\n       preprocessor macro, thus *all* the stock shaders fail to compile */\n#ifdef CORRADE_TARGET_ANDROID\nshader.addSource(\"#ifndef GL_ES\\n#define GL_ES 1\\n#endif\\n\");\n#endif\nshader.addSource(rs.get(\"compatibility.glsl\"));\nreturn shader;\n}\n} // namespace Implementation\n} // namespace Shaders\n} // namespace Magnum\n#endif\n
"},{"location":"api/cube__map_8cpp/","title":"File cube_map.cpp","text":"

FileList > gs > cube_map.cpp

Go to the source code of this file

"},{"location":"api/cube__map_8cpp/#namespaces","title":"Namespaces","text":"Type Name namespace robot_dart namespace gui namespace magnum namespace gs

The documentation for this class was generated from the following file robot_dart/gui/magnum/gs/cube_map.cpp

"},{"location":"api/cube__map_8cpp_source/","title":"File cube_map.cpp","text":"

File List > gs > cube_map.cpp

Go to the documentation of this file

#include \"cube_map.hpp\"\n#include \"create_compatibility_shader.hpp\"\n#include <Magnum/GL/Texture.h>\nnamespace robot_dart {\nnamespace gui {\nnamespace magnum {\nnamespace gs {\nCubeMap::CubeMap(CubeMap::Flags flags) : _flags(flags)\n{\nCorrade::Utility::Resource rs_shaders(\"RobotDARTShaders\");\nconst Magnum::GL::Version version = Magnum::GL::Version::GL320;\nMagnum::GL::Shader vert = Magnum::Shaders::Implementation::createCompatibilityShader(\nrs_shaders, version, Magnum::GL::Shader::Type::Vertex);\nMagnum::GL::Shader geom = Magnum::Shaders::Implementation::createCompatibilityShader(\nrs_shaders, version, Magnum::GL::Shader::Type::Geometry);\nMagnum::GL::Shader frag = Magnum::Shaders::Implementation::createCompatibilityShader(\nrs_shaders, version, Magnum::GL::Shader::Type::Fragment);\nstd::string defines = \"#define POSITION_ATTRIBUTE_LOCATION \" + std::to_string(Position::Location) + \"\\n\";\ndefines += \"#define TEXTURECOORDINATES_ATTRIBUTE_LOCATION \" + std::to_string(TextureCoordinates::Location) + \"\\n\";\nvert.addSource(flags ? \"#define TEXTURED\\n\" : \"\")\n.addSource(defines)\n.addSource(rs_shaders.get(\"CubeMap.vert\"));\ngeom.addSource(flags ? \"#define TEXTURED\\n\" : \"\")\n.addSource(rs_shaders.get(\"CubeMap.geom\"));\nfrag.addSource(flags ? \"#define TEXTURED\\n\" : \"\")\n.addSource(rs_shaders.get(\"CubeMap.frag\"));\nCORRADE_INTERNAL_ASSERT_OUTPUT(Magnum::GL::Shader::compile({vert, geom, frag}));\nattachShaders({vert, geom, frag});\nif (!Magnum::GL::Context::current().isExtensionSupported<Magnum::GL::Extensions::ARB::explicit_attrib_location>(version)) {\nbindAttributeLocation(Position::Location, \"position\");\nif (flags)\nbindAttributeLocation(TextureCoordinates::Location, \"textureCoords\");\n}\nCORRADE_INTERNAL_ASSERT_OUTPUT(link());\nif (!Magnum::GL::Context::current().isExtensionSupported<Magnum::GL::Extensions::ARB::explicit_uniform_location>(version)) {\n_transformation_matrix_uniform = uniformLocation(\"transformationMatrix\");\n_shadow_matrices_uniform = uniformLocation(\"shadowMatrices[0]\");\n_light_position_uniform = uniformLocation(\"lightPosition\");\n_far_plane_uniform = uniformLocation(\"farPlane\");\n_light_index_uniform = uniformLocation(\"lightIndex\");\n_diffuse_color_uniform = uniformLocation(\"diffuseColor\");\n}\n}\nCubeMap::CubeMap(Magnum::NoCreateT) noexcept : Magnum::GL::AbstractShaderProgram{Magnum::NoCreate} {}\nCubeMap::Flags CubeMap::flags() const { return _flags; }\nCubeMap& CubeMap::set_transformation_matrix(const Magnum::Matrix4& matrix)\n{\nsetUniform(_transformation_matrix_uniform, matrix);\nreturn *this;\n}\nCubeMap& CubeMap::set_shadow_matrices(Magnum::Matrix4 matrices[6])\n{\nfor (size_t i = 0; i < 6; i++)\nsetUniform(_shadow_matrices_uniform + i, matrices[i]);\nreturn *this;\n}\nCubeMap& CubeMap::set_light_position(const Magnum::Vector3& position)\n{\nsetUniform(_light_position_uniform, position);\nreturn *this;\n}\nCubeMap& CubeMap::set_far_plane(Magnum::Float far_plane)\n{\nsetUniform(_far_plane_uniform, far_plane);\nreturn *this;\n}\nCubeMap& CubeMap::set_light_index(Magnum::Int index)\n{\nsetUniform(_light_index_uniform, index);\nreturn *this;\n}\nCubeMap& CubeMap::set_material(Material& material)\n{\nif (material.has_diffuse_texture() && (_flags & Flag::DiffuseTexture)) {\n(*material.diffuse_texture()).bind(DiffuseTextureLayer);\nsetUniform(_diffuse_color_uniform, Magnum::Color4{1.0f});\n}\nelse\nsetUniform(_diffuse_color_uniform, material.diffuse_color());\nreturn *this;\n}\n} // namespace gs\n} // namespace magnum\n} // namespace gui\n} // namespace robot_dart\n
"},{"location":"api/cube__map_8hpp/","title":"File cube_map.hpp","text":"

FileList > gs > cube_map.hpp

Go to the source code of this file

"},{"location":"api/cube__map_8hpp/#namespaces","title":"Namespaces","text":"Type Name namespace robot_dart namespace gui namespace magnum namespace gs"},{"location":"api/cube__map_8hpp/#classes","title":"Classes","text":"Type Name class CubeMap

The documentation for this class was generated from the following file robot_dart/gui/magnum/gs/cube_map.hpp

"},{"location":"api/cube__map_8hpp_source/","title":"File cube_map.hpp","text":"

File List > gs > cube_map.hpp

Go to the documentation of this file

#ifndef ROBOT_DART_GUI_MAGNUM_GS_CUBE_MAP_HPP\n#define ROBOT_DART_GUI_MAGNUM_GS_CUBE_MAP_HPP\n#include <robot_dart/gui/magnum/gs/material.hpp>\n#include <Corrade/Containers/ArrayView.h>\n#include <Corrade/Containers/Reference.h>\n#include <Corrade/Utility/Assert.h>\n#include <Magnum/GL/AbstractShaderProgram.h>\n#include <Magnum/Math/Color.h>\n#include <Magnum/Math/Matrix4.h>\n#include <Magnum/Shaders/Generic.h>\nnamespace robot_dart {\nnamespace gui {\nnamespace magnum {\nnamespace gs {\nclass CubeMap : public Magnum::GL::AbstractShaderProgram {\npublic:\nusing Position = Magnum::Shaders::Generic3D::Position;\nusing TextureCoordinates = Magnum::Shaders::Generic3D::TextureCoordinates;\nenum class Flag : Magnum::UnsignedByte {\nDiffuseTexture = 1 << 0, };\nusing Flags = Magnum::Containers::EnumSet<Flag>;\nexplicit CubeMap(Flags flags = {});\nexplicit CubeMap(Magnum::NoCreateT) noexcept;\nFlags flags() const;\nCubeMap& set_transformation_matrix(const Magnum::Matrix4& matrix);\nCubeMap& set_shadow_matrices(Magnum::Matrix4 matrices[6]);\nCubeMap& set_light_position(const Magnum::Vector3& position);\nCubeMap& set_far_plane(Magnum::Float far_plane);\nCubeMap& set_light_index(Magnum::Int index);\nCubeMap& set_material(Material& material);\nprivate:\nFlags _flags;\nMagnum::Int _transformation_matrix_uniform{0},\n_shadow_matrices_uniform{5},\n_light_position_uniform{1},\n_far_plane_uniform{2},\n_light_index_uniform{3},\n_diffuse_color_uniform{4};\n};\nCORRADE_ENUMSET_OPERATORS(CubeMap::Flags)\n} // namespace gs\n} // namespace magnum\n} // namespace gui\n} // namespace robot_dart\n#endif\n
"},{"location":"api/cube__map__color_8cpp/","title":"File cube_map_color.cpp","text":"

FileList > gs > cube_map_color.cpp

Go to the source code of this file

"},{"location":"api/cube__map__color_8cpp/#namespaces","title":"Namespaces","text":"Type Name namespace robot_dart namespace gui namespace magnum namespace gs

The documentation for this class was generated from the following file robot_dart/gui/magnum/gs/cube_map_color.cpp

"},{"location":"api/cube__map__color_8cpp_source/","title":"File cube_map_color.cpp","text":"

File List > gs > cube_map_color.cpp

Go to the documentation of this file

#include \"cube_map_color.hpp\"\n#include \"create_compatibility_shader.hpp\"\n#include <Magnum/GL/CubeMapTextureArray.h>\n#include <Magnum/GL/Texture.h>\nnamespace robot_dart {\nnamespace gui {\nnamespace magnum {\nnamespace gs {\nCubeMapColor::CubeMapColor(CubeMapColor::Flags flags) : _flags(flags)\n{\nCorrade::Utility::Resource rs_shaders(\"RobotDARTShaders\");\nconst Magnum::GL::Version version = Magnum::GL::Version::GL320;\nMagnum::GL::Shader vert = Magnum::Shaders::Implementation::createCompatibilityShader(\nrs_shaders, version, Magnum::GL::Shader::Type::Vertex);\nMagnum::GL::Shader geom = Magnum::Shaders::Implementation::createCompatibilityShader(\nrs_shaders, version, Magnum::GL::Shader::Type::Geometry);\nMagnum::GL::Shader frag = Magnum::Shaders::Implementation::createCompatibilityShader(\nrs_shaders, version, Magnum::GL::Shader::Type::Fragment);\nstd::string defines = \"#define POSITION_ATTRIBUTE_LOCATION \" + std::to_string(Position::Location) + \"\\n\";\ndefines += \"#define TEXTURECOORDINATES_ATTRIBUTE_LOCATION \" + std::to_string(TextureCoordinates::Location) + \"\\n\";\nvert.addSource(flags ? \"#define TEXTURED\\n\" : \"\")\n.addSource(defines)\n.addSource(rs_shaders.get(\"CubeMap.vert\"));\ngeom.addSource(flags ? \"#define TEXTURED\\n\" : \"\")\n.addSource(rs_shaders.get(\"CubeMap.geom\"));\nfrag.addSource(flags ? \"#define TEXTURED\\n\" : \"\")\n.addSource(rs_shaders.get(\"CubeMapColor.frag\"));\nCORRADE_INTERNAL_ASSERT_OUTPUT(Magnum::GL::Shader::compile({vert, geom, frag}));\nattachShaders({vert, geom, frag});\nif (!Magnum::GL::Context::current().isExtensionSupported<Magnum::GL::Extensions::ARB::explicit_attrib_location>(version)) {\nbindAttributeLocation(Position::Location, \"position\");\nif (flags)\nbindAttributeLocation(TextureCoordinates::Location, \"textureCoords\");\n}\nCORRADE_INTERNAL_ASSERT_OUTPUT(link());\nif (!Magnum::GL::Context::current().isExtensionSupported<Magnum::GL::Extensions::ARB::explicit_uniform_location>(version)) {\n_transformation_matrix_uniform = uniformLocation(\"transformationMatrix\");\n_shadow_matrices_uniform = uniformLocation(\"shadowMatrices[0]\");\n_light_position_uniform = uniformLocation(\"lightPosition\");\n_far_plane_uniform = uniformLocation(\"farPlane\");\n_light_index_uniform = uniformLocation(\"lightIndex\");\n_diffuse_color_uniform = uniformLocation(\"diffuseColor\");\n}\nif (!Magnum::GL::Context::current()\n.isExtensionSupported<Magnum::GL::Extensions::ARB::shading_language_420pack>(version)) {\nsetUniform(uniformLocation(\"cubeMapTextures\"), _cube_map_textures_location);\nif (flags) {\nif (flags & Flag::DiffuseTexture)\nsetUniform(uniformLocation(\"diffuseTexture\"), DiffuseTextureLayer);\n}\n}\n}\nCubeMapColor::CubeMapColor(Magnum::NoCreateT) noexcept : Magnum::GL::AbstractShaderProgram{Magnum::NoCreate} {}\nCubeMapColor::Flags CubeMapColor::flags() const { return _flags; }\nCubeMapColor& CubeMapColor::set_transformation_matrix(const Magnum::Matrix4& matrix)\n{\nsetUniform(_transformation_matrix_uniform, matrix);\nreturn *this;\n}\nCubeMapColor& CubeMapColor::set_shadow_matrices(Magnum::Matrix4 matrices[6])\n{\nfor (size_t i = 0; i < 6; i++)\nsetUniform(_shadow_matrices_uniform + i, matrices[i]);\nreturn *this;\n}\nCubeMapColor& CubeMapColor::set_light_position(const Magnum::Vector3& position)\n{\nsetUniform(_light_position_uniform, position);\nreturn *this;\n}\nCubeMapColor& CubeMapColor::set_far_plane(Magnum::Float far_plane)\n{\nsetUniform(_far_plane_uniform, far_plane);\nreturn *this;\n}\nCubeMapColor& CubeMapColor::set_light_index(Magnum::Int index)\n{\nsetUniform(_light_index_uniform, index);\nreturn *this;\n}\nCubeMapColor& CubeMapColor::set_material(Material& material)\n{\nif (material.has_diffuse_texture() && (_flags & Flag::DiffuseTexture)) {\n(*material.diffuse_texture()).bind(DiffuseTextureLayer);\nsetUniform(_diffuse_color_uniform, Magnum::Color4{1.0f});\n}\nelse\nsetUniform(_diffuse_color_uniform, material.diffuse_color());\nreturn *this;\n}\nCubeMapColor& CubeMapColor::bind_cube_map_texture(Magnum::GL::CubeMapTextureArray& texture)\n{\ntexture.bind(_cube_map_textures_location);\nreturn *this;\n}\n} // namespace gs\n} // namespace magnum\n} // namespace gui\n} // namespace robot_dart\n
"},{"location":"api/cube__map__color_8hpp/","title":"File cube_map_color.hpp","text":"

FileList > gs > cube_map_color.hpp

Go to the source code of this file

"},{"location":"api/cube__map__color_8hpp/#namespaces","title":"Namespaces","text":"Type Name namespace robot_dart namespace gui namespace magnum namespace gs"},{"location":"api/cube__map__color_8hpp/#classes","title":"Classes","text":"Type Name class CubeMapColor

The documentation for this class was generated from the following file robot_dart/gui/magnum/gs/cube_map_color.hpp

"},{"location":"api/cube__map__color_8hpp_source/","title":"File cube_map_color.hpp","text":"

File List > gs > cube_map_color.hpp

Go to the documentation of this file

#ifndef ROBOT_DART_GUI_MAGNUM_GS_CUBE_MAP_COLOR_HPP\n#define ROBOT_DART_GUI_MAGNUM_GS_CUBE_MAP_COLOR_HPP\n#include <robot_dart/gui/magnum/gs/material.hpp>\n#include <Corrade/Containers/ArrayView.h>\n#include <Corrade/Containers/Reference.h>\n#include <Corrade/Utility/Assert.h>\n#include <Magnum/GL/AbstractShaderProgram.h>\n#include <Magnum/Math/Color.h>\n#include <Magnum/Math/Matrix4.h>\n#include <Magnum/Shaders/Generic.h>\nnamespace robot_dart {\nnamespace gui {\nnamespace magnum {\nnamespace gs {\nclass CubeMapColor : public Magnum::GL::AbstractShaderProgram {\npublic:\nusing Position = Magnum::Shaders::Generic3D::Position;\nusing TextureCoordinates = Magnum::Shaders::Generic3D::TextureCoordinates;\nenum class Flag : Magnum::UnsignedByte {\nDiffuseTexture = 1 << 0, };\nusing Flags = Magnum::Containers::EnumSet<Flag>;\nexplicit CubeMapColor(Flags flags = {});\nexplicit CubeMapColor(Magnum::NoCreateT) noexcept;\nFlags flags() const;\nCubeMapColor& set_transformation_matrix(const Magnum::Matrix4& matrix);\nCubeMapColor& set_shadow_matrices(Magnum::Matrix4 matrices[6]);\nCubeMapColor& set_light_position(const Magnum::Vector3& position);\nCubeMapColor& set_far_plane(Magnum::Float far_plane);\nCubeMapColor& set_light_index(Magnum::Int index);\nCubeMapColor& set_material(Material& material);\nCubeMapColor& bind_cube_map_texture(Magnum::GL::CubeMapTextureArray& texture);\nprivate:\nFlags _flags;\nMagnum::Int _transformation_matrix_uniform{0},\n_shadow_matrices_uniform{5},\n_light_position_uniform{1},\n_far_plane_uniform{2},\n_light_index_uniform{3},\n_diffuse_color_uniform{4},\n_cube_map_textures_location{2};\n};\nCORRADE_ENUMSET_OPERATORS(CubeMapColor::Flags)\n} // namespace gs\n} // namespace magnum\n} // namespace gui\n} // namespace robot_dart\n#endif\n
"},{"location":"api/magnum_2gs_2helper_8cpp/","title":"File helper.cpp","text":"

FileList > gs > helper.cpp

Go to the source code of this file

"},{"location":"api/magnum_2gs_2helper_8cpp/#namespaces","title":"Namespaces","text":"Type Name namespace robot_dart namespace gui namespace magnum namespace gs

The documentation for this class was generated from the following file robot_dart/gui/magnum/gs/helper.cpp

"},{"location":"api/magnum_2gs_2helper_8cpp_source/","title":"File helper.cpp","text":"

File List > gs > helper.cpp

Go to the documentation of this file

#include \"helper.hpp\"\n#include <Corrade/Containers/ArrayViewStl.h>\n#include <Corrade/Containers/StridedArrayView.h>\n#include <Corrade/Utility/Algorithms.h>\n#include <Magnum/Math/Color.h>\n#include <Magnum/Math/PackingBatch.h>\nnamespace robot_dart {\nnamespace gui {\nnamespace magnum {\nnamespace gs {\nImage rgb_from_image(Magnum::Image2D* image)\n{\nImage img;\nimg.width = image->size().x();\nimg.height = image->size().y();\nimg.channels = 3;\nimg.data.resize(image->size().product() * sizeof(Magnum::Color3ub));\nCorrade::Containers::StridedArrayView2D<const Magnum::Color3ub> src = image->pixels<Magnum::Color3ub>().flipped<0>();\nCorrade::Containers::StridedArrayView2D<Magnum::Color3ub> dst{Corrade::Containers::arrayCast<Magnum::Color3ub>(Corrade::Containers::arrayView(img.data)), {std::size_t(image->size().y()), std::size_t(image->size().x())}};\nCorrade::Utility::copy(src, dst);\nreturn img;\n}\nGrayscaleImage depth_from_image(Magnum::Image2D* image, bool linearize, Magnum::Float near_plane, Magnum::Float far_plane)\n{\nGrayscaleImage img;\nimg.width = image->size().x();\nimg.height = image->size().y();\nimg.data.resize(image->size().product() * sizeof(uint8_t));\nstd::vector<Magnum::Float> data = std::vector<Magnum::Float>(image->size().product());\nCorrade::Containers::StridedArrayView2D<const Magnum::Float> src = image->pixels<Magnum::Float>().flipped<0>();\nCorrade::Containers::StridedArrayView2D<Magnum::Float> dst{Corrade::Containers::arrayCast<Magnum::Float>(Corrade::Containers::arrayView(data)), {std::size_t(image->size().y()), std::size_t(image->size().x())}};\nCorrade::Utility::copy(src, dst);\nif (linearize) {\nfor (auto& depth : data)\ndepth = (2.f * near_plane) / (far_plane + near_plane - depth * (far_plane - near_plane));\n}\nCorrade::Containers::StridedArrayView2D<uint8_t> new_dst{Corrade::Containers::arrayCast<uint8_t>(Corrade::Containers::arrayView(img.data)), {std::size_t(image->size().y()), std::size_t(image->size().x())}};\nMagnum::Math::packInto(dst, new_dst);\nreturn img;\n}\nDepthImage depth_array_from_image(Magnum::Image2D* image, Magnum::Float near_plane, Magnum::Float far_plane)\n{\nDepthImage img;\nimg.width = image->size().x();\nimg.height = image->size().y();\nstd::vector<Magnum::Float> data = std::vector<Magnum::Float>(image->size().product());\nCorrade::Containers::StridedArrayView2D<const Magnum::Float> src = image->pixels<Magnum::Float>().flipped<0>();\nCorrade::Containers::StridedArrayView2D<Magnum::Float> dst{Corrade::Containers::arrayCast<Magnum::Float>(Corrade::Containers::arrayView(data)), {std::size_t(image->size().y()), std::size_t(image->size().x())}};\nCorrade::Utility::copy(src, dst);\nimg.data = std::vector<double>(data.begin(), data.end());\ndouble zNear = static_cast<double>(near_plane);\ndouble zFar = static_cast<double>(far_plane);\n// zNear * zFar / (zFar + d * (zNear - zFar));\nfor (auto& depth : img.data)\n// depth = (2. * zNear) / (zFar + zNear - depth * (zFar - zNear));\ndepth = (zNear * zFar) / (zFar - depth * (zFar - zNear));\nreturn img;\n}\n} // namespace gs\n} // namespace magnum\n} // namespace gui\n} // namespace robot_dart\n
"},{"location":"api/magnum_2gs_2helper_8hpp/","title":"File helper.hpp","text":"

FileList > gs > helper.hpp

Go to the source code of this file

"},{"location":"api/magnum_2gs_2helper_8hpp/#namespaces","title":"Namespaces","text":"Type Name namespace robot_dart namespace gui namespace magnum namespace gs

The documentation for this class was generated from the following file robot_dart/gui/magnum/gs/helper.hpp

"},{"location":"api/magnum_2gs_2helper_8hpp_source/","title":"File helper.hpp","text":"

File List > gs > helper.hpp

Go to the documentation of this file

#ifndef ROBOT_DART_GUI_MAGNUM_GS_HELPER_HPP\n#define ROBOT_DART_GUI_MAGNUM_GS_HELPER_HPP\n#include <robot_dart/gui/helper.hpp>\n#include <vector>\n#include <Magnum/Image.h>\nnamespace robot_dart {\nnamespace gui {\nnamespace magnum {\nnamespace gs {\nImage rgb_from_image(Magnum::Image2D* image);\nGrayscaleImage depth_from_image(Magnum::Image2D* image, bool linearize = false, Magnum::Float near_plane = 0.f, Magnum::Float far_plane = 100.f);\nDepthImage depth_array_from_image(Magnum::Image2D* image, Magnum::Float near_plane = 0.f, Magnum::Float far_plane = 100.f);\n} // namespace gs\n} // namespace magnum\n} // namespace gui\n} // namespace robot_dart\n#endif\n
"},{"location":"api/light_8cpp/","title":"File light.cpp","text":"

FileList > gs > light.cpp

Go to the source code of this file

"},{"location":"api/light_8cpp/#namespaces","title":"Namespaces","text":"Type Name namespace robot_dart namespace gui namespace magnum namespace gs

The documentation for this class was generated from the following file robot_dart/gui/magnum/gs/light.cpp

"},{"location":"api/light_8cpp_source/","title":"File light.cpp","text":"

File List > gs > light.cpp

Go to the documentation of this file

#include \"light.hpp\"\n#include <Magnum/GL/Texture.h>\nnamespace robot_dart {\nnamespace gui {\nnamespace magnum {\nnamespace gs {\nLight::Light() : _position(Magnum::Vector4{0.f, 0.f, 0.f, 1.f}),\n_transformed_position(_position),\n_material(Material()),\n_spot_direction(Magnum::Vector3{1.f, 0.f, 0.f}),\n_spot_exponent(1.f),\n_spot_cut_off(Magnum::Math::Constants<Magnum::Float>::pi()),\n_attenuation(Magnum::Vector4{0.f, 0.f, 1.f, 1.f}),\n_cast_shadows(true) {}\nLight::Light(const Magnum::Vector4& position, const Material& material, const Magnum::Vector3& spot_direction,\nMagnum::Float spot_exponent, Magnum::Float spot_cut_off, const Magnum::Vector4& attenuation, bool cast_shadows) : _position(position),\n_transformed_position(_position),\n_material(material),\n_spot_direction(spot_direction),\n_spot_exponent(spot_exponent),\n_spot_cut_off(spot_cut_off),\n_attenuation(attenuation),\n_cast_shadows(cast_shadows) {}\n// Magnum::Vector4& Light::position();\nMagnum::Vector4 Light::position() const { return _position; }\nMagnum::Vector4& Light::transformed_position() { return _transformed_position; }\nMagnum::Vector4 Light::transformed_position() const { return _transformed_position; }\nMaterial& Light::material() { return _material; }\nMaterial Light::material() const { return _material; }\n// Magnum::Vector3& Light::spot_direction() { return _spot_direction; }\nMagnum::Vector3 Light::spot_direction() const { return _spot_direction; }\nMagnum::Vector3& Light::transformed_spot_direction() { return _transformed_spot_direction; }\nMagnum::Vector3 Light::transformed_spot_direction() const { return _transformed_spot_direction; }\nMagnum::Float& Light::spot_exponent() { return _spot_exponent; }\nMagnum::Float Light::spot_exponent() const { return _spot_exponent; }\nMagnum::Float& Light::spot_cut_off() { return _spot_cut_off; }\nMagnum::Float Light::spot_cut_off() const { return _spot_cut_off; }\nMagnum::Vector4& Light::attenuation() { return _attenuation; }\nMagnum::Vector4 Light::attenuation() const { return _attenuation; }\nMagnum::Matrix4 Light::shadow_matrix() const { return _shadow_transform; }\nbool Light::casts_shadows() const { return _cast_shadows; }\nLight& Light::set_position(const Magnum::Vector4& position)\n{\n_position = position;\n_transformed_position = position;\nreturn *this;\n}\nLight& Light::set_transformed_position(const Magnum::Vector4& transformed_position)\n{\n_transformed_position = transformed_position;\nreturn *this;\n}\nLight& Light::set_material(const Material& material)\n{\n_material = material;\nreturn *this;\n}\nLight& Light::set_spot_direction(const Magnum::Vector3& spot_direction)\n{\n_spot_direction = spot_direction;\n_transformed_spot_direction = _spot_direction;\nreturn *this;\n}\nLight& Light::set_transformed_spot_direction(const Magnum::Vector3& transformed_spot_direction)\n{\n_transformed_spot_direction = transformed_spot_direction;\nreturn *this;\n}\nLight& Light::set_spot_exponent(Magnum::Float spot_exponent)\n{\n_spot_exponent = spot_exponent;\nreturn *this;\n}\nLight& Light::set_spot_cut_off(Magnum::Float spot_cut_off)\n{\n_spot_cut_off = spot_cut_off;\nreturn *this;\n}\nLight& Light::set_attenuation(const Magnum::Vector4& attenuation)\n{\n_attenuation = attenuation;\nreturn *this;\n}\nLight& Light::set_shadow_matrix(const Magnum::Matrix4& shadowTransform)\n{\n_shadow_transform = shadowTransform;\nreturn *this;\n}\nLight& Light::set_casts_shadows(bool cast_shadows)\n{\n_cast_shadows = cast_shadows;\nreturn *this;\n}\n} // namespace gs\n} // namespace magnum\n} // namespace gui\n} // namespace robot_dart\n
"},{"location":"api/light_8hpp/","title":"File light.hpp","text":"

FileList > gs > light.hpp

Go to the source code of this file

"},{"location":"api/light_8hpp/#namespaces","title":"Namespaces","text":"Type Name namespace robot_dart namespace gui namespace magnum namespace gs"},{"location":"api/light_8hpp/#classes","title":"Classes","text":"Type Name class Light

The documentation for this class was generated from the following file robot_dart/gui/magnum/gs/light.hpp

"},{"location":"api/light_8hpp_source/","title":"File light.hpp","text":"

File List > gs > light.hpp

Go to the documentation of this file

#ifndef ROBOT_DART_GUI_MAGNUM_GS_LIGHT_HPP\n#define ROBOT_DART_GUI_MAGNUM_GS_LIGHT_HPP\n#include <robot_dart/gui/magnum/gs/material.hpp>\n#include <Magnum/Math/Matrix4.h>\nnamespace robot_dart {\nnamespace gui {\nnamespace magnum {\nnamespace gs {\nclass Light {\npublic:\nLight();\nLight(const Magnum::Vector4& position, const Material& material, const Magnum::Vector3& spot_direction,\nMagnum::Float spot_exponent, Magnum::Float spot_cut_off, const Magnum::Vector4& attenuation, bool cast_shadows = true);\n// Magnum::Vector4& position();\nMagnum::Vector4 position() const;\nMagnum::Vector4& transformed_position();\nMagnum::Vector4 transformed_position() const;\nMaterial& material();\nMaterial material() const;\n// Magnum::Vector3& spot_direction();\nMagnum::Vector3 spot_direction() const;\nMagnum::Vector3& transformed_spot_direction();\nMagnum::Vector3 transformed_spot_direction() const;\nMagnum::Float& spot_exponent();\nMagnum::Float spot_exponent() const;\nMagnum::Float& spot_cut_off();\nMagnum::Float spot_cut_off() const;\nMagnum::Vector4& attenuation();\nMagnum::Vector4 attenuation() const;\nMagnum::Matrix4 shadow_matrix() const;\nbool casts_shadows() const;\nLight& set_position(const Magnum::Vector4& position);\nLight& set_transformed_position(const Magnum::Vector4& transformed_position);\nLight& set_material(const Material& material);\nLight& set_spot_direction(const Magnum::Vector3& spot_direction);\nLight& set_transformed_spot_direction(const Magnum::Vector3& transformed_spot_direction);\nLight& set_spot_exponent(Magnum::Float spot_exponent);\nLight& set_spot_cut_off(Magnum::Float spot_cut_off);\nLight& set_attenuation(const Magnum::Vector4& attenuation);\nLight& set_shadow_matrix(const Magnum::Matrix4& shadowTransform);\nLight& set_casts_shadows(bool cast_shadows);\nprotected:\n// Position for point-lights and spot-lights\n// Direction for directional lights (if position.w == 0)\nMagnum::Vector4 _position;\n// TO-DO: Handle dirtiness of transformed position\nMagnum::Vector4 _transformed_position;\nMaterial _material;\nMagnum::Vector3 _spot_direction;\n// TO-DO: Handle dirtiness of transformed spot direction\nMagnum::Vector3 _transformed_spot_direction;\nMagnum::Float _spot_exponent, _spot_cut_off;\n// Attenuation is: intensity/(constant + d * (linear + quadratic * d)\n// where d is the distance from the light position to the vertex position.\n//\n// (constant,linear,quadratic,intensity)\nMagnum::Vector4 _attenuation;\n// Shadow-Matrix\nMagnum::Matrix4 _shadow_transform{};\n// Whether it casts shadows\nbool _cast_shadows = true;\n};\n// Helpers for creating lights\ninline Light create_point_light(const Magnum::Vector3& position, const Material& material,\nMagnum::Float intensity, const Magnum::Vector3& attenuationTerms)\n{\nLight light;\nlight.set_material(material);\nlight.set_position(Magnum::Vector4{position, 1.f})\n.set_attenuation(Magnum::Vector4{attenuationTerms, intensity});\nreturn light;\n}\ninline Light create_spot_light(const Magnum::Vector3& position, const Material& material,\nconst Magnum::Vector3& spot_direction, Magnum::Float spot_exponent, Magnum::Float spot_cut_off,\nMagnum::Float intensity, const Magnum::Vector3& attenuationTerms)\n{\nreturn Light(Magnum::Vector4{position, 1.f}, material, spot_direction, spot_exponent, spot_cut_off,\nMagnum::Vector4{attenuationTerms, intensity});\n}\ninline Light create_directional_light(\nconst Magnum::Vector3& direction, const Material& material)\n{\nLight light;\nlight.set_material(material);\nlight.set_position(Magnum::Vector4{direction, 0.f});\nreturn light;\n}\n} // namespace gs\n} // namespace magnum\n} // namespace gui\n} // namespace robot_dart\n#endif\n
"},{"location":"api/material_8cpp/","title":"File material.cpp","text":"

FileList > gs > material.cpp

Go to the source code of this file

"},{"location":"api/material_8cpp/#namespaces","title":"Namespaces","text":"Type Name namespace robot_dart namespace gui namespace magnum namespace gs

The documentation for this class was generated from the following file robot_dart/gui/magnum/gs/material.cpp

"},{"location":"api/material_8cpp_source/","title":"File material.cpp","text":"

File List > gs > material.cpp

Go to the documentation of this file

#include \"material.hpp\"\n#include <Magnum/GL/Texture.h>\nnamespace robot_dart {\nnamespace gui {\nnamespace magnum {\nnamespace gs {\nMaterial::Material() : _ambient(Magnum::Color4{0.f, 0.f, 0.f, 1.f}),\n_diffuse(Magnum::Color4{0.f, 0.f, 0.f, 1.f}),\n_specular(Magnum::Color4{0.f, 0.f, 0.f, 1.f}),\n_shininess(2000.f) {}\nMaterial::Material(const Magnum::Color4& ambient, const Magnum::Color4& diffuse,\nconst Magnum::Color4& specular, Magnum::Float shininess) : _ambient(ambient),\n_diffuse(diffuse),\n_specular(specular),\n_shininess(shininess) {}\nMaterial::Material(Magnum::GL::Texture2D* ambient_texture,\nMagnum::GL::Texture2D* diffuse_texture,\nMagnum::GL::Texture2D* specular_texture, Magnum::Float shininess) : _ambient(Magnum::Color4{0.f, 0.f, 0.f, 1.f}),\n_diffuse(Magnum::Color4{0.f, 0.f, 0.f, 1.f}),\n_specular(Magnum::Color4{0.f, 0.f, 0.f, 1.f}),\n_shininess(shininess),\n_ambient_texture(ambient_texture),\n_diffuse_texture(diffuse_texture),\n_specular_texture(specular_texture) {}\nMagnum::Color4& Material::ambient_color() { return _ambient; }\nMagnum::Color4 Material::ambient_color() const { return _ambient; }\nMagnum::Color4& Material::diffuse_color() { return _diffuse; }\nMagnum::Color4 Material::diffuse_color() const { return _diffuse; }\nMagnum::Color4& Material::specular_color() { return _specular; }\nMagnum::Color4 Material::specular_color() const { return _specular; }\nMagnum::Float& Material::shininess() { return _shininess; }\nMagnum::Float Material::shininess() const { return _shininess; }\nMagnum::GL::Texture2D* Material::ambient_texture() { return _ambient_texture; }\nMagnum::GL::Texture2D* Material::diffuse_texture() { return _diffuse_texture; }\nMagnum::GL::Texture2D* Material::specular_texture() { return _specular_texture; }\nbool Material::has_ambient_texture() const { return _ambient_texture != NULL; }\nbool Material::has_diffuse_texture() const { return _diffuse_texture != NULL; }\nbool Material::has_specular_texture() const { return _specular_texture != NULL; }\nMaterial& Material::set_ambient_color(const Magnum::Color4& ambient)\n{\n_ambient = ambient;\nreturn *this;\n}\nMaterial& Material::set_diffuse_color(const Magnum::Color4& diffuse)\n{\n_diffuse = diffuse;\nreturn *this;\n}\nMaterial& Material::set_specular_color(const Magnum::Color4& specular)\n{\n_specular = specular;\nreturn *this;\n}\nMaterial& Material::set_shininess(Magnum::Float shininess)\n{\n_shininess = shininess;\nreturn *this;\n}\nMaterial& Material::set_ambient_texture(Magnum::GL::Texture2D* ambient_texture)\n{\n_ambient_texture = ambient_texture;\nreturn *this;\n}\nMaterial& Material::set_diffuse_texture(Magnum::GL::Texture2D* diffuse_texture)\n{\n_diffuse_texture = diffuse_texture;\nreturn *this;\n}\nMaterial& Material::set_specular_texture(Magnum::GL::Texture2D* specular_texture)\n{\n_specular_texture = specular_texture;\nreturn *this;\n}\n} // namespace gs\n} // namespace magnum\n} // namespace gui\n} // namespace robot_dart\n
"},{"location":"api/material_8hpp/","title":"File material.hpp","text":"

FileList > gs > material.hpp

Go to the source code of this file

"},{"location":"api/material_8hpp/#namespaces","title":"Namespaces","text":"Type Name namespace robot_dart namespace gui namespace magnum namespace gs"},{"location":"api/material_8hpp/#classes","title":"Classes","text":"Type Name class Material

The documentation for this class was generated from the following file robot_dart/gui/magnum/gs/material.hpp

"},{"location":"api/material_8hpp_source/","title":"File material.hpp","text":"

File List > gs > material.hpp

Go to the documentation of this file

#ifndef ROBOT_DART_GUI_MAGNUM_GS_MATERIAL_HPP\n#define ROBOT_DART_GUI_MAGNUM_GS_MATERIAL_HPP\n#include <Corrade/Containers/Optional.h>\n#include <Magnum/GL/GL.h>\n#include <Magnum/Magnum.h>\n#include <Magnum/Math/Color.h>\nnamespace robot_dart {\nnamespace gui {\nnamespace magnum {\nnamespace gs {\nclass Material {\npublic:\nMaterial();\nMaterial(const Magnum::Color4& ambient, const Magnum::Color4& diffuse,\nconst Magnum::Color4& specular, Magnum::Float shininess);\nMaterial(Magnum::GL::Texture2D* ambient_texture,\nMagnum::GL::Texture2D* diffuse_texture,\nMagnum::GL::Texture2D* specular_texture, Magnum::Float shininess);\nMagnum::Color4& ambient_color();\nMagnum::Color4 ambient_color() const;\nMagnum::Color4& diffuse_color();\nMagnum::Color4 diffuse_color() const;\nMagnum::Color4& specular_color();\nMagnum::Color4 specular_color() const;\nMagnum::Float& shininess();\nMagnum::Float shininess() const;\nMagnum::GL::Texture2D* ambient_texture();\nMagnum::GL::Texture2D* diffuse_texture();\nMagnum::GL::Texture2D* specular_texture();\nbool has_ambient_texture() const;\nbool has_diffuse_texture() const;\nbool has_specular_texture() const;\nMaterial& set_ambient_color(const Magnum::Color4& ambient);\nMaterial& set_diffuse_color(const Magnum::Color4& diffuse);\nMaterial& set_specular_color(const Magnum::Color4& specular);\nMaterial& set_shininess(Magnum::Float shininess);\nMaterial& set_ambient_texture(Magnum::GL::Texture2D* ambient_texture);\nMaterial& set_diffuse_texture(Magnum::GL::Texture2D* diffuse_texture);\nMaterial& set_specular_texture(Magnum::GL::Texture2D* specular_texture);\nprotected:\nMagnum::Color4 _ambient, _diffuse, _specular;\nMagnum::Float _shininess;\nMagnum::GL::Texture2D* _ambient_texture = NULL;\nMagnum::GL::Texture2D* _diffuse_texture = NULL;\nMagnum::GL::Texture2D* _specular_texture = NULL;\n};\n} // namespace gs\n} // namespace magnum\n} // namespace gui\n} // namespace robot_dart\n#endif\n
"},{"location":"api/phong__multi__light_8cpp/","title":"File phong_multi_light.cpp","text":"

FileList > gs > phong_multi_light.cpp

Go to the source code of this file

"},{"location":"api/phong__multi__light_8cpp/#namespaces","title":"Namespaces","text":"Type Name namespace robot_dart namespace gui namespace magnum namespace gs

The documentation for this class was generated from the following file robot_dart/gui/magnum/gs/phong_multi_light.cpp

"},{"location":"api/phong__multi__light_8cpp_source/","title":"File phong_multi_light.cpp","text":"

File List > gs > phong_multi_light.cpp

Go to the documentation of this file

#include \"phong_multi_light.hpp\"\n#include \"create_compatibility_shader.hpp\"\n#include <Magnum/GL/CubeMapTextureArray.h>\n#include <Magnum/GL/Texture.h>\n#include <Magnum/GL/TextureArray.h>\nnamespace robot_dart {\nnamespace gui {\nnamespace magnum {\nnamespace gs {\nPhongMultiLight::PhongMultiLight(PhongMultiLight::Flags flags, Magnum::Int max_lights) : _flags(flags), _max_lights(max_lights)\n{\nCorrade::Utility::Resource rs_shaders(\"RobotDARTShaders\");\nconst Magnum::GL::Version version = Magnum::GL::Version::GL320;\nMagnum::GL::Shader vert = Magnum::Shaders::Implementation::createCompatibilityShader(\nrs_shaders, version, Magnum::GL::Shader::Type::Vertex);\nMagnum::GL::Shader frag = Magnum::Shaders::Implementation::createCompatibilityShader(\nrs_shaders, version, Magnum::GL::Shader::Type::Fragment);\nstd::string defines = \"#define LIGHT_COUNT \" + std::to_string(_max_lights) + \"\\n\";\ndefines += \"#define POSITION_ATTRIBUTE_LOCATION \" + std::to_string(Position::Location) + \"\\n\";\ndefines += \"#define NORMAL_ATTRIBUTE_LOCATION \" + std::to_string(Normal::Location) + \"\\n\";\ndefines += \"#define TEXTURECOORDINATES_ATTRIBUTE_LOCATION \" + std::to_string(TextureCoordinates::Location) + \"\\n\";\nvert.addSource(flags ? \"#define TEXTURED\\n\" : \"\")\n.addSource(defines)\n.addSource(rs_shaders.get(\"PhongMultiLight.vert\"));\nfrag.addSource(flags & Flag::AmbientTexture ? \"#define AMBIENT_TEXTURE\\n\" : \"\")\n.addSource(flags & Flag::DiffuseTexture ? \"#define DIFFUSE_TEXTURE\\n\" : \"\")\n.addSource(flags & Flag::SpecularTexture ? \"#define SPECULAR_TEXTURE\\n\" : \"\")\n.addSource(defines)\n.addSource(rs_shaders.get(\"PhongMultiLight.frag\"));\nCORRADE_INTERNAL_ASSERT_OUTPUT(Magnum::GL::Shader::compile({vert, frag}));\nattachShaders({vert, frag});\nif (!Magnum::GL::Context::current().isExtensionSupported<Magnum::GL::Extensions::ARB::explicit_attrib_location>(version)) {\nbindAttributeLocation(Position::Location, \"position\");\nbindAttributeLocation(Normal::Location, \"normal\");\nif (flags)\nbindAttributeLocation(TextureCoordinates::Location, \"textureCoords\");\n}\nCORRADE_INTERNAL_ASSERT_OUTPUT(link());\n/* Get light matrices uniform */\n_lights_matrices_uniform = uniformLocation(\"lightMatrices[0]\");\nif (!Magnum::GL::Context::current().isExtensionSupported<Magnum::GL::Extensions::ARB::explicit_uniform_location>(version)) {\n_transformation_matrix_uniform = uniformLocation(\"transformationMatrix\");\n_projection_matrix_uniform = uniformLocation(\"projectionMatrix\");\n_camera_matrix_uniform = uniformLocation(\"cameraMatrix\");\n_normal_matrix_uniform = uniformLocation(\"normalMatrix\");\n_lights_uniform = uniformLocation(\"lights[0].position\");\n_lights_matrices_uniform = uniformLocation(\"lightMatrices[0]\");\n_ambient_color_uniform = uniformLocation(\"ambientColor\");\n_diffuse_color_uniform = uniformLocation(\"diffuseColor\");\n_specular_color_uniform = uniformLocation(\"specularColor\");\n_shininess_uniform = uniformLocation(\"shininess\");\n_far_plane_uniform = uniformLocation(\"farPlane\");\n_specular_strength_uniform = uniformLocation(\"specularStrength\");\n_is_shadowed_uniform = uniformLocation(\"isShadowed\");\n_transparent_shadows_uniform = uniformLocation(\"drawTransparentShadows\");\n}\nif (!Magnum::GL::Context::current()\n.isExtensionSupported<Magnum::GL::Extensions::ARB::shading_language_420pack>(version)) {\nsetUniform(uniformLocation(\"shadowTextures\"), _shadow_textures_location);\nsetUniform(uniformLocation(\"cubeMapTextures\"), _cube_map_textures_location);\nsetUniform(uniformLocation(\"shadowColorTextures\"), _shadow_color_textures_location);\nsetUniform(uniformLocation(\"cubeMapColorTextures\"), _cube_map_color_textures_location);\nif (flags) {\nif (flags & Flag::AmbientTexture)\nsetUniform(uniformLocation(\"ambientTexture\"), AmbientTextureLayer);\nif (flags & Flag::DiffuseTexture)\nsetUniform(uniformLocation(\"diffuseTexture\"), DiffuseTextureLayer);\nif (flags & Flag::SpecularTexture)\nsetUniform(uniformLocation(\"specularTexture\"), SpecularTextureLayer);\n}\n}\n/* Set defaults (normally they are set in shader code itself, but just in case) */\nMaterial material;\n/* Default to fully opaque white so we can see the textures */\nif (flags & Flag::AmbientTexture)\nmaterial.set_ambient_color(Magnum::Color4{1.0f});\nelse\nmaterial.set_ambient_color(Magnum::Color4{0.0f, 1.0f});\nif (flags & Flag::DiffuseTexture)\nmaterial.set_diffuse_color(Magnum::Color4{1.0f});\nmaterial.set_specular_color(Magnum::Color4{1.0f});\nmaterial.set_shininess(80.0f);\nset_material(material);\n/* Lights defaults need to be set by code */\n/* All lights are disabled i.e., color equal to black */\nLight light;\nfor (Magnum::Int i = 0; i < _max_lights; i++)\nset_light(i, light);\n}\nPhongMultiLight::PhongMultiLight(Magnum::NoCreateT) noexcept : Magnum::GL::AbstractShaderProgram{Magnum::NoCreate} {}\nPhongMultiLight::Flags PhongMultiLight::flags() const { return _flags; }\nPhongMultiLight& PhongMultiLight::set_material(Material& material)\n{\n// TO-DO: Check if we should do this or let the user define the proper\n// material\nif (material.has_ambient_texture() && (_flags & Flag::AmbientTexture)) {\n(*material.ambient_texture()).bind(AmbientTextureLayer);\nsetUniform(_ambient_color_uniform, Magnum::Color4{1.0f});\n}\nelse\nsetUniform(_ambient_color_uniform, material.ambient_color());\nif (material.has_diffuse_texture() && (_flags & Flag::DiffuseTexture)) {\n(*material.diffuse_texture()).bind(DiffuseTextureLayer);\nsetUniform(_diffuse_color_uniform, Magnum::Color4{1.0f});\n}\nelse\nsetUniform(_diffuse_color_uniform, material.diffuse_color());\nif (material.has_specular_texture() && (_flags & Flag::SpecularTexture)) {\n(*material.specular_texture()).bind(SpecularTextureLayer);\nsetUniform(_specular_color_uniform, Magnum::Color4{1.0f});\n}\nelse\nsetUniform(_specular_color_uniform, material.specular_color());\nsetUniform(_shininess_uniform, material.shininess());\nreturn *this;\n}\nPhongMultiLight& PhongMultiLight::set_light(Magnum::Int i, const Light& light)\n{\nCORRADE_INTERNAL_ASSERT(i >= 0 && i < _max_lights);\nMagnum::Vector4 attenuation = light.attenuation();\n// light position\nsetUniform(_lights_uniform + i * _light_loc_size, light.transformed_position());\n// light material\nsetUniform(_lights_uniform + i * _light_loc_size + 1, light.material().ambient_color());\nsetUniform(_lights_uniform + i * _light_loc_size + 2, light.material().diffuse_color());\nsetUniform(_lights_uniform + i * _light_loc_size + 3, light.material().specular_color());\n// spotlight properties\nsetUniform(_lights_uniform + i * _light_loc_size + 4, light.transformed_spot_direction());\nsetUniform(_lights_uniform + i * _light_loc_size + 5, light.spot_exponent());\nsetUniform(_lights_uniform + i * _light_loc_size + 6, light.spot_cut_off());\n// intesity\nsetUniform(_lights_uniform + i * _light_loc_size + 7, attenuation[3]);\n// constant attenuation term\nsetUniform(_lights_uniform + i * _light_loc_size + 8, attenuation[0]);\n// linear attenuation term\nsetUniform(_lights_uniform + i * _light_loc_size + 9, attenuation[1]);\n// quadratic attenuation term\nsetUniform(_lights_uniform + i * _light_loc_size + 10, attenuation[2]);\n// world position\nsetUniform(_lights_uniform + i * _light_loc_size + 11, light.position());\n// casts shadows?\nsetUniform(_lights_uniform + i * _light_loc_size + 12, light.casts_shadows());\nsetUniform(_lights_matrices_uniform + i, light.shadow_matrix());\nreturn *this;\n}\nPhongMultiLight& PhongMultiLight::set_transformation_matrix(const Magnum::Matrix4& matrix)\n{\nsetUniform(_transformation_matrix_uniform, matrix);\nreturn *this;\n}\nPhongMultiLight& PhongMultiLight::set_camera_matrix(const Magnum::Matrix4& matrix)\n{\nsetUniform(_camera_matrix_uniform, matrix);\nreturn *this;\n}\nPhongMultiLight& PhongMultiLight::set_normal_matrix(const Magnum::Matrix3x3& matrix)\n{\nsetUniform(_normal_matrix_uniform, matrix);\nreturn *this;\n}\nPhongMultiLight& PhongMultiLight::set_projection_matrix(const Magnum::Matrix4& matrix)\n{\nsetUniform(_projection_matrix_uniform, matrix);\nreturn *this;\n}\nPhongMultiLight& PhongMultiLight::set_far_plane(Magnum::Float far_plane)\n{\nsetUniform(_far_plane_uniform, far_plane);\nreturn *this;\n}\nPhongMultiLight& PhongMultiLight::set_is_shadowed(bool shadows)\n{\nsetUniform(_is_shadowed_uniform, shadows);\nreturn *this;\n}\nPhongMultiLight& PhongMultiLight::set_transparent_shadows(bool shadows)\n{\nsetUniform(_transparent_shadows_uniform, shadows);\nreturn *this;\n}\nPhongMultiLight& PhongMultiLight::set_specular_strength(Magnum::Float specular_strength)\n{\nsetUniform(_specular_strength_uniform, std::max(0.f, specular_strength));\nreturn *this;\n}\nPhongMultiLight& PhongMultiLight::bind_shadow_texture(Magnum::GL::Texture2DArray& texture)\n{\ntexture.bind(_shadow_textures_location);\nreturn *this;\n}\nPhongMultiLight& PhongMultiLight::bind_shadow_color_texture(Magnum::GL::Texture2DArray& texture)\n{\ntexture.bind(_shadow_color_textures_location);\nreturn *this;\n}\nPhongMultiLight& PhongMultiLight::bind_cube_map_texture(Magnum::GL::CubeMapTextureArray& texture)\n{\ntexture.bind(_cube_map_textures_location);\nreturn *this;\n}\nPhongMultiLight& PhongMultiLight::bind_cube_map_color_texture(Magnum::GL::CubeMapTextureArray& texture)\n{\ntexture.bind(_cube_map_color_textures_location);\nreturn *this;\n}\nMagnum::Int PhongMultiLight::max_lights() const { return _max_lights; }\n} // namespace gs\n} // namespace magnum\n} // namespace gui\n} // namespace robot_dart\n
"},{"location":"api/phong__multi__light_8hpp/","title":"File phong_multi_light.hpp","text":"

FileList > gs > phong_multi_light.hpp

Go to the source code of this file

"},{"location":"api/phong__multi__light_8hpp/#namespaces","title":"Namespaces","text":"Type Name namespace robot_dart namespace gui namespace magnum namespace gs"},{"location":"api/phong__multi__light_8hpp/#classes","title":"Classes","text":"Type Name class PhongMultiLight

The documentation for this class was generated from the following file robot_dart/gui/magnum/gs/phong_multi_light.hpp

"},{"location":"api/phong__multi__light_8hpp_source/","title":"File phong_multi_light.hpp","text":"

File List > gs > phong_multi_light.hpp

Go to the documentation of this file

#ifndef ROBOT_DART_GUI_MAGNUM_GS_PHONG_MULTI_LIGHT_HPP\n#define ROBOT_DART_GUI_MAGNUM_GS_PHONG_MULTI_LIGHT_HPP\n#include <robot_dart/gui/magnum/gs/light.hpp>\n#include <Corrade/Containers/ArrayView.h>\n#include <Corrade/Containers/Reference.h>\n#include <Corrade/Utility/Assert.h>\n#include <Magnum/GL/AbstractShaderProgram.h>\n#include <Magnum/Math/Color.h>\n#include <Magnum/Math/Matrix4.h>\n#include <Magnum/Shaders/Generic.h>\nnamespace robot_dart {\nnamespace gui {\nnamespace magnum {\nnamespace gs {\nclass PhongMultiLight : public Magnum::GL::AbstractShaderProgram {\npublic:\nusing Position = Magnum::Shaders::Generic3D::Position;\nusing Normal = Magnum::Shaders::Generic3D::Normal;\nusing TextureCoordinates = Magnum::Shaders::Generic3D::TextureCoordinates;\nenum class Flag : Magnum::UnsignedByte {\nAmbientTexture = 1 << 0, DiffuseTexture = 1 << 1, SpecularTexture = 1 << 2 };\nusing Flags = Magnum::Containers::EnumSet<Flag>;\nexplicit PhongMultiLight(Flags flags = {}, Magnum::Int max_lights = 10);\nexplicit PhongMultiLight(Magnum::NoCreateT) noexcept;\nFlags flags() const;\nPhongMultiLight& set_material(Material& material);\nPhongMultiLight& set_light(Magnum::Int i, const Light& light);\nPhongMultiLight& set_transformation_matrix(const Magnum::Matrix4& matrix);\nPhongMultiLight& set_camera_matrix(const Magnum::Matrix4& matrix);\nPhongMultiLight& set_normal_matrix(const Magnum::Matrix3x3& matrix);\nPhongMultiLight& set_projection_matrix(const Magnum::Matrix4& matrix);\nPhongMultiLight& set_far_plane(Magnum::Float far_plane);\nPhongMultiLight& set_is_shadowed(bool shadows);\nPhongMultiLight& set_transparent_shadows(bool shadows);\nPhongMultiLight& set_specular_strength(Magnum::Float specular_strength);\nPhongMultiLight& bind_shadow_texture(Magnum::GL::Texture2DArray& texture);\nPhongMultiLight& bind_shadow_color_texture(Magnum::GL::Texture2DArray& texture);\nPhongMultiLight& bind_cube_map_texture(Magnum::GL::CubeMapTextureArray& texture);\nPhongMultiLight& bind_cube_map_color_texture(Magnum::GL::CubeMapTextureArray& texture);\nMagnum::Int max_lights() const;\nprivate:\nFlags _flags;\nMagnum::Int _max_lights = 10;\nMagnum::Int _transformation_matrix_uniform{0}, _camera_matrix_uniform{7}, _projection_matrix_uniform{1}, _normal_matrix_uniform{2},\n_shininess_uniform{3}, _ambient_color_uniform{4}, _diffuse_color_uniform{5}, _specular_color_uniform{6}, _specular_strength_uniform{11},\n_lights_uniform{12}, _lights_matrices_uniform, _far_plane_uniform{8}, _is_shadowed_uniform{9}, _transparent_shadows_uniform{10},\n_shadow_textures_location{3}, _cube_map_textures_location{4}, _shadow_color_textures_location{5}, _cube_map_color_textures_location{6};\nconst Magnum::Int _light_loc_size = 13;\n};\nCORRADE_ENUMSET_OPERATORS(PhongMultiLight::Flags)\n} // namespace gs\n} // namespace magnum\n} // namespace gui\n} // namespace robot_dart\n#endif\n
"},{"location":"api/shadow__map_8cpp/","title":"File shadow_map.cpp","text":"

FileList > gs > shadow_map.cpp

Go to the source code of this file

"},{"location":"api/shadow__map_8cpp/#namespaces","title":"Namespaces","text":"Type Name namespace robot_dart namespace gui namespace magnum namespace gs

The documentation for this class was generated from the following file robot_dart/gui/magnum/gs/shadow_map.cpp

"},{"location":"api/shadow__map_8cpp_source/","title":"File shadow_map.cpp","text":"

File List > gs > shadow_map.cpp

Go to the documentation of this file

#include \"shadow_map.hpp\"\n#include \"create_compatibility_shader.hpp\"\n#include <Magnum/GL/Texture.h>\nnamespace robot_dart {\nnamespace gui {\nnamespace magnum {\nnamespace gs {\nShadowMap::ShadowMap(ShadowMap::Flags flags) : _flags(flags)\n{\nCorrade::Utility::Resource rs_shaders(\"RobotDARTShaders\");\nconst Magnum::GL::Version version = Magnum::GL::Version::GL320;\nMagnum::GL::Shader vert = Magnum::Shaders::Implementation::createCompatibilityShader(\nrs_shaders, version, Magnum::GL::Shader::Type::Vertex);\nMagnum::GL::Shader frag = Magnum::Shaders::Implementation::createCompatibilityShader(\nrs_shaders, version, Magnum::GL::Shader::Type::Fragment);\nstd::string defines = \"#define POSITION_ATTRIBUTE_LOCATION \" + std::to_string(Position::Location) + \"\\n\";\ndefines += \"#define TEXTURECOORDINATES_ATTRIBUTE_LOCATION \" + std::to_string(TextureCoordinates::Location) + \"\\n\";\nvert.addSource(flags ? \"#define TEXTURED\\n\" : \"\")\n.addSource(defines)\n.addSource(rs_shaders.get(\"ShadowMap.vert\"));\nfrag.addSource(flags ? \"#define TEXTURED\\n\" : \"\")\n.addSource(rs_shaders.get(\"ShadowMap.frag\"));\nCORRADE_INTERNAL_ASSERT_OUTPUT(Magnum::GL::Shader::compile({vert, frag}));\nattachShaders({vert, frag});\nif (!Magnum::GL::Context::current().isExtensionSupported<Magnum::GL::Extensions::ARB::explicit_attrib_location>(version)) {\nbindAttributeLocation(Position::Location, \"position\");\nif (flags)\nbindAttributeLocation(TextureCoordinates::Location, \"textureCoords\");\n}\nCORRADE_INTERNAL_ASSERT_OUTPUT(link());\nif (!Magnum::GL::Context::current().isExtensionSupported<Magnum::GL::Extensions::ARB::explicit_uniform_location>(version)) {\n_transformation_matrix_uniform = uniformLocation(\"transformationMatrix\");\n_projection_matrix_uniform = uniformLocation(\"projectionMatrix\");\n_diffuse_color_uniform = uniformLocation(\"diffuseColor\");\n}\nif (!Magnum::GL::Context::current()\n.isExtensionSupported<Magnum::GL::Extensions::ARB::shading_language_420pack>(version)\n&& flags) {\nsetUniform(uniformLocation(\"diffuseTexture\"), DiffuseTextureLayer);\n}\n}\nShadowMap::ShadowMap(Magnum::NoCreateT) noexcept : Magnum::GL::AbstractShaderProgram{Magnum::NoCreate} {}\nShadowMap::Flags ShadowMap::flags() const { return _flags; }\nShadowMap& ShadowMap::set_transformation_matrix(const Magnum::Matrix4& matrix)\n{\nsetUniform(_transformation_matrix_uniform, matrix);\nreturn *this;\n}\nShadowMap& ShadowMap::set_projection_matrix(const Magnum::Matrix4& matrix)\n{\nsetUniform(_projection_matrix_uniform, matrix);\nreturn *this;\n}\nShadowMap& ShadowMap::set_material(Material& material)\n{\nif (material.has_diffuse_texture() && (_flags & Flag::DiffuseTexture)) {\n(*material.diffuse_texture()).bind(DiffuseTextureLayer);\nsetUniform(_diffuse_color_uniform, Magnum::Color4{1.0f});\n}\nelse\nsetUniform(_diffuse_color_uniform, material.diffuse_color());\nreturn *this;\n}\n} // namespace gs\n} // namespace magnum\n} // namespace gui\n} // namespace robot_dart\n
"},{"location":"api/shadow__map_8hpp/","title":"File shadow_map.hpp","text":"

FileList > gs > shadow_map.hpp

Go to the source code of this file

"},{"location":"api/shadow__map_8hpp/#namespaces","title":"Namespaces","text":"Type Name namespace robot_dart namespace gui namespace magnum namespace gs"},{"location":"api/shadow__map_8hpp/#classes","title":"Classes","text":"Type Name class ShadowMap

The documentation for this class was generated from the following file robot_dart/gui/magnum/gs/shadow_map.hpp

"},{"location":"api/shadow__map_8hpp_source/","title":"File shadow_map.hpp","text":"

File List > gs > shadow_map.hpp

Go to the documentation of this file

#ifndef ROBOT_DART_GUI_MAGNUM_GS_SHADOW_MAP_HPP\n#define ROBOT_DART_GUI_MAGNUM_GS_SHADOW_MAP_HPP\n#include <robot_dart/gui/magnum/gs/material.hpp>\n#include <Corrade/Containers/ArrayView.h>\n#include <Corrade/Containers/Reference.h>\n#include <Corrade/Utility/Assert.h>\n#include <Magnum/GL/AbstractShaderProgram.h>\n#include <Magnum/Math/Color.h>\n#include <Magnum/Math/Matrix4.h>\n#include <Magnum/Shaders/Generic.h>\nnamespace robot_dart {\nnamespace gui {\nnamespace magnum {\nnamespace gs {\nclass ShadowMap : public Magnum::GL::AbstractShaderProgram {\npublic:\nusing Position = Magnum::Shaders::Generic3D::Position;\nusing TextureCoordinates = Magnum::Shaders::Generic3D::TextureCoordinates;\nenum class Flag : Magnum::UnsignedByte {\nDiffuseTexture = 1 << 0, };\nusing Flags = Magnum::Containers::EnumSet<Flag>;\nexplicit ShadowMap(Flags flags = {});\nexplicit ShadowMap(Magnum::NoCreateT) noexcept;\nFlags flags() const;\nShadowMap& set_transformation_matrix(const Magnum::Matrix4& matrix);\nShadowMap& set_projection_matrix(const Magnum::Matrix4& matrix);\nShadowMap& set_material(Material& material);\nprivate:\nFlags _flags;\nMagnum::Int _transformation_matrix_uniform{0}, _projection_matrix_uniform{1}, _diffuse_color_uniform{2};\n};\nCORRADE_ENUMSET_OPERATORS(ShadowMap::Flags)\n} // namespace gs\n} // namespace magnum\n} // namespace gui\n} // namespace robot_dart\n#endif\n
"},{"location":"api/shadow__map__color_8cpp/","title":"File shadow_map_color.cpp","text":"

FileList > gs > shadow_map_color.cpp

Go to the source code of this file

"},{"location":"api/shadow__map__color_8cpp/#namespaces","title":"Namespaces","text":"Type Name namespace robot_dart namespace gui namespace magnum namespace gs

The documentation for this class was generated from the following file robot_dart/gui/magnum/gs/shadow_map_color.cpp

"},{"location":"api/shadow__map__color_8cpp_source/","title":"File shadow_map_color.cpp","text":"

File List > gs > shadow_map_color.cpp

Go to the documentation of this file

#include \"shadow_map_color.hpp\"\n#include \"create_compatibility_shader.hpp\"\n#include <Magnum/GL/Texture.h>\nnamespace robot_dart {\nnamespace gui {\nnamespace magnum {\nnamespace gs {\nShadowMapColor::ShadowMapColor(ShadowMapColor::Flags flags) : _flags(flags)\n{\nCorrade::Utility::Resource rs_shaders(\"RobotDARTShaders\");\nconst Magnum::GL::Version version = Magnum::GL::Version::GL320;\nMagnum::GL::Shader vert = Magnum::Shaders::Implementation::createCompatibilityShader(\nrs_shaders, version, Magnum::GL::Shader::Type::Vertex);\nMagnum::GL::Shader frag = Magnum::Shaders::Implementation::createCompatibilityShader(\nrs_shaders, version, Magnum::GL::Shader::Type::Fragment);\nstd::string defines = \"#define POSITION_ATTRIBUTE_LOCATION \" + std::to_string(Position::Location) + \"\\n\";\ndefines += \"#define TEXTURECOORDINATES_ATTRIBUTE_LOCATION \" + std::to_string(TextureCoordinates::Location) + \"\\n\";\nvert.addSource(flags ? \"#define TEXTURED\\n\" : \"\")\n.addSource(defines)\n.addSource(rs_shaders.get(\"ShadowMap.vert\"));\nfrag.addSource(flags ? \"#define TEXTURED\\n\" : \"\")\n.addSource(rs_shaders.get(\"ShadowMapColor.frag\"));\nCORRADE_INTERNAL_ASSERT_OUTPUT(Magnum::GL::Shader::compile({vert, frag}));\nattachShaders({vert, frag});\nif (!Magnum::GL::Context::current().isExtensionSupported<Magnum::GL::Extensions::ARB::explicit_attrib_location>(version)) {\nbindAttributeLocation(Position::Location, \"position\");\nif (flags)\nbindAttributeLocation(TextureCoordinates::Location, \"textureCoords\");\n}\nCORRADE_INTERNAL_ASSERT_OUTPUT(link());\nif (!Magnum::GL::Context::current().isExtensionSupported<Magnum::GL::Extensions::ARB::explicit_uniform_location>(version)) {\n_transformation_matrix_uniform = uniformLocation(\"transformationMatrix\");\n_projection_matrix_uniform = uniformLocation(\"projectionMatrix\");\n_diffuse_color_uniform = uniformLocation(\"diffuseColor\");\n}\nif (!Magnum::GL::Context::current()\n.isExtensionSupported<Magnum::GL::Extensions::ARB::shading_language_420pack>(version)\n&& flags) {\nsetUniform(uniformLocation(\"diffuseTexture\"), DiffuseTextureLayer);\n}\n}\nShadowMapColor::ShadowMapColor(Magnum::NoCreateT) noexcept : Magnum::GL::AbstractShaderProgram{Magnum::NoCreate} {}\nShadowMapColor::Flags ShadowMapColor::flags() const { return _flags; }\nShadowMapColor& ShadowMapColor::set_transformation_matrix(const Magnum::Matrix4& matrix)\n{\nsetUniform(_transformation_matrix_uniform, matrix);\nreturn *this;\n}\nShadowMapColor& ShadowMapColor::set_projection_matrix(const Magnum::Matrix4& matrix)\n{\nsetUniform(_projection_matrix_uniform, matrix);\nreturn *this;\n}\nShadowMapColor& ShadowMapColor::set_material(Material& material)\n{\nif (material.has_diffuse_texture() && (_flags & Flag::DiffuseTexture)) {\n(*material.diffuse_texture()).bind(DiffuseTextureLayer);\nsetUniform(_diffuse_color_uniform, Magnum::Color4{1.0f});\n}\nelse\nsetUniform(_diffuse_color_uniform, material.diffuse_color());\nreturn *this;\n}\n} // namespace gs\n} // namespace magnum\n} // namespace gui\n} // namespace robot_dart\n
"},{"location":"api/shadow__map__color_8hpp/","title":"File shadow_map_color.hpp","text":"

FileList > gs > shadow_map_color.hpp

Go to the source code of this file

"},{"location":"api/shadow__map__color_8hpp/#namespaces","title":"Namespaces","text":"Type Name namespace robot_dart namespace gui namespace magnum namespace gs"},{"location":"api/shadow__map__color_8hpp/#classes","title":"Classes","text":"Type Name class ShadowMapColor

The documentation for this class was generated from the following file robot_dart/gui/magnum/gs/shadow_map_color.hpp

"},{"location":"api/shadow__map__color_8hpp_source/","title":"File shadow_map_color.hpp","text":"

File List > gs > shadow_map_color.hpp

Go to the documentation of this file

#ifndef ROBOT_DART_GUI_MAGNUM_GS_SHADOW_MAP_COLOR_HPP\n#define ROBOT_DART_GUI_MAGNUM_GS_SHADOW_MAP_COLOR_HPP\n#include <robot_dart/gui/magnum/gs/material.hpp>\n#include <Corrade/Containers/ArrayView.h>\n#include <Corrade/Containers/Reference.h>\n#include <Corrade/Utility/Assert.h>\n#include <Magnum/GL/AbstractShaderProgram.h>\n#include <Magnum/Math/Color.h>\n#include <Magnum/Math/Matrix4.h>\n#include <Magnum/Shaders/Generic.h>\nnamespace robot_dart {\nnamespace gui {\nnamespace magnum {\nnamespace gs {\nclass ShadowMapColor : public Magnum::GL::AbstractShaderProgram {\npublic:\nusing Position = Magnum::Shaders::Generic3D::Position;\nusing TextureCoordinates = Magnum::Shaders::Generic3D::TextureCoordinates;\nenum class Flag : Magnum::UnsignedByte {\nDiffuseTexture = 1 << 0, };\nusing Flags = Magnum::Containers::EnumSet<Flag>;\nexplicit ShadowMapColor(Flags flags = {});\nexplicit ShadowMapColor(Magnum::NoCreateT) noexcept;\nFlags flags() const;\nShadowMapColor& set_transformation_matrix(const Magnum::Matrix4& matrix);\nShadowMapColor& set_projection_matrix(const Magnum::Matrix4& matrix);\nShadowMapColor& set_material(Material& material);\nprivate:\nFlags _flags;\nMagnum::Int _transformation_matrix_uniform{0}, _projection_matrix_uniform{1}, _diffuse_color_uniform{2};\n};\nCORRADE_ENUMSET_OPERATORS(ShadowMapColor::Flags)\n} // namespace gs\n} // namespace magnum\n} // namespace gui\n} // namespace robot_dart\n#endif\n
"},{"location":"api/dir_2c74a777547786aaf50e99ba400e19fa/","title":"Dir robot_dart/gui/magnum/sensor","text":"

FileList > gui > magnum > sensor

"},{"location":"api/dir_2c74a777547786aaf50e99ba400e19fa/#files","title":"Files","text":"Type Name file camera.cpp file camera.hpp

The documentation for this class was generated from the following file robot_dart/gui/magnum/sensor/

"},{"location":"api/sensor_2camera_8cpp/","title":"File camera.cpp","text":"

FileList > gui > magnum > sensor > camera.cpp

Go to the source code of this file

"},{"location":"api/sensor_2camera_8cpp/#namespaces","title":"Namespaces","text":"Type Name namespace robot_dart namespace gui namespace magnum namespace sensor

The documentation for this class was generated from the following file robot_dart/gui/magnum/sensor/camera.cpp

"},{"location":"api/sensor_2camera_8cpp_source/","title":"Macro Syntax Error","text":"

Line 46 in Markdown file: unexpected '}'

                    _framebuffer = Magnum::GL::Framebuffer({{}, {w, h}});\n

"},{"location":"api/sensor_2camera_8hpp/","title":"File camera.hpp","text":"

FileList > gui > magnum > sensor > camera.hpp

Go to the source code of this file

"},{"location":"api/sensor_2camera_8hpp/#namespaces","title":"Namespaces","text":"Type Name namespace robot_dart namespace gui namespace magnum namespace sensor namespace sensor"},{"location":"api/sensor_2camera_8hpp/#classes","title":"Classes","text":"Type Name class Camera

The documentation for this class was generated from the following file robot_dart/gui/magnum/sensor/camera.hpp

"},{"location":"api/sensor_2camera_8hpp_source/","title":"File camera.hpp","text":"

File List > gui > magnum > sensor > camera.hpp

Go to the documentation of this file

#ifndef ROBOT_DART_GUI_MAGNUM_SENSOR_CAMERA_HPP\n#define ROBOT_DART_GUI_MAGNUM_SENSOR_CAMERA_HPP\n#include <robot_dart/gui/magnum/base_application.hpp>\n#include <robot_dart/gui/magnum/gs/helper.hpp>\n#include <robot_dart/sensor/sensor.hpp>\n#include <Magnum/GL/Framebuffer.h>\n#include <Magnum/GL/Renderbuffer.h>\n#include <Magnum/PixelFormat.h>\nnamespace robot_dart {\nnamespace gui {\nnamespace magnum {\nnamespace sensor {\nclass Camera : public robot_dart::sensor::Sensor {\npublic:\nCamera(BaseApplication* app, size_t width, size_t height, size_t freq = 30, bool draw_debug = false);\n~Camera() {}\nvoid init() override;\nvoid calculate(double) override;\nstd::string type() const override;\nvoid attach_to_body(dart::dynamics::BodyNode* body, const Eigen::Isometry3d& tf = Eigen::Isometry3d::Identity()) override;\nvoid attach_to_joint(dart::dynamics::Joint*, const Eigen::Isometry3d&) override\n{\nROBOT_DART_WARNING(true, \"You cannot attach a camera to a joint!\");\n}\ngs::Camera& camera() { return *_camera; }\nconst gs::Camera& camera() const { return *_camera; }\nEigen::Matrix3d camera_intrinsic_matrix() const;\nEigen::Matrix4d camera_extrinsic_matrix() const;\nbool drawing_debug() const { return _draw_debug; }\nvoid draw_debug(bool draw = true) { _draw_debug = draw; }\nvoid look_at(const Eigen::Vector3d& camera_pos, const Eigen::Vector3d& look_at = Eigen::Vector3d(0, 0, 0), const Eigen::Vector3d& up = Eigen::Vector3d(0, 0, 1));\n// this will use the default FPS of the camera if fps == -1\nvoid record_video(const std::string& video_fname)\n{\n_camera->record_video(video_fname, _frequency);\n}\nMagnum::Image2D* magnum_image()\n{\nif (_camera->image())\nreturn &(*_camera->image());\nreturn nullptr;\n}\nImage image()\n{\nauto image = magnum_image();\nif (image)\nreturn gs::rgb_from_image(image);\nreturn Image();\n}\nMagnum::Image2D* magnum_depth_image()\n{\nif (_camera->depth_image())\nreturn &(*_camera->depth_image());\nreturn nullptr;\n}\n// This is for visualization purposes\nGrayscaleImage depth_image();\n// Image filled with depth buffer values\nGrayscaleImage raw_depth_image();\n// \"Image\" filled with depth buffer values (this returns an array of doubles)\nDepthImage depth_array();\nprotected:\nMagnum::GL::Framebuffer _framebuffer{Magnum::NoCreate};\nMagnum::PixelFormat _format;\nMagnum::GL::Renderbuffer _color, _depth;\nBaseApplication* _magnum_app;\nsize_t _width, _height;\nstd::unique_ptr<gs::Camera> _camera;\nbool _draw_debug;\n};\n} // namespace sensor\n} // namespace magnum\n} // namespace gui\nnamespace sensor {\nusing gui::magnum::sensor::Camera;\n}\n} // namespace robot_dart\n#endif\n
"},{"location":"api/types_8hpp/","title":"File types.hpp","text":"

FileList > gui > magnum > types.hpp

Go to the source code of this file

"},{"location":"api/types_8hpp/#namespaces","title":"Namespaces","text":"Type Name namespace robot_dart namespace gui namespace magnum

The documentation for this class was generated from the following file robot_dart/gui/magnum/types.hpp

"},{"location":"api/types_8hpp_source/","title":"File types.hpp","text":"

File List > gui > magnum > types.hpp

Go to the documentation of this file

#ifndef ROBOT_DART_GUI_MAGNUM_TYPES_HPP\n#define ROBOT_DART_GUI_MAGNUM_TYPES_HPP\n#include <Magnum/SceneGraph/Camera.h>\n#include <Magnum/SceneGraph/MatrixTransformation3D.h>\n#include <Magnum/SceneGraph/Scene.h>\nnamespace robot_dart {\nnamespace gui {\nnamespace magnum {\nusing Object3D = Magnum::SceneGraph::Object<Magnum::SceneGraph::MatrixTransformation3D>;\nusing Scene3D = Magnum::SceneGraph::Scene<Magnum::SceneGraph::MatrixTransformation3D>;\nusing Camera3D = Magnum::SceneGraph::Camera3D;\n} // namespace magnum\n} // namespace gui\n} // namespace robot_dart\n#endif\n
"},{"location":"api/utils__headers__eigen_8hpp/","title":"File utils_headers_eigen.hpp","text":"

FileList > gui > magnum > utils_headers_eigen.hpp

Go to the source code of this file

The documentation for this class was generated from the following file robot_dart/gui/magnum/utils_headers_eigen.hpp

"},{"location":"api/utils__headers__eigen_8hpp_source/","title":"File utils_headers_eigen.hpp","text":"

File List > gui > magnum > utils_headers_eigen.hpp

Go to the documentation of this file

#ifndef ROBOT_DART_GUI_MAGNUM_UTILS_HEADERS_EXTERNAL_GUI_HPP\n#define ROBOT_DART_GUI_MAGNUM_UTILS_HEADERS_EXTERNAL_GUI_HPP\n#pragma GCC system_header\n#include <Magnum/EigenIntegration/GeometryIntegration.h>\n#include <Magnum/EigenIntegration/Integration.h>\n#endif\n
"},{"location":"api/windowless__gl__application_8cpp/","title":"File windowless_gl_application.cpp","text":"

FileList > gui > magnum > windowless_gl_application.cpp

Go to the source code of this file

"},{"location":"api/windowless__gl__application_8cpp/#namespaces","title":"Namespaces","text":"Type Name namespace robot_dart namespace gui namespace magnum

The documentation for this class was generated from the following file robot_dart/gui/magnum/windowless_gl_application.cpp

"},{"location":"api/windowless__gl__application_8cpp_source/","title":"Macro Syntax Error","text":"

Line 42 in Markdown file: unexpected '}'

                _framebuffer = Magnum::GL::Framebuffer({{}, {w, h}});\n

"},{"location":"api/windowless__gl__application_8hpp/","title":"File windowless_gl_application.hpp","text":"

FileList > gui > magnum > windowless_gl_application.hpp

Go to the source code of this file

"},{"location":"api/windowless__gl__application_8hpp/#namespaces","title":"Namespaces","text":"Type Name namespace robot_dart namespace gui namespace magnum"},{"location":"api/windowless__gl__application_8hpp/#classes","title":"Classes","text":"Type Name class WindowlessGLApplication

The documentation for this class was generated from the following file robot_dart/gui/magnum/windowless_gl_application.hpp

"},{"location":"api/windowless__gl__application_8hpp_source/","title":"File windowless_gl_application.hpp","text":"

File List > gui > magnum > windowless_gl_application.hpp

Go to the documentation of this file

#ifndef ROBOT_DART_GUI_MAGNUM_GLX_APPLICATION_HPP\n#define ROBOT_DART_GUI_MAGNUM_GLX_APPLICATION_HPP\n#include <robot_dart/gui/magnum/base_application.hpp>\n#include <Magnum/GL/Renderbuffer.h>\n#include <Magnum/PixelFormat.h>\nnamespace robot_dart {\nnamespace gui {\nnamespace magnum {\nclass WindowlessGLApplication : public BaseApplication, public Magnum::Platform::WindowlessApplication {\npublic:\nexplicit WindowlessGLApplication(int argc, char** argv, RobotDARTSimu* simu, const GraphicsConfiguration& configuration = GraphicsConfiguration());\n~WindowlessGLApplication();\nvoid render() override;\nprotected:\nRobotDARTSimu* _simu;\nbool _draw_main_camera, _draw_debug;\nMagnum::Color4 _bg_color;\nMagnum::GL::Framebuffer _framebuffer{Magnum::NoCreate};\nMagnum::PixelFormat _format;\nMagnum::GL::Renderbuffer _color{Magnum::NoCreate}, _depth{Magnum::NoCreate};\n// size_t _index = 0;\nvirtual int exec() override { return 0; }\n};\n} // namespace magnum\n} // namespace gui\n} // namespace robot_dart\n#endif\n
"},{"location":"api/windowless__graphics_8cpp/","title":"File windowless_graphics.cpp","text":"

FileList > gui > magnum > windowless_graphics.cpp

Go to the source code of this file

"},{"location":"api/windowless__graphics_8cpp/#namespaces","title":"Namespaces","text":"Type Name namespace robot_dart namespace gui namespace magnum

The documentation for this class was generated from the following file robot_dart/gui/magnum/windowless_graphics.cpp

"},{"location":"api/windowless__graphics_8cpp_source/","title":"File windowless_graphics.cpp","text":"

File List > gui > magnum > windowless_graphics.cpp

Go to the documentation of this file

#include <robot_dart/gui/magnum/windowless_graphics.hpp>\nnamespace robot_dart {\nnamespace gui {\nnamespace magnum {\nvoid WindowlessGraphics::set_simu(RobotDARTSimu* simu)\n{\nBaseGraphics<WindowlessGLApplication>::set_simu(simu);\n// we should not synchronize by default if we want windowless graphics (usually used only for sensors)\nsimu->scheduler().set_sync(false);\n// disable summary text when windowless graphics activated\nsimu->enable_text_panel(false);\nsimu->enable_status_bar(false);\n}\nGraphicsConfiguration WindowlessGraphics::default_configuration()\n{\nGraphicsConfiguration config;\n// by default we do not draw text in windowless mode\nconfig.draw_debug = false;\nconfig.draw_text = false;\nreturn config;\n}\n} // namespace magnum\n} // namespace gui\n} // namespace robot_dart\n
"},{"location":"api/windowless__graphics_8hpp/","title":"File windowless_graphics.hpp","text":"

FileList > gui > magnum > windowless_graphics.hpp

Go to the source code of this file

"},{"location":"api/windowless__graphics_8hpp/#namespaces","title":"Namespaces","text":"Type Name namespace robot_dart namespace gui namespace magnum"},{"location":"api/windowless__graphics_8hpp/#classes","title":"Classes","text":"Type Name class WindowlessGraphics

The documentation for this class was generated from the following file robot_dart/gui/magnum/windowless_graphics.hpp

"},{"location":"api/windowless__graphics_8hpp_source/","title":"File windowless_graphics.hpp","text":"

File List > gui > magnum > windowless_graphics.hpp

Go to the documentation of this file

#ifndef ROBOT_DART_GUI_MAGNUM_WINDOWLESS_GRAPHICS_HPP\n#define ROBOT_DART_GUI_MAGNUM_WINDOWLESS_GRAPHICS_HPP\n#include <robot_dart/gui/magnum/base_graphics.hpp>\n#include <robot_dart/gui/magnum/windowless_gl_application.hpp>\nnamespace robot_dart {\nnamespace gui {\nnamespace magnum {\nclass WindowlessGraphics : public BaseGraphics<WindowlessGLApplication> {\npublic:\nWindowlessGraphics(const GraphicsConfiguration& configuration = default_configuration()) : BaseGraphics<WindowlessGLApplication>(configuration) {}\n~WindowlessGraphics() {}\nvoid set_simu(RobotDARTSimu* simu) override;\nstatic GraphicsConfiguration default_configuration();\n};\n} // namespace magnum\n} // namespace gui\n} // namespace robot_dart\n#endif\n
"},{"location":"api/stb__image__write_8h/","title":"File stb_image_write.h","text":"

FileList > gui > stb_image_write.h

Go to the source code of this file

"},{"location":"api/stb__image__write_8h/#public-types","title":"Public Types","text":"Type Name typedef void stbi_write_func"},{"location":"api/stb__image__write_8h/#public-attributes","title":"Public Attributes","text":"Type Name int stbi_write_force_png_filter int stbi_write_png_compression_level int stbi_write_tga_with_rle"},{"location":"api/stb__image__write_8h/#public-functions","title":"Public Functions","text":"Type Name STBIWDEF void stbi_flip_vertically_on_write (int flip_boolean) STBIWDEF int stbi_write_bmp (char const * filename, int w, int h, int comp, const void * data) STBIWDEF int stbi_write_bmp_to_func (stbi_write_func * func, void * context, int w, int h, int comp, const void * data) STBIWDEF int stbi_write_hdr (char const * filename, int w, int h, int comp, const float * data) STBIWDEF int stbi_write_hdr_to_func (stbi_write_func * func, void * context, int w, int h, int comp, const float * data) STBIWDEF int stbi_write_jpg (char const * filename, int x, int y, int comp, const void * data, int quality) STBIWDEF int stbi_write_jpg_to_func (stbi_write_func * func, void * context, int x, int y, int comp, const void * data, int quality) STBIWDEF int stbi_write_png (char const * filename, int w, int h, int comp, const void * data, int stride_in_bytes) STBIWDEF int stbi_write_png_to_func (stbi_write_func * func, void * context, int w, int h, int comp, const void * data, int stride_in_bytes) STBIWDEF int stbi_write_tga (char const * filename, int w, int h, int comp, const void * data) STBIWDEF int stbi_write_tga_to_func (stbi_write_func * func, void * context, int w, int h, int comp, const void * data)"},{"location":"api/stb__image__write_8h/#macros","title":"Macros","text":"Type Name define STBIWDEF extern"},{"location":"api/stb__image__write_8h/#public-types-documentation","title":"Public Types Documentation","text":""},{"location":"api/stb__image__write_8h/#typedef-stbi_write_func","title":"typedef stbi_write_func","text":"
typedef void stbi_write_func(void *context, void *data, int size);\n
"},{"location":"api/stb__image__write_8h/#public-attributes-documentation","title":"Public Attributes Documentation","text":""},{"location":"api/stb__image__write_8h/#variable-stbi_write_force_png_filter","title":"variable stbi_write_force_png_filter","text":"
int stbi_write_force_png_filter;\n
"},{"location":"api/stb__image__write_8h/#variable-stbi_write_png_compression_level","title":"variable stbi_write_png_compression_level","text":"
int stbi_write_png_compression_level;\n
"},{"location":"api/stb__image__write_8h/#variable-stbi_write_tga_with_rle","title":"variable stbi_write_tga_with_rle","text":"
int stbi_write_tga_with_rle;\n
"},{"location":"api/stb__image__write_8h/#public-functions-documentation","title":"Public Functions Documentation","text":""},{"location":"api/stb__image__write_8h/#function-stbi_flip_vertically_on_write","title":"function stbi_flip_vertically_on_write","text":"
STBIWDEF void stbi_flip_vertically_on_write (\nint flip_boolean\n) 
"},{"location":"api/stb__image__write_8h/#function-stbi_write_bmp","title":"function stbi_write_bmp","text":"
STBIWDEF int stbi_write_bmp (\nchar const * filename,\nint w,\nint h,\nint comp,\nconst void * data\n) 
"},{"location":"api/stb__image__write_8h/#function-stbi_write_bmp_to_func","title":"function stbi_write_bmp_to_func","text":"
STBIWDEF int stbi_write_bmp_to_func (\nstbi_write_func * func,\nvoid * context,\nint w,\nint h,\nint comp,\nconst void * data\n) 
"},{"location":"api/stb__image__write_8h/#function-stbi_write_hdr","title":"function stbi_write_hdr","text":"
STBIWDEF int stbi_write_hdr (\nchar const * filename,\nint w,\nint h,\nint comp,\nconst float * data\n) 
"},{"location":"api/stb__image__write_8h/#function-stbi_write_hdr_to_func","title":"function stbi_write_hdr_to_func","text":"
STBIWDEF int stbi_write_hdr_to_func (\nstbi_write_func * func,\nvoid * context,\nint w,\nint h,\nint comp,\nconst float * data\n) 
"},{"location":"api/stb__image__write_8h/#function-stbi_write_jpg","title":"function stbi_write_jpg","text":"
STBIWDEF int stbi_write_jpg (\nchar const * filename,\nint x,\nint y,\nint comp,\nconst void * data,\nint quality\n) 
"},{"location":"api/stb__image__write_8h/#function-stbi_write_jpg_to_func","title":"function stbi_write_jpg_to_func","text":"
STBIWDEF int stbi_write_jpg_to_func (\nstbi_write_func * func,\nvoid * context,\nint x,\nint y,\nint comp,\nconst void * data,\nint quality\n) 
"},{"location":"api/stb__image__write_8h/#function-stbi_write_png","title":"function stbi_write_png","text":"
STBIWDEF int stbi_write_png (\nchar const * filename,\nint w,\nint h,\nint comp,\nconst void * data,\nint stride_in_bytes\n) 
"},{"location":"api/stb__image__write_8h/#function-stbi_write_png_to_func","title":"function stbi_write_png_to_func","text":"
STBIWDEF int stbi_write_png_to_func (\nstbi_write_func * func,\nvoid * context,\nint w,\nint h,\nint comp,\nconst void * data,\nint stride_in_bytes\n) 
"},{"location":"api/stb__image__write_8h/#function-stbi_write_tga","title":"function stbi_write_tga","text":"
STBIWDEF int stbi_write_tga (\nchar const * filename,\nint w,\nint h,\nint comp,\nconst void * data\n) 
"},{"location":"api/stb__image__write_8h/#function-stbi_write_tga_to_func","title":"function stbi_write_tga_to_func","text":"
STBIWDEF int stbi_write_tga_to_func (\nstbi_write_func * func,\nvoid * context,\nint w,\nint h,\nint comp,\nconst void * data\n) 
"},{"location":"api/stb__image__write_8h/#macro-definition-documentation","title":"Macro Definition Documentation","text":""},{"location":"api/stb__image__write_8h/#define-stbiwdef","title":"define STBIWDEF","text":"
#define STBIWDEF extern\n

The documentation for this class was generated from the following file robot_dart/gui/stb_image_write.h

"},{"location":"api/stb__image__write_8h_source/","title":"File stb_image_write.h","text":"

File List > gui > stb_image_write.h

Go to the documentation of this file

/* stb_image_write - v1.13 - public domain - http://nothings.org/stb\n   writes out PNG/BMP/TGA/JPEG/HDR images to C stdio - Sean Barrett 2010-2015\n                                     no warranty implied; use at your own risk\n   Before #including,\n       #define STB_IMAGE_WRITE_IMPLEMENTATION\n   in the file that you want to have the implementation.\n   Will probably not work correctly with strict-aliasing optimizations.\nABOUT:\n   This header file is a library for writing images to C stdio or a callback.\n   The PNG output is not optimal; it is 20-50% larger than the file\n   written by a decent optimizing implementation; though providing a custom\n   zlib compress function (see STBIW_ZLIB_COMPRESS) can mitigate that.\n   This library is designed for source code compactness and simplicity,\n   not optimal image file size or run-time performance.\nBUILDING:\n   You can #define STBIW_ASSERT(x) before the #include to avoid using assert.h.\n   You can #define STBIW_MALLOC(), STBIW_REALLOC(), and STBIW_FREE() to replace\n   malloc,realloc,free.\n   You can #define STBIW_MEMMOVE() to replace memmove()\n   You can #define STBIW_ZLIB_COMPRESS to use a custom zlib-style compress function\n   for PNG compression (instead of the builtin one), it must have the following signature:\n   unsigned char * my_compress(unsigned char *data, int data_len, int *out_len, int quality);\n   The returned data will be freed with STBIW_FREE() (free() by default),\n   so it must be heap allocated with STBIW_MALLOC() (malloc() by default),\nUNICODE:\n   If compiling for Windows and you wish to use Unicode filenames, compile\n   with\n       #define STBIW_WINDOWS_UTF8\n   and pass utf8-encoded filenames. Call stbiw_convert_wchar_to_utf8 to convert\n   Windows wchar_t filenames to utf8.\nUSAGE:\n   There are five functions, one for each image file format:\n     int stbi_write_png(char const *filename, int w, int h, int comp, const void *data, int stride_in_bytes);\n     int stbi_write_bmp(char const *filename, int w, int h, int comp, const void *data);\n     int stbi_write_tga(char const *filename, int w, int h, int comp, const void *data);\n     int stbi_write_jpg(char const *filename, int w, int h, int comp, const void *data, int quality);\n     int stbi_write_hdr(char const *filename, int w, int h, int comp, const float *data);\n     void stbi_flip_vertically_on_write(int flag); // flag is non-zero to flip data vertically\n   There are also five equivalent functions that use an arbitrary write function. You are\n   expected to open/close your file-equivalent before and after calling these:\n     int stbi_write_png_to_func(stbi_write_func *func, void *context, int w, int h, int comp, const void  *data, int stride_in_bytes);\n     int stbi_write_bmp_to_func(stbi_write_func *func, void *context, int w, int h, int comp, const void  *data);\n     int stbi_write_tga_to_func(stbi_write_func *func, void *context, int w, int h, int comp, const void  *data);\n     int stbi_write_hdr_to_func(stbi_write_func *func, void *context, int w, int h, int comp, const float *data);\n     int stbi_write_jpg_to_func(stbi_write_func *func, void *context, int x, int y, int comp, const void *data, int quality);\n   where the callback is:\n      void stbi_write_func(void *context, void *data, int size);\n   You can configure it with these global variables:\n      int stbi_write_tga_with_rle;             // defaults to true; set to 0 to disable RLE\n      int stbi_write_png_compression_level;    // defaults to 8; set to higher for more compression\n      int stbi_write_force_png_filter;         // defaults to -1; set to 0..5 to force a filter mode\n   You can define STBI_WRITE_NO_STDIO to disable the file variant of these\n   functions, so the library will not use stdio.h at all. However, this will\n   also disable HDR writing, because it requires stdio for formatted output.\n   Each function returns 0 on failure and non-0 on success.\n   The functions create an image file defined by the parameters. The image\n   is a rectangle of pixels stored from left-to-right, top-to-bottom.\n   Each pixel contains 'comp' channels of data stored interleaved with 8-bits\n   per channel, in the following order: 1=Y, 2=YA, 3=RGB, 4=RGBA. (Y is\n   monochrome color.) The rectangle is 'w' pixels wide and 'h' pixels tall.\n   The *data pointer points to the first byte of the top-left-most pixel.\n   For PNG, \"stride_in_bytes\" is the distance in bytes from the first byte of\n   a row of pixels to the first byte of the next row of pixels.\n   PNG creates output files with the same number of components as the input.\n   The BMP format expands Y to RGB in the file format and does not\n   output alpha.\n   PNG supports writing rectangles of data even when the bytes storing rows of\n   data are not consecutive in memory (e.g. sub-rectangles of a larger image),\n   by supplying the stride between the beginning of adjacent rows. The other\n   formats do not. (Thus you cannot write a native-format BMP through the BMP\n   writer, both because it is in BGR order and because it may have padding\n   at the end of the line.)\n   PNG allows you to set the deflate compression level by setting the global\n   variable 'stbi_write_png_compression_level' (it defaults to 8).\n   HDR expects linear float data. Since the format is always 32-bit rgb(e)\n   data, alpha (if provided) is discarded, and for monochrome data it is\n   replicated across all three channels.\n   TGA supports RLE or non-RLE compressed data. To use non-RLE-compressed\n   data, set the global variable 'stbi_write_tga_with_rle' to 0.\n   JPEG does ignore alpha channels in input data; quality is between 1 and 100.\n   Higher quality looks better but results in a bigger image.\n   JPEG baseline (no JPEG progressive).\nCREDITS:\n   Sean Barrett           -    PNG/BMP/TGA \n   Baldur Karlsson        -    HDR\n   Jean-Sebastien Guay    -    TGA monochrome\n   Tim Kelsey             -    misc enhancements\n   Alan Hickman           -    TGA RLE\n   Emmanuel Julien        -    initial file IO callback implementation\n   Jon Olick              -    original jo_jpeg.cpp code\n   Daniel Gibson          -    integrate JPEG, allow external zlib\n   Aarni Koskela          -    allow choosing PNG filter\n   bugfixes:\n      github:Chribba\n      Guillaume Chereau\n      github:jry2\n      github:romigrou\n      Sergio Gonzalez\n      Jonas Karlsson\n      Filip Wasil\n      Thatcher Ulrich\n      github:poppolopoppo\n      Patrick Boettcher\n      github:xeekworx\n      Cap Petschulat\n      Simon Rodriguez\n      Ivan Tikhonov\n      github:ignotion\n      Adam Schackart\nLICENSE\n  See end of file for license information.\n*/\n#pragma GCC system_header\n#ifndef INCLUDE_STB_IMAGE_WRITE_H\n#define INCLUDE_STB_IMAGE_WRITE_H\n#include <stdlib.h>\n// if STB_IMAGE_WRITE_STATIC causes problems, try defining STBIWDEF to 'inline' or 'static inline'\n#ifndef STBIWDEF\n#ifdef STB_IMAGE_WRITE_STATIC\n#define STBIWDEF  static\n#else\n#ifdef __cplusplus\n#define STBIWDEF  extern \"C\"\n#else\n#define STBIWDEF  extern\n#endif\n#endif\n#endif\n#ifndef STB_IMAGE_WRITE_STATIC  // C++ forbids static forward declarations\nextern int stbi_write_tga_with_rle;\nextern int stbi_write_png_compression_level;\nextern int stbi_write_force_png_filter;\n#endif\n#ifndef STBI_WRITE_NO_STDIO\nSTBIWDEF int stbi_write_png(char const *filename, int w, int h, int comp, const void  *data, int stride_in_bytes);\nSTBIWDEF int stbi_write_bmp(char const *filename, int w, int h, int comp, const void  *data);\nSTBIWDEF int stbi_write_tga(char const *filename, int w, int h, int comp, const void  *data);\nSTBIWDEF int stbi_write_hdr(char const *filename, int w, int h, int comp, const float *data);\nSTBIWDEF int stbi_write_jpg(char const *filename, int x, int y, int comp, const void  *data, int quality);\n#ifdef STBI_WINDOWS_UTF8\nSTBIWDEF int stbiw_convert_wchar_to_utf8(char *buffer, size_t bufferlen, const wchar_t* input);\n#endif\n#endif\ntypedef void stbi_write_func(void *context, void *data, int size);\nSTBIWDEF int stbi_write_png_to_func(stbi_write_func *func, void *context, int w, int h, int comp, const void  *data, int stride_in_bytes);\nSTBIWDEF int stbi_write_bmp_to_func(stbi_write_func *func, void *context, int w, int h, int comp, const void  *data);\nSTBIWDEF int stbi_write_tga_to_func(stbi_write_func *func, void *context, int w, int h, int comp, const void  *data);\nSTBIWDEF int stbi_write_hdr_to_func(stbi_write_func *func, void *context, int w, int h, int comp, const float *data);\nSTBIWDEF int stbi_write_jpg_to_func(stbi_write_func *func, void *context, int x, int y, int comp, const void  *data, int quality);\nSTBIWDEF void stbi_flip_vertically_on_write(int flip_boolean);\n#endif//INCLUDE_STB_IMAGE_WRITE_H\n#ifdef STB_IMAGE_WRITE_IMPLEMENTATION\n#ifdef _WIN32\n#ifndef _CRT_SECURE_NO_WARNINGS\n#define _CRT_SECURE_NO_WARNINGS\n#endif\n#ifndef _CRT_NONSTDC_NO_DEPRECATE\n#define _CRT_NONSTDC_NO_DEPRECATE\n#endif\n#endif\n#ifndef STBI_WRITE_NO_STDIO\n#include <stdio.h>\n#endif // STBI_WRITE_NO_STDIO\n#include <stdarg.h>\n#include <stdlib.h>\n#include <string.h>\n#include <math.h>\n#if defined(STBIW_MALLOC) && defined(STBIW_FREE) && (defined(STBIW_REALLOC) || defined(STBIW_REALLOC_SIZED))\n// ok\n#elif !defined(STBIW_MALLOC) && !defined(STBIW_FREE) && !defined(STBIW_REALLOC) && !defined(STBIW_REALLOC_SIZED)\n// ok\n#else\n#error \"Must define all or none of STBIW_MALLOC, STBIW_FREE, and STBIW_REALLOC (or STBIW_REALLOC_SIZED).\"\n#endif\n#ifndef STBIW_MALLOC\n#define STBIW_MALLOC(sz)        malloc(sz)\n#define STBIW_REALLOC(p,newsz)  realloc(p,newsz)\n#define STBIW_FREE(p)           free(p)\n#endif\n#ifndef STBIW_REALLOC_SIZED\n#define STBIW_REALLOC_SIZED(p,oldsz,newsz) STBIW_REALLOC(p,newsz)\n#endif\n#ifndef STBIW_MEMMOVE\n#define STBIW_MEMMOVE(a,b,sz) memmove(a,b,sz)\n#endif\n#ifndef STBIW_ASSERT\n#include <assert.h>\n#define STBIW_ASSERT(x) assert(x)\n#endif\n#define STBIW_UCHAR(x) (unsigned char) ((x) & 0xff)\n#ifdef STB_IMAGE_WRITE_STATIC\nstatic int stbi__flip_vertically_on_write=0;\nstatic int stbi_write_png_compression_level = 8;\nstatic int stbi_write_tga_with_rle = 1;\nstatic int stbi_write_force_png_filter = -1;\n#else\nint stbi_write_png_compression_level = 8;\nint stbi__flip_vertically_on_write=0;\nint stbi_write_tga_with_rle = 1;\nint stbi_write_force_png_filter = -1;\n#endif\nSTBIWDEF void stbi_flip_vertically_on_write(int flag)\n{\nstbi__flip_vertically_on_write = flag;\n}\ntypedef struct\n{\nstbi_write_func *func;\nvoid *context;\n} stbi__write_context;\n// initialize a callback-based context\nstatic void stbi__start_write_callbacks(stbi__write_context *s, stbi_write_func *c, void *context)\n{\ns->func    = c;\ns->context = context;\n}\n#ifndef STBI_WRITE_NO_STDIO\nstatic void stbi__stdio_write(void *context, void *data, int size)\n{\nfwrite(data,1,size,(FILE*) context);\n}\n#if defined(_MSC_VER) && defined(STBI_WINDOWS_UTF8)\n#ifdef __cplusplus\n#define STBIW_EXTERN extern \"C\"\n#else\n#define STBIW_EXTERN extern\n#endif\nSTBIW_EXTERN __declspec(dllimport) int __stdcall MultiByteToWideChar(unsigned int cp, unsigned long flags, const char *str, int cbmb, wchar_t *widestr, int cchwide);\nSTBIW_EXTERN __declspec(dllimport) int __stdcall WideCharToMultiByte(unsigned int cp, unsigned long flags, const wchar_t *widestr, int cchwide, char *str, int cbmb, const char *defchar, int *used_default);\nSTBIWDEF int stbiw_convert_wchar_to_utf8(char *buffer, size_t bufferlen, const wchar_t* input)\n{\nreturn WideCharToMultiByte(65001 /* UTF8 */, 0, input, -1, buffer, (int) bufferlen, NULL, NULL);\n}\n#endif\nstatic FILE *stbiw__fopen(char const *filename, char const *mode)\n{\nFILE *f;\n#if defined(_MSC_VER) && defined(STBI_WINDOWS_UTF8)\nwchar_t wMode[64];\nwchar_t wFilename[1024];\nif (0 == MultiByteToWideChar(65001 /* UTF8 */, 0, filename, -1, wFilename, sizeof(wFilename)))\nreturn 0;\nif (0 == MultiByteToWideChar(65001 /* UTF8 */, 0, mode, -1, wMode, sizeof(wMode)))\nreturn 0;\n#if _MSC_VER >= 1400\nif (0 != _wfopen_s(&f, wFilename, wMode))\nf = 0;\n#else\nf = _wfopen(wFilename, wMode);\n#endif\n#elif defined(_MSC_VER) && _MSC_VER >= 1400\nif (0 != fopen_s(&f, filename, mode))\nf=0;\n#else\nf = fopen(filename, mode);\n#endif\nreturn f;\n}\nstatic int stbi__start_write_file(stbi__write_context *s, const char *filename)\n{\nFILE *f = stbiw__fopen(filename, \"wb\");\nstbi__start_write_callbacks(s, stbi__stdio_write, (void *) f);\nreturn f != NULL;\n}\nstatic void stbi__end_write_file(stbi__write_context *s)\n{\nfclose((FILE *)s->context);\n}\n#endif // !STBI_WRITE_NO_STDIO\ntypedef unsigned int stbiw_uint32;\ntypedef int stb_image_write_test[sizeof(stbiw_uint32)==4 ? 1 : -1];\nstatic void stbiw__writefv(stbi__write_context *s, const char *fmt, va_list v)\n{\nwhile (*fmt) {\nswitch (*fmt++) {\ncase ' ': break;\ncase '1': { unsigned char x = STBIW_UCHAR(va_arg(v, int));\ns->func(s->context,&x,1);\nbreak; }\ncase '2': { int x = va_arg(v,int);\nunsigned char b[2];\nb[0] = STBIW_UCHAR(x);\nb[1] = STBIW_UCHAR(x>>8);\ns->func(s->context,b,2);\nbreak; }\ncase '4': { stbiw_uint32 x = va_arg(v,int);\nunsigned char b[4];\nb[0]=STBIW_UCHAR(x);\nb[1]=STBIW_UCHAR(x>>8);\nb[2]=STBIW_UCHAR(x>>16);\nb[3]=STBIW_UCHAR(x>>24);\ns->func(s->context,b,4);\nbreak; }\ndefault:\nSTBIW_ASSERT(0);\nreturn;\n}\n}\n}\nstatic void stbiw__writef(stbi__write_context *s, const char *fmt, ...)\n{\nva_list v;\nva_start(v, fmt);\nstbiw__writefv(s, fmt, v);\nva_end(v);\n}\nstatic void stbiw__putc(stbi__write_context *s, unsigned char c)\n{\ns->func(s->context, &c, 1);\n}\nstatic void stbiw__write3(stbi__write_context *s, unsigned char a, unsigned char b, unsigned char c)\n{\nunsigned char arr[3];\narr[0] = a; arr[1] = b; arr[2] = c;\ns->func(s->context, arr, 3);\n}\nstatic void stbiw__write_pixel(stbi__write_context *s, int rgb_dir, int comp, int write_alpha, int expand_mono, unsigned char *d)\n{\nunsigned char bg[3] = { 255, 0, 255}, px[3];\nint k;\nif (write_alpha < 0)\ns->func(s->context, &d[comp - 1], 1);\nswitch (comp) {\ncase 2: // 2 pixels = mono + alpha, alpha is written separately, so same as 1-channel case\ncase 1:\nif (expand_mono)\nstbiw__write3(s, d[0], d[0], d[0]); // monochrome bmp\nelse\ns->func(s->context, d, 1);  // monochrome TGA\nbreak;\ncase 4:\nif (!write_alpha) {\n// composite against pink background\nfor (k = 0; k < 3; ++k)\npx[k] = bg[k] + ((d[k] - bg[k]) * d[3]) / 255;\nstbiw__write3(s, px[1 - rgb_dir], px[1], px[1 + rgb_dir]);\nbreak;\n}\n/* FALLTHROUGH */\ncase 3:\nstbiw__write3(s, d[1 - rgb_dir], d[1], d[1 + rgb_dir]);\nbreak;\n}\nif (write_alpha > 0)\ns->func(s->context, &d[comp - 1], 1);\n}\nstatic void stbiw__write_pixels(stbi__write_context *s, int rgb_dir, int vdir, int x, int y, int comp, void *data, int write_alpha, int scanline_pad, int expand_mono)\n{\nstbiw_uint32 zero = 0;\nint i,j, j_end;\nif (y <= 0)\nreturn;\nif (stbi__flip_vertically_on_write)\nvdir *= -1;\nif (vdir < 0) {\nj_end = -1; j = y-1;\n} else {\nj_end =  y; j = 0;\n}\nfor (; j != j_end; j += vdir) {\nfor (i=0; i < x; ++i) {\nunsigned char *d = (unsigned char *) data + (j*x+i)*comp;\nstbiw__write_pixel(s, rgb_dir, comp, write_alpha, expand_mono, d);\n}\ns->func(s->context, &zero, scanline_pad);\n}\n}\nstatic int stbiw__outfile(stbi__write_context *s, int rgb_dir, int vdir, int x, int y, int comp, int expand_mono, void *data, int alpha, int pad, const char *fmt, ...)\n{\nif (y < 0 || x < 0) {\nreturn 0;\n} else {\nva_list v;\nva_start(v, fmt);\nstbiw__writefv(s, fmt, v);\nva_end(v);\nstbiw__write_pixels(s,rgb_dir,vdir,x,y,comp,data,alpha,pad, expand_mono);\nreturn 1;\n}\n}\nstatic int stbi_write_bmp_core(stbi__write_context *s, int x, int y, int comp, const void *data)\n{\nint pad = (-x*3) & 3;\nreturn stbiw__outfile(s,-1,-1,x,y,comp,1,(void *) data,0,pad,\n\"11 4 22 4\" \"4 44 22 444444\",\n'B', 'M', 14+40+(x*3+pad)*y, 0,0, 14+40,  // file header\n40, x,y, 1,24, 0,0,0,0,0,0);             // bitmap header\n}\nSTBIWDEF int stbi_write_bmp_to_func(stbi_write_func *func, void *context, int x, int y, int comp, const void *data)\n{\nstbi__write_context s;\nstbi__start_write_callbacks(&s, func, context);\nreturn stbi_write_bmp_core(&s, x, y, comp, data);\n}\n#ifndef STBI_WRITE_NO_STDIO\nSTBIWDEF int stbi_write_bmp(char const *filename, int x, int y, int comp, const void *data)\n{\nstbi__write_context s;\nif (stbi__start_write_file(&s,filename)) {\nint r = stbi_write_bmp_core(&s, x, y, comp, data);\nstbi__end_write_file(&s);\nreturn r;\n} else\nreturn 0;\n}\n#endif \nstatic int stbi_write_tga_core(stbi__write_context *s, int x, int y, int comp, void *data)\n{\nint has_alpha = (comp == 2 || comp == 4);\nint colorbytes = has_alpha ? comp-1 : comp;\nint format = colorbytes < 2 ? 3 : 2; // 3 color channels (RGB/RGBA) = 2, 1 color channel (Y/YA) = 3\nif (y < 0 || x < 0)\nreturn 0;\nif (!stbi_write_tga_with_rle) {\nreturn stbiw__outfile(s, -1, -1, x, y, comp, 0, (void *) data, has_alpha, 0,\n\"111 221 2222 11\", 0, 0, format, 0, 0, 0, 0, 0, x, y, (colorbytes + has_alpha) * 8, has_alpha * 8);\n} else {\nint i,j,k;\nint jend, jdir;\nstbiw__writef(s, \"111 221 2222 11\", 0,0,format+8, 0,0,0, 0,0,x,y, (colorbytes + has_alpha) * 8, has_alpha * 8);\nif (stbi__flip_vertically_on_write) {\nj = 0;\njend = y;\njdir = 1;\n} else {\nj = y-1;\njend = -1;\njdir = -1;\n}\nfor (; j != jend; j += jdir) {\nunsigned char *row = (unsigned char *) data + j * x * comp;\nint len;\nfor (i = 0; i < x; i += len) {\nunsigned char *begin = row + i * comp;\nint diff = 1;\nlen = 1;\nif (i < x - 1) {\n++len;\ndiff = memcmp(begin, row + (i + 1) * comp, comp);\nif (diff) {\nconst unsigned char *prev = begin;\nfor (k = i + 2; k < x && len < 128; ++k) {\nif (memcmp(prev, row + k * comp, comp)) {\nprev += comp;\n++len;\n} else {\n--len;\nbreak;\n}\n}\n} else {\nfor (k = i + 2; k < x && len < 128; ++k) {\nif (!memcmp(begin, row + k * comp, comp)) {\n++len;\n} else {\nbreak;\n}\n}\n}\n}\nif (diff) {\nunsigned char header = STBIW_UCHAR(len - 1);\ns->func(s->context, &header, 1);\nfor (k = 0; k < len; ++k) {\nstbiw__write_pixel(s, -1, comp, has_alpha, 0, begin + k * comp);\n}\n} else {\nunsigned char header = STBIW_UCHAR(len - 129);\ns->func(s->context, &header, 1);\nstbiw__write_pixel(s, -1, comp, has_alpha, 0, begin);\n}\n}\n}\n}\nreturn 1;\n}\nSTBIWDEF int stbi_write_tga_to_func(stbi_write_func *func, void *context, int x, int y, int comp, const void *data)\n{\nstbi__write_context s;\nstbi__start_write_callbacks(&s, func, context);\nreturn stbi_write_tga_core(&s, x, y, comp, (void *) data);\n}\n#ifndef STBI_WRITE_NO_STDIO\nSTBIWDEF int stbi_write_tga(char const *filename, int x, int y, int comp, const void *data)\n{\nstbi__write_context s;\nif (stbi__start_write_file(&s,filename)) {\nint r = stbi_write_tga_core(&s, x, y, comp, (void *) data);\nstbi__end_write_file(&s);\nreturn r;\n} else\nreturn 0;\n}\n#endif\n// *************************************************************************************************\n// Radiance RGBE HDR writer\n// by Baldur Karlsson\n#define stbiw__max(a, b)  ((a) > (b) ? (a) : (b))\nstatic void stbiw__linear_to_rgbe(unsigned char *rgbe, float *linear)\n{\nint exponent;\nfloat maxcomp = stbiw__max(linear[0], stbiw__max(linear[1], linear[2]));\nif (maxcomp < 1e-32f) {\nrgbe[0] = rgbe[1] = rgbe[2] = rgbe[3] = 0;\n} else {\nfloat normalize = (float) frexp(maxcomp, &exponent) * 256.0f/maxcomp;\nrgbe[0] = (unsigned char)(linear[0] * normalize);\nrgbe[1] = (unsigned char)(linear[1] * normalize);\nrgbe[2] = (unsigned char)(linear[2] * normalize);\nrgbe[3] = (unsigned char)(exponent + 128);\n}\n}\nstatic void stbiw__write_run_data(stbi__write_context *s, int length, unsigned char databyte)\n{\nunsigned char lengthbyte = STBIW_UCHAR(length+128);\nSTBIW_ASSERT(length+128 <= 255);\ns->func(s->context, &lengthbyte, 1);\ns->func(s->context, &databyte, 1);\n}\nstatic void stbiw__write_dump_data(stbi__write_context *s, int length, unsigned char *data)\n{\nunsigned char lengthbyte = STBIW_UCHAR(length);\nSTBIW_ASSERT(length <= 128); // inconsistent with spec but consistent with official code\ns->func(s->context, &lengthbyte, 1);\ns->func(s->context, data, length);\n}\nstatic void stbiw__write_hdr_scanline(stbi__write_context *s, int width, int ncomp, unsigned char *scratch, float *scanline)\n{\nunsigned char scanlineheader[4] = { 2, 2, 0, 0 };\nunsigned char rgbe[4];\nfloat linear[3];\nint x;\nscanlineheader[2] = (width&0xff00)>>8;\nscanlineheader[3] = (width&0x00ff);\n/* skip RLE for images too small or large */\nif (width < 8 || width >= 32768) {\nfor (x=0; x < width; x++) {\nswitch (ncomp) {\ncase 4: /* fallthrough */\ncase 3: linear[2] = scanline[x*ncomp + 2];\nlinear[1] = scanline[x*ncomp + 1];\nlinear[0] = scanline[x*ncomp + 0];\nbreak;\ndefault:\nlinear[0] = linear[1] = linear[2] = scanline[x*ncomp + 0];\nbreak;\n}\nstbiw__linear_to_rgbe(rgbe, linear);\ns->func(s->context, rgbe, 4);\n}\n} else {\nint c,r;\n/* encode into scratch buffer */\nfor (x=0; x < width; x++) {\nswitch(ncomp) {\ncase 4: /* fallthrough */\ncase 3: linear[2] = scanline[x*ncomp + 2];\nlinear[1] = scanline[x*ncomp + 1];\nlinear[0] = scanline[x*ncomp + 0];\nbreak;\ndefault:\nlinear[0] = linear[1] = linear[2] = scanline[x*ncomp + 0];\nbreak;\n}\nstbiw__linear_to_rgbe(rgbe, linear);\nscratch[x + width*0] = rgbe[0];\nscratch[x + width*1] = rgbe[1];\nscratch[x + width*2] = rgbe[2];\nscratch[x + width*3] = rgbe[3];\n}\ns->func(s->context, scanlineheader, 4);\n/* RLE each component separately */\nfor (c=0; c < 4; c++) {\nunsigned char *comp = &scratch[width*c];\nx = 0;\nwhile (x < width) {\n// find first run\nr = x;\nwhile (r+2 < width) {\nif (comp[r] == comp[r+1] && comp[r] == comp[r+2])\nbreak;\n++r;\n}\nif (r+2 >= width)\nr = width;\n// dump up to first run\nwhile (x < r) {\nint len = r-x;\nif (len > 128) len = 128;\nstbiw__write_dump_data(s, len, &comp[x]);\nx += len;\n}\n// if there's a run, output it\nif (r+2 < width) { // same test as what we break out of in search loop, so only true if we break'd\n// find next byte after run\nwhile (r < width && comp[r] == comp[x])\n++r;\n// output run up to r\nwhile (x < r) {\nint len = r-x;\nif (len > 127) len = 127;\nstbiw__write_run_data(s, len, comp[x]);\nx += len;\n}\n}\n}\n}\n}\n}\nstatic int stbi_write_hdr_core(stbi__write_context *s, int x, int y, int comp, float *data)\n{\nif (y <= 0 || x <= 0 || data == NULL)\nreturn 0;\nelse {\n// Each component is stored separately. Allocate scratch space for full output scanline.\nunsigned char *scratch = (unsigned char *) STBIW_MALLOC(x*4);\nint i, len;\nchar buffer[128];\nchar header[] = \"#?RADIANCE\\n# Written by stb_image_write.h\\nFORMAT=32-bit_rle_rgbe\\n\";\ns->func(s->context, header, sizeof(header)-1);\n#ifdef __STDC_WANT_SECURE_LIB__\nlen = sprintf_s(buffer, sizeof(buffer), \"EXPOSURE=          1.0000000000000\\n\\n-Y %d +X %d\\n\", y, x);\n#else\nlen = sprintf(buffer, \"EXPOSURE=          1.0000000000000\\n\\n-Y %d +X %d\\n\", y, x);\n#endif\ns->func(s->context, buffer, len);\nfor(i=0; i < y; i++)\nstbiw__write_hdr_scanline(s, x, comp, scratch, data + comp*x*(stbi__flip_vertically_on_write ? y-1-i : i));\nSTBIW_FREE(scratch);\nreturn 1;\n}\n}\nSTBIWDEF int stbi_write_hdr_to_func(stbi_write_func *func, void *context, int x, int y, int comp, const float *data)\n{\nstbi__write_context s;\nstbi__start_write_callbacks(&s, func, context);\nreturn stbi_write_hdr_core(&s, x, y, comp, (float *) data);\n}\n#ifndef STBI_WRITE_NO_STDIO\nSTBIWDEF int stbi_write_hdr(char const *filename, int x, int y, int comp, const float *data)\n{\nstbi__write_context s;\nif (stbi__start_write_file(&s,filename)) {\nint r = stbi_write_hdr_core(&s, x, y, comp, (float *) data);\nstbi__end_write_file(&s);\nreturn r;\n} else\nreturn 0;\n}\n#endif // STBI_WRITE_NO_STDIO\n//\n// PNG writer\n//\n#ifndef STBIW_ZLIB_COMPRESS\n// stretchy buffer; stbiw__sbpush() == vector<>::push_back() -- stbiw__sbcount() == vector<>::size()\n#define stbiw__sbraw(a) ((int *) (a) - 2)\n#define stbiw__sbm(a)   stbiw__sbraw(a)[0]\n#define stbiw__sbn(a)   stbiw__sbraw(a)[1]\n#define stbiw__sbneedgrow(a,n)  ((a)==0 || stbiw__sbn(a)+n >= stbiw__sbm(a))\n#define stbiw__sbmaybegrow(a,n) (stbiw__sbneedgrow(a,(n)) ? stbiw__sbgrow(a,n) : 0)\n#define stbiw__sbgrow(a,n)  stbiw__sbgrowf((void **) &(a), (n), sizeof(*(a)))\n#define stbiw__sbpush(a, v)      (stbiw__sbmaybegrow(a,1), (a)[stbiw__sbn(a)++] = (v))\n#define stbiw__sbcount(a)        ((a) ? stbiw__sbn(a) : 0)\n#define stbiw__sbfree(a)         ((a) ? STBIW_FREE(stbiw__sbraw(a)),0 : 0)\nstatic void *stbiw__sbgrowf(void **arr, int increment, int itemsize)\n{\nint m = *arr ? 2*stbiw__sbm(*arr)+increment : increment+1;\nvoid *p = STBIW_REALLOC_SIZED(*arr ? stbiw__sbraw(*arr) : 0, *arr ? (stbiw__sbm(*arr)*itemsize + sizeof(int)*2) : 0, itemsize * m + sizeof(int)*2);\nSTBIW_ASSERT(p);\nif (p) {\nif (!*arr) ((int *) p)[1] = 0;\n*arr = (void *) ((int *) p + 2);\nstbiw__sbm(*arr) = m;\n}\nreturn *arr;\n}\nstatic unsigned char *stbiw__zlib_flushf(unsigned char *data, unsigned int *bitbuffer, int *bitcount)\n{\nwhile (*bitcount >= 8) {\nstbiw__sbpush(data, STBIW_UCHAR(*bitbuffer));\n*bitbuffer >>= 8;\n*bitcount -= 8;\n}\nreturn data;\n}\nstatic int stbiw__zlib_bitrev(int code, int codebits)\n{\nint res=0;\nwhile (codebits--) {\nres = (res << 1) | (code & 1);\ncode >>= 1;\n}\nreturn res;\n}\nstatic unsigned int stbiw__zlib_countm(unsigned char *a, unsigned char *b, int limit)\n{\nint i;\nfor (i=0; i < limit && i < 258; ++i)\nif (a[i] != b[i]) break;\nreturn i;\n}\nstatic unsigned int stbiw__zhash(unsigned char *data)\n{\nstbiw_uint32 hash = data[0] + (data[1] << 8) + (data[2] << 16);\nhash ^= hash << 3;\nhash += hash >> 5;\nhash ^= hash << 4;\nhash += hash >> 17;\nhash ^= hash << 25;\nhash += hash >> 6;\nreturn hash;\n}\n#define stbiw__zlib_flush() (out = stbiw__zlib_flushf(out, &bitbuf, &bitcount))\n#define stbiw__zlib_add(code,codebits) \\\n      (bitbuf |= (code) << bitcount, bitcount += (codebits), stbiw__zlib_flush())\n#define stbiw__zlib_huffa(b,c)  stbiw__zlib_add(stbiw__zlib_bitrev(b,c),c)\n// default huffman tables\n#define stbiw__zlib_huff1(n)  stbiw__zlib_huffa(0x30 + (n), 8)\n#define stbiw__zlib_huff2(n)  stbiw__zlib_huffa(0x190 + (n)-144, 9)\n#define stbiw__zlib_huff3(n)  stbiw__zlib_huffa(0 + (n)-256,7)\n#define stbiw__zlib_huff4(n)  stbiw__zlib_huffa(0xc0 + (n)-280,8)\n#define stbiw__zlib_huff(n)  ((n) <= 143 ? stbiw__zlib_huff1(n) : (n) <= 255 ? stbiw__zlib_huff2(n) : (n) <= 279 ? stbiw__zlib_huff3(n) : stbiw__zlib_huff4(n))\n#define stbiw__zlib_huffb(n) ((n) <= 143 ? stbiw__zlib_huff1(n) : stbiw__zlib_huff2(n))\n#define stbiw__ZHASH   16384\n#endif // STBIW_ZLIB_COMPRESS\nSTBIWDEF unsigned char * stbi_zlib_compress(unsigned char *data, int data_len, int *out_len, int quality)\n{\n#ifdef STBIW_ZLIB_COMPRESS\n// user provided a zlib compress implementation, use that\nreturn STBIW_ZLIB_COMPRESS(data, data_len, out_len, quality);\n#else // use builtin\nstatic unsigned short lengthc[] = { 3,4,5,6,7,8,9,10,11,13,15,17,19,23,27,31,35,43,51,59,67,83,99,115,131,163,195,227,258, 259 };\nstatic unsigned char  lengtheb[]= { 0,0,0,0,0,0,0, 0, 1, 1, 1, 1, 2, 2, 2, 2, 3, 3, 3, 3, 4, 4, 4,  4,  5,  5,  5,  5,  0 };\nstatic unsigned short distc[]   = { 1,2,3,4,5,7,9,13,17,25,33,49,65,97,129,193,257,385,513,769,1025,1537,2049,3073,4097,6145,8193,12289,16385,24577, 32768 };\nstatic unsigned char  disteb[]  = { 0,0,0,0,1,1,2,2,3,3,4,4,5,5,6,6,7,7,8,8,9,9,10,10,11,11,12,12,13,13 };\nunsigned int bitbuf=0;\nint i,j, bitcount=0;\nunsigned char *out = NULL;\nunsigned char ***hash_table = (unsigned char***) STBIW_MALLOC(stbiw__ZHASH * sizeof(unsigned char**));\nif (hash_table == NULL)\nreturn NULL;\nif (quality < 5) quality = 5;\nstbiw__sbpush(out, 0x78);   // DEFLATE 32K window\nstbiw__sbpush(out, 0x5e);   // FLEVEL = 1\nstbiw__zlib_add(1,1);  // BFINAL = 1\nstbiw__zlib_add(1,2);  // BTYPE = 1 -- fixed huffman\nfor (i=0; i < stbiw__ZHASH; ++i)\nhash_table[i] = NULL;\ni=0;\nwhile (i < data_len-3) {\n// hash next 3 bytes of data to be compressed\nint h = stbiw__zhash(data+i)&(stbiw__ZHASH-1), best=3;\nunsigned char *bestloc = 0;\nunsigned char **hlist = hash_table[h];\nint n = stbiw__sbcount(hlist);\nfor (j=0; j < n; ++j) {\nif (hlist[j]-data > i-32768) { // if entry lies within window\nint d = stbiw__zlib_countm(hlist[j], data+i, data_len-i);\nif (d >= best) { best=d; bestloc=hlist[j]; }\n}\n}\n// when hash table entry is too long, delete half the entries\nif (hash_table[h] && stbiw__sbn(hash_table[h]) == 2*quality) {\nSTBIW_MEMMOVE(hash_table[h], hash_table[h]+quality, sizeof(hash_table[h][0])*quality);\nstbiw__sbn(hash_table[h]) = quality;\n}\nstbiw__sbpush(hash_table[h],data+i);\nif (bestloc) {\n// \"lazy matching\" - check match at *next* byte, and if it's better, do cur byte as literal\nh = stbiw__zhash(data+i+1)&(stbiw__ZHASH-1);\nhlist = hash_table[h];\nn = stbiw__sbcount(hlist);\nfor (j=0; j < n; ++j) {\nif (hlist[j]-data > i-32767) {\nint e = stbiw__zlib_countm(hlist[j], data+i+1, data_len-i-1);\nif (e > best) { // if next match is better, bail on current match\nbestloc = NULL;\nbreak;\n}\n}\n}\n}\nif (bestloc) {\nint d = (int) (data+i - bestloc); // distance back\nSTBIW_ASSERT(d <= 32767 && best <= 258);\nfor (j=0; best > lengthc[j+1]-1; ++j);\nstbiw__zlib_huff(j+257);\nif (lengtheb[j]) stbiw__zlib_add(best - lengthc[j], lengtheb[j]);\nfor (j=0; d > distc[j+1]-1; ++j);\nstbiw__zlib_add(stbiw__zlib_bitrev(j,5),5);\nif (disteb[j]) stbiw__zlib_add(d - distc[j], disteb[j]);\ni += best;\n} else {\nstbiw__zlib_huffb(data[i]);\n++i;\n}\n}\n// write out final bytes\nfor (;i < data_len; ++i)\nstbiw__zlib_huffb(data[i]);\nstbiw__zlib_huff(256); // end of block\n// pad with 0 bits to byte boundary\nwhile (bitcount)\nstbiw__zlib_add(0,1);\nfor (i=0; i < stbiw__ZHASH; ++i)\n(void) stbiw__sbfree(hash_table[i]);\nSTBIW_FREE(hash_table);\n{\n// compute adler32 on input\nunsigned int s1=1, s2=0;\nint blocklen = (int) (data_len % 5552);\nj=0;\nwhile (j < data_len) {\nfor (i=0; i < blocklen; ++i) { s1 += data[j+i]; s2 += s1; }\ns1 %= 65521; s2 %= 65521;\nj += blocklen;\nblocklen = 5552;\n}\nstbiw__sbpush(out, STBIW_UCHAR(s2 >> 8));\nstbiw__sbpush(out, STBIW_UCHAR(s2));\nstbiw__sbpush(out, STBIW_UCHAR(s1 >> 8));\nstbiw__sbpush(out, STBIW_UCHAR(s1));\n}\n*out_len = stbiw__sbn(out);\n// make returned pointer freeable\nSTBIW_MEMMOVE(stbiw__sbraw(out), out, *out_len);\nreturn (unsigned char *) stbiw__sbraw(out);\n#endif // STBIW_ZLIB_COMPRESS\n}\nstatic unsigned int stbiw__crc32(unsigned char *buffer, int len)\n{\n#ifdef STBIW_CRC32\nreturn STBIW_CRC32(buffer, len);\n#else\nstatic unsigned int crc_table[256] =\n{\n0x00000000, 0x77073096, 0xEE0E612C, 0x990951BA, 0x076DC419, 0x706AF48F, 0xE963A535, 0x9E6495A3,\n0x0eDB8832, 0x79DCB8A4, 0xE0D5E91E, 0x97D2D988, 0x09B64C2B, 0x7EB17CBD, 0xE7B82D07, 0x90BF1D91,\n0x1DB71064, 0x6AB020F2, 0xF3B97148, 0x84BE41DE, 0x1ADAD47D, 0x6DDDE4EB, 0xF4D4B551, 0x83D385C7,\n0x136C9856, 0x646BA8C0, 0xFD62F97A, 0x8A65C9EC, 0x14015C4F, 0x63066CD9, 0xFA0F3D63, 0x8D080DF5,\n0x3B6E20C8, 0x4C69105E, 0xD56041E4, 0xA2677172, 0x3C03E4D1, 0x4B04D447, 0xD20D85FD, 0xA50AB56B,\n0x35B5A8FA, 0x42B2986C, 0xDBBBC9D6, 0xACBCF940, 0x32D86CE3, 0x45DF5C75, 0xDCD60DCF, 0xABD13D59,\n0x26D930AC, 0x51DE003A, 0xC8D75180, 0xBFD06116, 0x21B4F4B5, 0x56B3C423, 0xCFBA9599, 0xB8BDA50F,\n0x2802B89E, 0x5F058808, 0xC60CD9B2, 0xB10BE924, 0x2F6F7C87, 0x58684C11, 0xC1611DAB, 0xB6662D3D,\n0x76DC4190, 0x01DB7106, 0x98D220BC, 0xEFD5102A, 0x71B18589, 0x06B6B51F, 0x9FBFE4A5, 0xE8B8D433,\n0x7807C9A2, 0x0F00F934, 0x9609A88E, 0xE10E9818, 0x7F6A0DBB, 0x086D3D2D, 0x91646C97, 0xE6635C01,\n0x6B6B51F4, 0x1C6C6162, 0x856530D8, 0xF262004E, 0x6C0695ED, 0x1B01A57B, 0x8208F4C1, 0xF50FC457,\n0x65B0D9C6, 0x12B7E950, 0x8BBEB8EA, 0xFCB9887C, 0x62DD1DDF, 0x15DA2D49, 0x8CD37CF3, 0xFBD44C65,\n0x4DB26158, 0x3AB551CE, 0xA3BC0074, 0xD4BB30E2, 0x4ADFA541, 0x3DD895D7, 0xA4D1C46D, 0xD3D6F4FB,\n0x4369E96A, 0x346ED9FC, 0xAD678846, 0xDA60B8D0, 0x44042D73, 0x33031DE5, 0xAA0A4C5F, 0xDD0D7CC9,\n0x5005713C, 0x270241AA, 0xBE0B1010, 0xC90C2086, 0x5768B525, 0x206F85B3, 0xB966D409, 0xCE61E49F,\n0x5EDEF90E, 0x29D9C998, 0xB0D09822, 0xC7D7A8B4, 0x59B33D17, 0x2EB40D81, 0xB7BD5C3B, 0xC0BA6CAD,\n0xEDB88320, 0x9ABFB3B6, 0x03B6E20C, 0x74B1D29A, 0xEAD54739, 0x9DD277AF, 0x04DB2615, 0x73DC1683,\n0xE3630B12, 0x94643B84, 0x0D6D6A3E, 0x7A6A5AA8, 0xE40ECF0B, 0x9309FF9D, 0x0A00AE27, 0x7D079EB1,\n0xF00F9344, 0x8708A3D2, 0x1E01F268, 0x6906C2FE, 0xF762575D, 0x806567CB, 0x196C3671, 0x6E6B06E7,\n0xFED41B76, 0x89D32BE0, 0x10DA7A5A, 0x67DD4ACC, 0xF9B9DF6F, 0x8EBEEFF9, 0x17B7BE43, 0x60B08ED5,\n0xD6D6A3E8, 0xA1D1937E, 0x38D8C2C4, 0x4FDFF252, 0xD1BB67F1, 0xA6BC5767, 0x3FB506DD, 0x48B2364B,\n0xD80D2BDA, 0xAF0A1B4C, 0x36034AF6, 0x41047A60, 0xDF60EFC3, 0xA867DF55, 0x316E8EEF, 0x4669BE79,\n0xCB61B38C, 0xBC66831A, 0x256FD2A0, 0x5268E236, 0xCC0C7795, 0xBB0B4703, 0x220216B9, 0x5505262F,\n0xC5BA3BBE, 0xB2BD0B28, 0x2BB45A92, 0x5CB36A04, 0xC2D7FFA7, 0xB5D0CF31, 0x2CD99E8B, 0x5BDEAE1D,\n0x9B64C2B0, 0xEC63F226, 0x756AA39C, 0x026D930A, 0x9C0906A9, 0xEB0E363F, 0x72076785, 0x05005713,\n0x95BF4A82, 0xE2B87A14, 0x7BB12BAE, 0x0CB61B38, 0x92D28E9B, 0xE5D5BE0D, 0x7CDCEFB7, 0x0BDBDF21,\n0x86D3D2D4, 0xF1D4E242, 0x68DDB3F8, 0x1FDA836E, 0x81BE16CD, 0xF6B9265B, 0x6FB077E1, 0x18B74777,\n0x88085AE6, 0xFF0F6A70, 0x66063BCA, 0x11010B5C, 0x8F659EFF, 0xF862AE69, 0x616BFFD3, 0x166CCF45,\n0xA00AE278, 0xD70DD2EE, 0x4E048354, 0x3903B3C2, 0xA7672661, 0xD06016F7, 0x4969474D, 0x3E6E77DB,\n0xAED16A4A, 0xD9D65ADC, 0x40DF0B66, 0x37D83BF0, 0xA9BCAE53, 0xDEBB9EC5, 0x47B2CF7F, 0x30B5FFE9,\n0xBDBDF21C, 0xCABAC28A, 0x53B39330, 0x24B4A3A6, 0xBAD03605, 0xCDD70693, 0x54DE5729, 0x23D967BF,\n0xB3667A2E, 0xC4614AB8, 0x5D681B02, 0x2A6F2B94, 0xB40BBE37, 0xC30C8EA1, 0x5A05DF1B, 0x2D02EF8D\n};\nunsigned int crc = ~0u;\nint i;\nfor (i=0; i < len; ++i)\ncrc = (crc >> 8) ^ crc_table[buffer[i] ^ (crc & 0xff)];\nreturn ~crc;\n#endif\n}\n#define stbiw__wpng4(o,a,b,c,d) ((o)[0]=STBIW_UCHAR(a),(o)[1]=STBIW_UCHAR(b),(o)[2]=STBIW_UCHAR(c),(o)[3]=STBIW_UCHAR(d),(o)+=4)\n#define stbiw__wp32(data,v) stbiw__wpng4(data, (v)>>24,(v)>>16,(v)>>8,(v));\n#define stbiw__wptag(data,s) stbiw__wpng4(data, s[0],s[1],s[2],s[3])\nstatic void stbiw__wpcrc(unsigned char **data, int len)\n{\nunsigned int crc = stbiw__crc32(*data - len - 4, len+4);\nstbiw__wp32(*data, crc);\n}\nstatic unsigned char stbiw__paeth(int a, int b, int c)\n{\nint p = a + b - c, pa = abs(p-a), pb = abs(p-b), pc = abs(p-c);\nif (pa <= pb && pa <= pc) return STBIW_UCHAR(a);\nif (pb <= pc) return STBIW_UCHAR(b);\nreturn STBIW_UCHAR(c);\n}\n// @OPTIMIZE: provide an option that always forces left-predict or paeth predict\nstatic void stbiw__encode_png_line(unsigned char *pixels, int stride_bytes, int width, int height, int y, int n, int filter_type, signed char *line_buffer)\n{\nstatic int mapping[] = { 0,1,2,3,4 };\nstatic int firstmap[] = { 0,1,0,5,6 };\nint *mymap = (y != 0) ? mapping : firstmap;\nint i;\nint type = mymap[filter_type];\nunsigned char *z = pixels + stride_bytes * (stbi__flip_vertically_on_write ? height-1-y : y);\nint signed_stride = stbi__flip_vertically_on_write ? -stride_bytes : stride_bytes;\nif (type==0) {\nmemcpy(line_buffer, z, width*n);\nreturn;\n}\n// first loop isn't optimized since it's just one pixel    \nfor (i = 0; i < n; ++i) {\nswitch (type) {\ncase 1: line_buffer[i] = z[i]; break;\ncase 2: line_buffer[i] = z[i] - z[i-signed_stride]; break;\ncase 3: line_buffer[i] = z[i] - (z[i-signed_stride]>>1); break;\ncase 4: line_buffer[i] = (signed char) (z[i] - stbiw__paeth(0,z[i-signed_stride],0)); break;\ncase 5: line_buffer[i] = z[i]; break;\ncase 6: line_buffer[i] = z[i]; break;\n}\n}\nswitch (type) {\ncase 1: for (i=n; i < width*n; ++i) line_buffer[i] = z[i] - z[i-n]; break;\ncase 2: for (i=n; i < width*n; ++i) line_buffer[i] = z[i] - z[i-signed_stride]; break;\ncase 3: for (i=n; i < width*n; ++i) line_buffer[i] = z[i] - ((z[i-n] + z[i-signed_stride])>>1); break;\ncase 4: for (i=n; i < width*n; ++i) line_buffer[i] = z[i] - stbiw__paeth(z[i-n], z[i-signed_stride], z[i-signed_stride-n]); break;\ncase 5: for (i=n; i < width*n; ++i) line_buffer[i] = z[i] - (z[i-n]>>1); break;\ncase 6: for (i=n; i < width*n; ++i) line_buffer[i] = z[i] - stbiw__paeth(z[i-n], 0,0); break;\n}\n}\nSTBIWDEF unsigned char *stbi_write_png_to_mem(const unsigned char *pixels, int stride_bytes, int x, int y, int n, int *out_len)\n{\nint force_filter = stbi_write_force_png_filter;\nint ctype[5] = { -1, 0, 4, 2, 6 };\nunsigned char sig[8] = { 137,80,78,71,13,10,26,10 };\nunsigned char *out,*o, *filt, *zlib;\nsigned char *line_buffer;\nint j,zlen;\nif (stride_bytes == 0)\nstride_bytes = x * n;\nif (force_filter >= 5) {\nforce_filter = -1;\n}\nfilt = (unsigned char *) STBIW_MALLOC((x*n+1) * y); if (!filt) return 0;\nline_buffer = (signed char *) STBIW_MALLOC(x * n); if (!line_buffer) { STBIW_FREE(filt); return 0; }\nfor (j=0; j < y; ++j) {\nint filter_type;\nif (force_filter > -1) {\nfilter_type = force_filter;\nstbiw__encode_png_line((unsigned char*)(pixels), stride_bytes, x, y, j, n, force_filter, line_buffer);\n} else { // Estimate the best filter by running through all of them:\nint best_filter = 0, best_filter_val = 0x7fffffff, est, i;\nfor (filter_type = 0; filter_type < 5; filter_type++) {\nstbiw__encode_png_line((unsigned char*)(pixels), stride_bytes, x, y, j, n, filter_type, line_buffer);\n// Estimate the entropy of the line using this filter; the less, the better.\nest = 0;\nfor (i = 0; i < x*n; ++i) {\nest += abs((signed char) line_buffer[i]);\n}\nif (est < best_filter_val) {\nbest_filter_val = est;\nbest_filter = filter_type;\n}\n}\nif (filter_type != best_filter) {  // If the last iteration already got us the best filter, don't redo it\nstbiw__encode_png_line((unsigned char*)(pixels), stride_bytes, x, y, j, n, best_filter, line_buffer);\nfilter_type = best_filter;\n}\n}\n// when we get here, filter_type contains the filter type, and line_buffer contains the data\nfilt[j*(x*n+1)] = (unsigned char) filter_type;\nSTBIW_MEMMOVE(filt+j*(x*n+1)+1, line_buffer, x*n);\n}\nSTBIW_FREE(line_buffer);\nzlib = stbi_zlib_compress(filt, y*( x*n+1), &zlen, stbi_write_png_compression_level);\nSTBIW_FREE(filt);\nif (!zlib) return 0;\n// each tag requires 12 bytes of overhead\nout = (unsigned char *) STBIW_MALLOC(8 + 12+13 + 12+zlen + 12);\nif (!out) return 0;\n*out_len = 8 + 12+13 + 12+zlen + 12;\no=out;\nSTBIW_MEMMOVE(o,sig,8); o+= 8;\nstbiw__wp32(o, 13); // header length\nstbiw__wptag(o, \"IHDR\");\nstbiw__wp32(o, x);\nstbiw__wp32(o, y);\n*o++ = 8;\n*o++ = STBIW_UCHAR(ctype[n]);\n*o++ = 0;\n*o++ = 0;\n*o++ = 0;\nstbiw__wpcrc(&o,13);\nstbiw__wp32(o, zlen);\nstbiw__wptag(o, \"IDAT\");\nSTBIW_MEMMOVE(o, zlib, zlen);\no += zlen;\nSTBIW_FREE(zlib);\nstbiw__wpcrc(&o, zlen);\nstbiw__wp32(o,0);\nstbiw__wptag(o, \"IEND\");\nstbiw__wpcrc(&o,0);\nSTBIW_ASSERT(o == out + *out_len);\nreturn out;\n}\n#ifndef STBI_WRITE_NO_STDIO\nSTBIWDEF int stbi_write_png(char const *filename, int x, int y, int comp, const void *data, int stride_bytes)\n{\nFILE *f;\nint len;\nunsigned char *png = stbi_write_png_to_mem((const unsigned char *) data, stride_bytes, x, y, comp, &len);\nif (png == NULL) return 0;\nf = stbiw__fopen(filename, \"wb\");\nif (!f) { STBIW_FREE(png); return 0; }\nfwrite(png, 1, len, f);\nfclose(f);\nSTBIW_FREE(png);\nreturn 1;\n}\n#endif\nSTBIWDEF int stbi_write_png_to_func(stbi_write_func *func, void *context, int x, int y, int comp, const void *data, int stride_bytes)\n{\nint len;\nunsigned char *png = stbi_write_png_to_mem((const unsigned char *) data, stride_bytes, x, y, comp, &len);\nif (png == NULL) return 0;\nfunc(context, png, len);\nSTBIW_FREE(png);\nreturn 1;\n}\n/* ***************************************************************************\n *\n * JPEG writer\n *\n * This is based on Jon Olick's jo_jpeg.cpp:\n * public domain Simple, Minimalistic JPEG writer - http://www.jonolick.com/code.html\n */\nstatic const unsigned char stbiw__jpg_ZigZag[] = { 0,1,5,6,14,15,27,28,2,4,7,13,16,26,29,42,3,8,12,17,25,30,41,43,9,11,18,\n24,31,40,44,53,10,19,23,32,39,45,52,54,20,22,33,38,46,51,55,60,21,34,37,47,50,56,59,61,35,36,48,49,57,58,62,63 };\nstatic void stbiw__jpg_writeBits(stbi__write_context *s, int *bitBufP, int *bitCntP, const unsigned short *bs) {\nint bitBuf = *bitBufP, bitCnt = *bitCntP;\nbitCnt += bs[1];\nbitBuf |= bs[0] << (24 - bitCnt);\nwhile(bitCnt >= 8) {\nunsigned char c = (bitBuf >> 16) & 255;\nstbiw__putc(s, c);\nif(c == 255) {\nstbiw__putc(s, 0);\n}\nbitBuf <<= 8;\nbitCnt -= 8;\n}\n*bitBufP = bitBuf;\n*bitCntP = bitCnt;\n}\nstatic void stbiw__jpg_DCT(float *d0p, float *d1p, float *d2p, float *d3p, float *d4p, float *d5p, float *d6p, float *d7p) {\nfloat d0 = *d0p, d1 = *d1p, d2 = *d2p, d3 = *d3p, d4 = *d4p, d5 = *d5p, d6 = *d6p, d7 = *d7p;\nfloat z1, z2, z3, z4, z5, z11, z13;\nfloat tmp0 = d0 + d7;\nfloat tmp7 = d0 - d7;\nfloat tmp1 = d1 + d6;\nfloat tmp6 = d1 - d6;\nfloat tmp2 = d2 + d5;\nfloat tmp5 = d2 - d5;\nfloat tmp3 = d3 + d4;\nfloat tmp4 = d3 - d4;\n// Even part\nfloat tmp10 = tmp0 + tmp3;   // phase 2\nfloat tmp13 = tmp0 - tmp3;\nfloat tmp11 = tmp1 + tmp2;\nfloat tmp12 = tmp1 - tmp2;\nd0 = tmp10 + tmp11;       // phase 3\nd4 = tmp10 - tmp11;\nz1 = (tmp12 + tmp13) * 0.707106781f; // c4\nd2 = tmp13 + z1;       // phase 5\nd6 = tmp13 - z1;\n// Odd part\ntmp10 = tmp4 + tmp5;       // phase 2\ntmp11 = tmp5 + tmp6;\ntmp12 = tmp6 + tmp7;\n// The rotator is modified from fig 4-8 to avoid extra negations.\nz5 = (tmp10 - tmp12) * 0.382683433f; // c6\nz2 = tmp10 * 0.541196100f + z5; // c2-c6\nz4 = tmp12 * 1.306562965f + z5; // c2+c6\nz3 = tmp11 * 0.707106781f; // c4\nz11 = tmp7 + z3;      // phase 5\nz13 = tmp7 - z3;\n*d5p = z13 + z2;         // phase 6\n*d3p = z13 - z2;\n*d1p = z11 + z4;\n*d7p = z11 - z4;\n*d0p = d0;  *d2p = d2;  *d4p = d4;  *d6p = d6;\n}\nstatic void stbiw__jpg_calcBits(int val, unsigned short bits[2]) {\nint tmp1 = val < 0 ? -val : val;\nval = val < 0 ? val-1 : val;\nbits[1] = 1;\nwhile(tmp1 >>= 1) {\n++bits[1];\n}\nbits[0] = val & ((1<<bits[1])-1);\n}\nstatic int stbiw__jpg_processDU(stbi__write_context *s, int *bitBuf, int *bitCnt, float *CDU, float *fdtbl, int DC, const unsigned short HTDC[256][2], const unsigned short HTAC[256][2]) {\nconst unsigned short EOB[2] = { HTAC[0x00][0], HTAC[0x00][1] };\nconst unsigned short M16zeroes[2] = { HTAC[0xF0][0], HTAC[0xF0][1] };\nint dataOff, i, diff, end0pos;\nint DU[64];\n// DCT rows\nfor(dataOff=0; dataOff<64; dataOff+=8) {\nstbiw__jpg_DCT(&CDU[dataOff], &CDU[dataOff+1], &CDU[dataOff+2], &CDU[dataOff+3], &CDU[dataOff+4], &CDU[dataOff+5], &CDU[dataOff+6], &CDU[dataOff+7]);\n}\n// DCT columns\nfor(dataOff=0; dataOff<8; ++dataOff) {\nstbiw__jpg_DCT(&CDU[dataOff], &CDU[dataOff+8], &CDU[dataOff+16], &CDU[dataOff+24], &CDU[dataOff+32], &CDU[dataOff+40], &CDU[dataOff+48], &CDU[dataOff+56]);\n}\n// Quantize/descale/zigzag the coefficients\nfor(i=0; i<64; ++i) {\nfloat v = CDU[i]*fdtbl[i];\n// DU[stbiw__jpg_ZigZag[i]] = (int)(v < 0 ? ceilf(v - 0.5f) : floorf(v + 0.5f));\n// ceilf() and floorf() are C99, not C89, but I /think/ they're not needed here anyway?\nDU[stbiw__jpg_ZigZag[i]] = (int)(v < 0 ? v - 0.5f : v + 0.5f);\n}\n// Encode DC\ndiff = DU[0] - DC;\nif (diff == 0) {\nstbiw__jpg_writeBits(s, bitBuf, bitCnt, HTDC[0]);\n} else {\nunsigned short bits[2];\nstbiw__jpg_calcBits(diff, bits);\nstbiw__jpg_writeBits(s, bitBuf, bitCnt, HTDC[bits[1]]);\nstbiw__jpg_writeBits(s, bitBuf, bitCnt, bits);\n}\n// Encode ACs\nend0pos = 63;\nfor(; (end0pos>0)&&(DU[end0pos]==0); --end0pos) {\n}\n// end0pos = first element in reverse order !=0\nif(end0pos == 0) {\nstbiw__jpg_writeBits(s, bitBuf, bitCnt, EOB);\nreturn DU[0];\n}\nfor(i = 1; i <= end0pos; ++i) {\nint startpos = i;\nint nrzeroes;\nunsigned short bits[2];\nfor (; DU[i]==0 && i<=end0pos; ++i) {\n}\nnrzeroes = i-startpos;\nif ( nrzeroes >= 16 ) {\nint lng = nrzeroes>>4;\nint nrmarker;\nfor (nrmarker=1; nrmarker <= lng; ++nrmarker)\nstbiw__jpg_writeBits(s, bitBuf, bitCnt, M16zeroes);\nnrzeroes &= 15;\n}\nstbiw__jpg_calcBits(DU[i], bits);\nstbiw__jpg_writeBits(s, bitBuf, bitCnt, HTAC[(nrzeroes<<4)+bits[1]]);\nstbiw__jpg_writeBits(s, bitBuf, bitCnt, bits);\n}\nif(end0pos != 63) {\nstbiw__jpg_writeBits(s, bitBuf, bitCnt, EOB);\n}\nreturn DU[0];\n}\nstatic int stbi_write_jpg_core(stbi__write_context *s, int width, int height, int comp, const void* data, int quality) {\n// Constants that don't pollute global namespace\nstatic const unsigned char std_dc_luminance_nrcodes[] = {0,0,1,5,1,1,1,1,1,1,0,0,0,0,0,0,0};\nstatic const unsigned char std_dc_luminance_values[] = {0,1,2,3,4,5,6,7,8,9,10,11};\nstatic const unsigned char std_ac_luminance_nrcodes[] = {0,0,2,1,3,3,2,4,3,5,5,4,4,0,0,1,0x7d};\nstatic const unsigned char std_ac_luminance_values[] = {\n0x01,0x02,0x03,0x00,0x04,0x11,0x05,0x12,0x21,0x31,0x41,0x06,0x13,0x51,0x61,0x07,0x22,0x71,0x14,0x32,0x81,0x91,0xa1,0x08,\n0x23,0x42,0xb1,0xc1,0x15,0x52,0xd1,0xf0,0x24,0x33,0x62,0x72,0x82,0x09,0x0a,0x16,0x17,0x18,0x19,0x1a,0x25,0x26,0x27,0x28,\n0x29,0x2a,0x34,0x35,0x36,0x37,0x38,0x39,0x3a,0x43,0x44,0x45,0x46,0x47,0x48,0x49,0x4a,0x53,0x54,0x55,0x56,0x57,0x58,0x59,\n0x5a,0x63,0x64,0x65,0x66,0x67,0x68,0x69,0x6a,0x73,0x74,0x75,0x76,0x77,0x78,0x79,0x7a,0x83,0x84,0x85,0x86,0x87,0x88,0x89,\n0x8a,0x92,0x93,0x94,0x95,0x96,0x97,0x98,0x99,0x9a,0xa2,0xa3,0xa4,0xa5,0xa6,0xa7,0xa8,0xa9,0xaa,0xb2,0xb3,0xb4,0xb5,0xb6,\n0xb7,0xb8,0xb9,0xba,0xc2,0xc3,0xc4,0xc5,0xc6,0xc7,0xc8,0xc9,0xca,0xd2,0xd3,0xd4,0xd5,0xd6,0xd7,0xd8,0xd9,0xda,0xe1,0xe2,\n0xe3,0xe4,0xe5,0xe6,0xe7,0xe8,0xe9,0xea,0xf1,0xf2,0xf3,0xf4,0xf5,0xf6,0xf7,0xf8,0xf9,0xfa\n};\nstatic const unsigned char std_dc_chrominance_nrcodes[] = {0,0,3,1,1,1,1,1,1,1,1,1,0,0,0,0,0};\nstatic const unsigned char std_dc_chrominance_values[] = {0,1,2,3,4,5,6,7,8,9,10,11};\nstatic const unsigned char std_ac_chrominance_nrcodes[] = {0,0,2,1,2,4,4,3,4,7,5,4,4,0,1,2,0x77};\nstatic const unsigned char std_ac_chrominance_values[] = {\n0x00,0x01,0x02,0x03,0x11,0x04,0x05,0x21,0x31,0x06,0x12,0x41,0x51,0x07,0x61,0x71,0x13,0x22,0x32,0x81,0x08,0x14,0x42,0x91,\n0xa1,0xb1,0xc1,0x09,0x23,0x33,0x52,0xf0,0x15,0x62,0x72,0xd1,0x0a,0x16,0x24,0x34,0xe1,0x25,0xf1,0x17,0x18,0x19,0x1a,0x26,\n0x27,0x28,0x29,0x2a,0x35,0x36,0x37,0x38,0x39,0x3a,0x43,0x44,0x45,0x46,0x47,0x48,0x49,0x4a,0x53,0x54,0x55,0x56,0x57,0x58,\n0x59,0x5a,0x63,0x64,0x65,0x66,0x67,0x68,0x69,0x6a,0x73,0x74,0x75,0x76,0x77,0x78,0x79,0x7a,0x82,0x83,0x84,0x85,0x86,0x87,\n0x88,0x89,0x8a,0x92,0x93,0x94,0x95,0x96,0x97,0x98,0x99,0x9a,0xa2,0xa3,0xa4,0xa5,0xa6,0xa7,0xa8,0xa9,0xaa,0xb2,0xb3,0xb4,\n0xb5,0xb6,0xb7,0xb8,0xb9,0xba,0xc2,0xc3,0xc4,0xc5,0xc6,0xc7,0xc8,0xc9,0xca,0xd2,0xd3,0xd4,0xd5,0xd6,0xd7,0xd8,0xd9,0xda,\n0xe2,0xe3,0xe4,0xe5,0xe6,0xe7,0xe8,0xe9,0xea,0xf2,0xf3,0xf4,0xf5,0xf6,0xf7,0xf8,0xf9,0xfa\n};\n// Huffman tables\nstatic const unsigned short YDC_HT[256][2] = { {0,2},{2,3},{3,3},{4,3},{5,3},{6,3},{14,4},{30,5},{62,6},{126,7},{254,8},{510,9}};\nstatic const unsigned short UVDC_HT[256][2] = { {0,2},{1,2},{2,2},{6,3},{14,4},{30,5},{62,6},{126,7},{254,8},{510,9},{1022,10},{2046,11}};\nstatic const unsigned short YAC_HT[256][2] = {\n{10,4},{0,2},{1,2},{4,3},{11,4},{26,5},{120,7},{248,8},{1014,10},{65410,16},{65411,16},{0,0},{0,0},{0,0},{0,0},{0,0},{0,0},\n{12,4},{27,5},{121,7},{502,9},{2038,11},{65412,16},{65413,16},{65414,16},{65415,16},{65416,16},{0,0},{0,0},{0,0},{0,0},{0,0},{0,0},\n{28,5},{249,8},{1015,10},{4084,12},{65417,16},{65418,16},{65419,16},{65420,16},{65421,16},{65422,16},{0,0},{0,0},{0,0},{0,0},{0,0},{0,0},\n{58,6},{503,9},{4085,12},{65423,16},{65424,16},{65425,16},{65426,16},{65427,16},{65428,16},{65429,16},{0,0},{0,0},{0,0},{0,0},{0,0},{0,0},\n{59,6},{1016,10},{65430,16},{65431,16},{65432,16},{65433,16},{65434,16},{65435,16},{65436,16},{65437,16},{0,0},{0,0},{0,0},{0,0},{0,0},{0,0},\n{122,7},{2039,11},{65438,16},{65439,16},{65440,16},{65441,16},{65442,16},{65443,16},{65444,16},{65445,16},{0,0},{0,0},{0,0},{0,0},{0,0},{0,0},\n{123,7},{4086,12},{65446,16},{65447,16},{65448,16},{65449,16},{65450,16},{65451,16},{65452,16},{65453,16},{0,0},{0,0},{0,0},{0,0},{0,0},{0,0},\n{250,8},{4087,12},{65454,16},{65455,16},{65456,16},{65457,16},{65458,16},{65459,16},{65460,16},{65461,16},{0,0},{0,0},{0,0},{0,0},{0,0},{0,0},\n{504,9},{32704,15},{65462,16},{65463,16},{65464,16},{65465,16},{65466,16},{65467,16},{65468,16},{65469,16},{0,0},{0,0},{0,0},{0,0},{0,0},{0,0},\n{505,9},{65470,16},{65471,16},{65472,16},{65473,16},{65474,16},{65475,16},{65476,16},{65477,16},{65478,16},{0,0},{0,0},{0,0},{0,0},{0,0},{0,0},\n{506,9},{65479,16},{65480,16},{65481,16},{65482,16},{65483,16},{65484,16},{65485,16},{65486,16},{65487,16},{0,0},{0,0},{0,0},{0,0},{0,0},{0,0},\n{1017,10},{65488,16},{65489,16},{65490,16},{65491,16},{65492,16},{65493,16},{65494,16},{65495,16},{65496,16},{0,0},{0,0},{0,0},{0,0},{0,0},{0,0},\n{1018,10},{65497,16},{65498,16},{65499,16},{65500,16},{65501,16},{65502,16},{65503,16},{65504,16},{65505,16},{0,0},{0,0},{0,0},{0,0},{0,0},{0,0},\n{2040,11},{65506,16},{65507,16},{65508,16},{65509,16},{65510,16},{65511,16},{65512,16},{65513,16},{65514,16},{0,0},{0,0},{0,0},{0,0},{0,0},{0,0},\n{65515,16},{65516,16},{65517,16},{65518,16},{65519,16},{65520,16},{65521,16},{65522,16},{65523,16},{65524,16},{0,0},{0,0},{0,0},{0,0},{0,0},\n{2041,11},{65525,16},{65526,16},{65527,16},{65528,16},{65529,16},{65530,16},{65531,16},{65532,16},{65533,16},{65534,16},{0,0},{0,0},{0,0},{0,0},{0,0}\n};\nstatic const unsigned short UVAC_HT[256][2] = {\n{0,2},{1,2},{4,3},{10,4},{24,5},{25,5},{56,6},{120,7},{500,9},{1014,10},{4084,12},{0,0},{0,0},{0,0},{0,0},{0,0},{0,0},\n{11,4},{57,6},{246,8},{501,9},{2038,11},{4085,12},{65416,16},{65417,16},{65418,16},{65419,16},{0,0},{0,0},{0,0},{0,0},{0,0},{0,0},\n{26,5},{247,8},{1015,10},{4086,12},{32706,15},{65420,16},{65421,16},{65422,16},{65423,16},{65424,16},{0,0},{0,0},{0,0},{0,0},{0,0},{0,0},\n{27,5},{248,8},{1016,10},{4087,12},{65425,16},{65426,16},{65427,16},{65428,16},{65429,16},{65430,16},{0,0},{0,0},{0,0},{0,0},{0,0},{0,0},\n{58,6},{502,9},{65431,16},{65432,16},{65433,16},{65434,16},{65435,16},{65436,16},{65437,16},{65438,16},{0,0},{0,0},{0,0},{0,0},{0,0},{0,0},\n{59,6},{1017,10},{65439,16},{65440,16},{65441,16},{65442,16},{65443,16},{65444,16},{65445,16},{65446,16},{0,0},{0,0},{0,0},{0,0},{0,0},{0,0},\n{121,7},{2039,11},{65447,16},{65448,16},{65449,16},{65450,16},{65451,16},{65452,16},{65453,16},{65454,16},{0,0},{0,0},{0,0},{0,0},{0,0},{0,0},\n{122,7},{2040,11},{65455,16},{65456,16},{65457,16},{65458,16},{65459,16},{65460,16},{65461,16},{65462,16},{0,0},{0,0},{0,0},{0,0},{0,0},{0,0},\n{249,8},{65463,16},{65464,16},{65465,16},{65466,16},{65467,16},{65468,16},{65469,16},{65470,16},{65471,16},{0,0},{0,0},{0,0},{0,0},{0,0},{0,0},\n{503,9},{65472,16},{65473,16},{65474,16},{65475,16},{65476,16},{65477,16},{65478,16},{65479,16},{65480,16},{0,0},{0,0},{0,0},{0,0},{0,0},{0,0},\n{504,9},{65481,16},{65482,16},{65483,16},{65484,16},{65485,16},{65486,16},{65487,16},{65488,16},{65489,16},{0,0},{0,0},{0,0},{0,0},{0,0},{0,0},\n{505,9},{65490,16},{65491,16},{65492,16},{65493,16},{65494,16},{65495,16},{65496,16},{65497,16},{65498,16},{0,0},{0,0},{0,0},{0,0},{0,0},{0,0},\n{506,9},{65499,16},{65500,16},{65501,16},{65502,16},{65503,16},{65504,16},{65505,16},{65506,16},{65507,16},{0,0},{0,0},{0,0},{0,0},{0,0},{0,0},\n{2041,11},{65508,16},{65509,16},{65510,16},{65511,16},{65512,16},{65513,16},{65514,16},{65515,16},{65516,16},{0,0},{0,0},{0,0},{0,0},{0,0},{0,0},\n{16352,14},{65517,16},{65518,16},{65519,16},{65520,16},{65521,16},{65522,16},{65523,16},{65524,16},{65525,16},{0,0},{0,0},{0,0},{0,0},{0,0},\n{1018,10},{32707,15},{65526,16},{65527,16},{65528,16},{65529,16},{65530,16},{65531,16},{65532,16},{65533,16},{65534,16},{0,0},{0,0},{0,0},{0,0},{0,0}\n};\nstatic const int YQT[] = {16,11,10,16,24,40,51,61,12,12,14,19,26,58,60,55,14,13,16,24,40,57,69,56,14,17,22,29,51,87,80,62,18,22,\n37,56,68,109,103,77,24,35,55,64,81,104,113,92,49,64,78,87,103,121,120,101,72,92,95,98,112,100,103,99};\nstatic const int UVQT[] = {17,18,24,47,99,99,99,99,18,21,26,66,99,99,99,99,24,26,56,99,99,99,99,99,47,66,99,99,99,99,99,99,\n99,99,99,99,99,99,99,99,99,99,99,99,99,99,99,99,99,99,99,99,99,99,99,99,99,99,99,99,99,99,99,99};\nstatic const float aasf[] = { 1.0f * 2.828427125f, 1.387039845f * 2.828427125f, 1.306562965f * 2.828427125f, 1.175875602f * 2.828427125f, 1.0f * 2.828427125f, 0.785694958f * 2.828427125f, 0.541196100f * 2.828427125f, 0.275899379f * 2.828427125f };\nint row, col, i, k;\nfloat fdtbl_Y[64], fdtbl_UV[64];\nunsigned char YTable[64], UVTable[64];\nif(!data || !width || !height || comp > 4 || comp < 1) {\nreturn 0;\n}\nquality = quality ? quality : 90;\nquality = quality < 1 ? 1 : quality > 100 ? 100 : quality;\nquality = quality < 50 ? 5000 / quality : 200 - quality * 2;\nfor(i = 0; i < 64; ++i) {\nint uvti, yti = (YQT[i]*quality+50)/100;\nYTable[stbiw__jpg_ZigZag[i]] = (unsigned char) (yti < 1 ? 1 : yti > 255 ? 255 : yti);\nuvti = (UVQT[i]*quality+50)/100;\nUVTable[stbiw__jpg_ZigZag[i]] = (unsigned char) (uvti < 1 ? 1 : uvti > 255 ? 255 : uvti);\n}\nfor(row = 0, k = 0; row < 8; ++row) {\nfor(col = 0; col < 8; ++col, ++k) {\nfdtbl_Y[k]  = 1 / (YTable [stbiw__jpg_ZigZag[k]] * aasf[row] * aasf[col]);\nfdtbl_UV[k] = 1 / (UVTable[stbiw__jpg_ZigZag[k]] * aasf[row] * aasf[col]);\n}\n}\n// Write Headers\n{\nstatic const unsigned char head0[] = { 0xFF,0xD8,0xFF,0xE0,0,0x10,'J','F','I','F',0,1,1,0,0,1,0,1,0,0,0xFF,0xDB,0,0x84,0 };\nstatic const unsigned char head2[] = { 0xFF,0xDA,0,0xC,3,1,0,2,0x11,3,0x11,0,0x3F,0 };\nconst unsigned char head1[] = { 0xFF,0xC0,0,0x11,8,(unsigned char)(height>>8),STBIW_UCHAR(height),(unsigned char)(width>>8),STBIW_UCHAR(width),\n3,1,0x11,0,2,0x11,1,3,0x11,1,0xFF,0xC4,0x01,0xA2,0 };\ns->func(s->context, (void*)head0, sizeof(head0));\ns->func(s->context, (void*)YTable, sizeof(YTable));\nstbiw__putc(s, 1);\ns->func(s->context, UVTable, sizeof(UVTable));\ns->func(s->context, (void*)head1, sizeof(head1));\ns->func(s->context, (void*)(std_dc_luminance_nrcodes+1), sizeof(std_dc_luminance_nrcodes)-1);\ns->func(s->context, (void*)std_dc_luminance_values, sizeof(std_dc_luminance_values));\nstbiw__putc(s, 0x10); // HTYACinfo\ns->func(s->context, (void*)(std_ac_luminance_nrcodes+1), sizeof(std_ac_luminance_nrcodes)-1);\ns->func(s->context, (void*)std_ac_luminance_values, sizeof(std_ac_luminance_values));\nstbiw__putc(s, 1); // HTUDCinfo\ns->func(s->context, (void*)(std_dc_chrominance_nrcodes+1), sizeof(std_dc_chrominance_nrcodes)-1);\ns->func(s->context, (void*)std_dc_chrominance_values, sizeof(std_dc_chrominance_values));\nstbiw__putc(s, 0x11); // HTUACinfo\ns->func(s->context, (void*)(std_ac_chrominance_nrcodes+1), sizeof(std_ac_chrominance_nrcodes)-1);\ns->func(s->context, (void*)std_ac_chrominance_values, sizeof(std_ac_chrominance_values));\ns->func(s->context, (void*)head2, sizeof(head2));\n}\n// Encode 8x8 macroblocks\n{\nstatic const unsigned short fillBits[] = {0x7F, 7};\nconst unsigned char *imageData = (const unsigned char *)data;\nint DCY=0, DCU=0, DCV=0;\nint bitBuf=0, bitCnt=0;\n// comp == 2 is grey+alpha (alpha is ignored)\nint ofsG = comp > 2 ? 1 : 0, ofsB = comp > 2 ? 2 : 0;\nint x, y, pos;\nfor(y = 0; y < height; y += 8) {\nfor(x = 0; x < width; x += 8) {\nfloat YDU[64], UDU[64], VDU[64];\nfor(row = y, pos = 0; row < y+8; ++row) {\n// row >= height => use last input row\nint clamped_row = (row < height) ? row : height - 1;\nint base_p = (stbi__flip_vertically_on_write ? (height-1-clamped_row) : clamped_row)*width*comp;\nfor(col = x; col < x+8; ++col, ++pos) {\nfloat r, g, b;\n// if col >= width => use pixel from last input column\nint p = base_p + ((col < width) ? col : (width-1))*comp;\nr = imageData[p+0];\ng = imageData[p+ofsG];\nb = imageData[p+ofsB];\nYDU[pos]=+0.29900f*r+0.58700f*g+0.11400f*b-128;\nUDU[pos]=-0.16874f*r-0.33126f*g+0.50000f*b;\nVDU[pos]=+0.50000f*r-0.41869f*g-0.08131f*b;\n}\n}\nDCY = stbiw__jpg_processDU(s, &bitBuf, &bitCnt, YDU, fdtbl_Y, DCY, YDC_HT, YAC_HT);\nDCU = stbiw__jpg_processDU(s, &bitBuf, &bitCnt, UDU, fdtbl_UV, DCU, UVDC_HT, UVAC_HT);\nDCV = stbiw__jpg_processDU(s, &bitBuf, &bitCnt, VDU, fdtbl_UV, DCV, UVDC_HT, UVAC_HT);\n}\n}\n// Do the bit alignment of the EOI marker\nstbiw__jpg_writeBits(s, &bitBuf, &bitCnt, fillBits);\n}\n// EOI\nstbiw__putc(s, 0xFF);\nstbiw__putc(s, 0xD9);\nreturn 1;\n}\nSTBIWDEF int stbi_write_jpg_to_func(stbi_write_func *func, void *context, int x, int y, int comp, const void *data, int quality)\n{\nstbi__write_context s;\nstbi__start_write_callbacks(&s, func, context);\nreturn stbi_write_jpg_core(&s, x, y, comp, (void *) data, quality);\n}\n#ifndef STBI_WRITE_NO_STDIO\nSTBIWDEF int stbi_write_jpg(char const *filename, int x, int y, int comp, const void *data, int quality)\n{\nstbi__write_context s;\nif (stbi__start_write_file(&s,filename)) {\nint r = stbi_write_jpg_core(&s, x, y, comp, data, quality);\nstbi__end_write_file(&s);\nreturn r;\n} else\nreturn 0;\n}\n#endif\n#endif // STB_IMAGE_WRITE_IMPLEMENTATION\n/* Revision history\n      1.11  (2019-08-11)\n      1.10  (2019-02-07)\n             support utf8 filenames in Windows; fix warnings and platform ifdefs \n      1.09  (2018-02-11)\n             fix typo in zlib quality API, improve STB_I_W_STATIC in C++\n      1.08  (2018-01-29)\n             add stbi__flip_vertically_on_write, external zlib, zlib quality, choose PNG filter\n      1.07  (2017-07-24)\n             doc fix\n      1.06 (2017-07-23)\n             writing JPEG (using Jon Olick's code)\n      1.05   ???\n      1.04 (2017-03-03)\n             monochrome BMP expansion\n      1.03   ???\n      1.02 (2016-04-02)\n             avoid allocating large structures on the stack\n      1.01 (2016-01-16)\n             STBIW_REALLOC_SIZED: support allocators with no realloc support\n             avoid race-condition in crc initialization\n             minor compile issues\n      1.00 (2015-09-14)\n             installable file IO function\n      0.99 (2015-09-13)\n             warning fixes; TGA rle support\n      0.98 (2015-04-08)\n             added STBIW_MALLOC, STBIW_ASSERT etc\n      0.97 (2015-01-18)\n             fixed HDR asserts, rewrote HDR rle logic\n      0.96 (2015-01-17)\n             add HDR output\n             fix monochrome BMP\n      0.95 (2014-08-17)\n               add monochrome TGA output\n      0.94 (2014-05-31)\n             rename private functions to avoid conflicts with stb_image.h\n      0.93 (2014-05-27)\n             warning fixes\n      0.92 (2010-08-01)\n             casts to unsigned char to fix warnings\n      0.91 (2010-07-17)\n             first public release\n      0.90   first internal release\n*/\n/*\n------------------------------------------------------------------------------\nThis software is available under 2 licenses -- choose whichever you prefer.\n------------------------------------------------------------------------------\nALTERNATIVE A - MIT License\nCopyright (c) 2017 Sean Barrett\nPermission is hereby granted, free of charge, to any person obtaining a copy of \nthis software and associated documentation files (the \"Software\"), to deal in \nthe Software without restriction, including without limitation the rights to \nuse, copy, modify, merge, publish, distribute, sublicense, and/or sell copies \nof the Software, and to permit persons to whom the Software is furnished to do \nso, subject to the following conditions:\nThe above copyright notice and this permission notice shall be included in all \ncopies or substantial portions of the Software.\nTHE SOFTWARE IS PROVIDED \"AS IS\", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR \nIMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, \nFITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE \nAUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER \nLIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, \nOUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE \nSOFTWARE.\n------------------------------------------------------------------------------\nALTERNATIVE B - Public Domain (www.unlicense.org)\nThis is free and unencumbered software released into the public domain.\nAnyone is free to copy, modify, publish, use, compile, sell, or distribute this \nsoftware, either in source code form or as a compiled binary, for any purpose, \ncommercial or non-commercial, and by any means.\nIn jurisdictions that recognize copyright laws, the author or authors of this \nsoftware dedicate any and all copyright interest in the software to the public \ndomain. We make this dedication for the benefit of the public at large and to \nthe detriment of our heirs and successors. We intend this dedication to be an \novert act of relinquishment in perpetuity of all present and future rights to \nthis software under copyright law.\nTHE SOFTWARE IS PROVIDED \"AS IS\", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR \nIMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, \nFITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE \nAUTHORS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER LIABILITY, WHETHER IN AN \nACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN CONNECTION \nWITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE.\n------------------------------------------------------------------------------\n*/\n
"},{"location":"api/dir_087fbdcd93b501a5d3f98df93e9f8cc4/","title":"Dir robot_dart/robots","text":"

FileList > robot_dart > robots

"},{"location":"api/dir_087fbdcd93b501a5d3f98df93e9f8cc4/#files","title":"Files","text":"Type Name file a1.cpp file a1.hpp file arm.hpp file franka.cpp file franka.hpp file hexapod.hpp file icub.cpp file icub.hpp file iiwa.cpp file iiwa.hpp file pendulum.hpp file talos.cpp file talos.hpp file tiago.cpp file tiago.hpp file ur3e.cpp file ur3e.hpp file vx300.hpp

The documentation for this class was generated from the following file robot_dart/robots/

"},{"location":"api/a1_8cpp/","title":"File a1.cpp","text":"

FileList > robot_dart > robots > a1.cpp

Go to the source code of this file

"},{"location":"api/a1_8cpp/#namespaces","title":"Namespaces","text":"Type Name namespace robot_dart namespace robots

The documentation for this class was generated from the following file robot_dart/robots/a1.cpp

"},{"location":"api/a1_8cpp_source/","title":"File a1.cpp","text":"

File List > robot_dart > robots > a1.cpp

Go to the documentation of this file

#include \"robot_dart/robots/a1.hpp\"\n#include \"robot_dart/robot_dart_simu.hpp\"\nnamespace robot_dart {\nnamespace robots {\nA1::A1(size_t frequency, const std::string& urdf, const std::vector<std::pair<std::string, std::string>>& packages)\n: Robot(urdf, packages),\n_imu(std::make_shared<sensor::IMU>(sensor::IMUConfig(body_node(\"imu_link\"), frequency)))\n{\nset_color_mode(\"material\");\nset_self_collision(true);\nset_position_enforced(true);\n// put above ground\nset_base_pose(robot_dart::make_vector({0., 0., 0., 0., 0., 0.5}));\n// standing pose\nauto names = dof_names(true, true, true);\nnames = std::vector<std::string>(names.begin() + 6, names.end());\nset_positions(robot_dart::make_vector({0.0, 0.67, -1.3, -0.0, 0.67, -1.3, 0.0, 0.67, -1.3, -0.0, 0.67, -1.3}), names);\n}\nvoid A1::reset()\n{\nRobot::reset();\n// put above ground\nset_base_pose(robot_dart::make_vector({0., 0., 0., 0., 0., 0.5}));\n// standing pose\nauto names = dof_names(true, true, true);\nnames = std::vector<std::string>(names.begin() + 6, names.end());\nset_positions(robot_dart::make_vector({0.0, 0.67, -1.3, -0.0, 0.67, -1.3, 0.0, 0.67, -1.3, -0.0, 0.67, -1.3}), names);\n}\n} // namespace robots\n} // namespace robot_dart\n
"},{"location":"api/a1_8hpp/","title":"File a1.hpp","text":"

FileList > robot_dart > robots > a1.hpp

Go to the source code of this file

"},{"location":"api/a1_8hpp/#namespaces","title":"Namespaces","text":"Type Name namespace robot_dart namespace robots"},{"location":"api/a1_8hpp/#classes","title":"Classes","text":"Type Name class A1

The documentation for this class was generated from the following file robot_dart/robots/a1.hpp

"},{"location":"api/a1_8hpp_source/","title":"File a1.hpp","text":"

File List > robot_dart > robots > a1.hpp

Go to the documentation of this file

#ifndef ROBOT_DART_ROBOTS_A1_HPP\n#define ROBOT_DART_ROBOTS_A1_HPP\n#include \"robot_dart/robot.hpp\"\n#include \"robot_dart/sensor/imu.hpp\"\nnamespace robot_dart {\nnamespace robots {\nclass A1 : public Robot {\npublic:\nA1(size_t frequency = 1000, const std::string& urdf = \"unitree_a1/a1.urdf\", const std::vector<std::pair<std::string, std::string>>& packages = ('a1_description', 'unitree_a1/a1_description'));\nvoid reset() override;\nconst sensor::IMU& imu() const { return *_imu; }\nprotected:\nstd::shared_ptr<sensor::IMU> _imu;\n};\n} // namespace robots\n} // namespace robot_dart\n#endif\n
"},{"location":"api/arm_8hpp/","title":"File arm.hpp","text":"

FileList > robot_dart > robots > arm.hpp

Go to the source code of this file

"},{"location":"api/arm_8hpp/#namespaces","title":"Namespaces","text":"Type Name namespace robot_dart namespace robots"},{"location":"api/arm_8hpp/#classes","title":"Classes","text":"Type Name class Arm

The documentation for this class was generated from the following file robot_dart/robots/arm.hpp

"},{"location":"api/arm_8hpp_source/","title":"File arm.hpp","text":"

File List > robot_dart > robots > arm.hpp

Go to the documentation of this file

#ifndef ROBOT_DART_ROBOTS_ARM_HPP\n#define ROBOT_DART_ROBOTS_ARM_HPP\n#include \"robot_dart/robot.hpp\"\nnamespace robot_dart {\nnamespace robots {\nclass Arm : public Robot {\npublic:\nArm(const std::string& urdf = \"arm.urdf\") : Robot(urdf)\n{\nfix_to_world();\nset_position_enforced(true);\n}\n};\n} // namespace robots\n} // namespace robot_dart\n#endif\n
"},{"location":"api/franka_8cpp/","title":"File franka.cpp","text":"

FileList > robot_dart > robots > franka.cpp

Go to the source code of this file

"},{"location":"api/franka_8cpp/#namespaces","title":"Namespaces","text":"Type Name namespace robot_dart namespace robots

The documentation for this class was generated from the following file robot_dart/robots/franka.cpp

"},{"location":"api/franka_8cpp_source/","title":"File franka.cpp","text":"

File List > robot_dart > robots > franka.cpp

Go to the documentation of this file

#include \"robot_dart/robots/franka.hpp\"\n#include \"robot_dart/robot_dart_simu.hpp\"\nnamespace robot_dart {\nnamespace robots {\nFranka::Franka(size_t frequency, const std::string& urdf, const std::vector<std::pair<std::string, std::string>>& packages)\n: Robot(urdf, packages),\n_ft_wrist(std::make_shared<sensor::ForceTorque>(joint(\"panda_link7\"), frequency))\n{\nfix_to_world();\nset_position_enforced(true);\nset_color_mode(\"material\");\n}\nvoid Franka::_post_addition(RobotDARTSimu* simu)\n{\n// We do not want to add sensors if we are a ghost robot\nif (ghost())\nreturn;\nsimu->add_sensor(_ft_wrist);\n}\nvoid Franka::_post_removal(RobotDARTSimu* simu)\n{\nsimu->remove_sensor(_ft_wrist);\n}\n} // namespace robots\n} // namespace robot_dart\n
"},{"location":"api/franka_8hpp/","title":"File franka.hpp","text":"

FileList > robot_dart > robots > franka.hpp

Go to the source code of this file

"},{"location":"api/franka_8hpp/#namespaces","title":"Namespaces","text":"Type Name namespace robot_dart namespace robots"},{"location":"api/franka_8hpp/#classes","title":"Classes","text":"Type Name class Franka

The documentation for this class was generated from the following file robot_dart/robots/franka.hpp

"},{"location":"api/franka_8hpp_source/","title":"File franka.hpp","text":"

File List > robot_dart > robots > franka.hpp

Go to the documentation of this file

#ifndef ROBOT_DART_ROBOTS_FRANKA_HPP\n#define ROBOT_DART_ROBOTS_FRANKA_HPP\n#include \"robot_dart/robot.hpp\"\n#include \"robot_dart/sensor/force_torque.hpp\"\nnamespace robot_dart {\nnamespace robots {\nclass Franka : public Robot {\npublic:\nFranka(size_t frequency = 1000, const std::string& urdf = \"franka/franka.urdf\", const std::vector<std::pair<std::string, std::string>>& packages = ('franka_description', 'franka/franka_description'));\nconst sensor::ForceTorque& ft_wrist() const { return *_ft_wrist; }\nprotected:\nstd::shared_ptr<sensor::ForceTorque> _ft_wrist;\nvoid _post_addition(RobotDARTSimu* simu) override;\nvoid _post_removal(RobotDARTSimu* simu) override;\n};\n} // namespace robots\n} // namespace robot_dart\n#endif\n
"},{"location":"api/hexapod_8hpp/","title":"File hexapod.hpp","text":"

FileList > robot_dart > robots > hexapod.hpp

Go to the source code of this file

"},{"location":"api/hexapod_8hpp/#namespaces","title":"Namespaces","text":"Type Name namespace robot_dart namespace robots"},{"location":"api/hexapod_8hpp/#classes","title":"Classes","text":"Type Name class Hexapod

The documentation for this class was generated from the following file robot_dart/robots/hexapod.hpp

"},{"location":"api/hexapod_8hpp_source/","title":"File hexapod.hpp","text":"

File List > robot_dart > robots > hexapod.hpp

Go to the documentation of this file

#ifndef ROBOT_DART_ROBOTS_HEXAPOD_HPP\n#define ROBOT_DART_ROBOTS_HEXAPOD_HPP\n#include \"robot_dart/robot.hpp\"\nnamespace robot_dart {\nnamespace robots {\nclass Hexapod : public Robot {\npublic:\nHexapod(const std::string& urdf = \"pexod.urdf\") : Robot(urdf)\n{\nset_position_enforced(true);\nskeleton()->enableSelfCollisionCheck();\nset_base_pose(robot_dart::make_vector({0., 0., 0., 0., 0., 0.2}));\n}\nvoid reset() override\n{\nRobot::reset();\nset_base_pose(robot_dart::make_vector({0., 0., 0., 0., 0., 0.2}));\n}\n};\n} // namespace robots\n} // namespace robot_dart\n#endif\n
"},{"location":"api/icub_8cpp/","title":"File icub.cpp","text":"

FileList > robot_dart > robots > icub.cpp

Go to the source code of this file

"},{"location":"api/icub_8cpp/#namespaces","title":"Namespaces","text":"Type Name namespace robot_dart namespace robots

The documentation for this class was generated from the following file robot_dart/robots/icub.cpp

"},{"location":"api/icub_8cpp_source/","title":"File icub.cpp","text":"

File List > robot_dart > robots > icub.cpp

Go to the documentation of this file

#include \"robot_dart/robots/icub.hpp\"\n#include \"robot_dart/robot_dart_simu.hpp\"\nnamespace robot_dart {\nnamespace robots {\nICub::ICub(size_t frequency, const std::string& urdf, const std::vector<std::pair<std::string, std::string>>& packages)\n: Robot(urdf, packages),\n_imu(std::make_shared<sensor::IMU>(sensor::IMUConfig(body_node(\"head\"), frequency))),\n_ft_foot_left(std::make_shared<sensor::ForceTorque>(joint(\"l_ankle_roll\"), frequency)),\n_ft_foot_right(std::make_shared<sensor::ForceTorque>(joint(\"r_ankle_roll\"), frequency))\n{\nset_color_mode(\"material\");\nset_position_enforced(true);\n// position iCub\nset_base_pose(robot_dart::make_vector({0., 0., M_PI / 2., 0., 0., 0.46}));\n}\nvoid ICub::reset()\n{\nRobot::reset();\n// position iCub\nset_base_pose(robot_dart::make_vector({0., 0., M_PI / 2., 0., 0., 0.46}));\n}\nvoid ICub::_post_addition(RobotDARTSimu* simu)\n{\n// We do not want to add sensors if we are a ghost robot\nif (ghost())\nreturn;\nsimu->add_sensor(_imu);\nsimu->add_sensor(_ft_foot_left);\nsimu->add_sensor(_ft_foot_right);\n}\nvoid ICub::_post_removal(RobotDARTSimu* simu)\n{\nsimu->remove_sensor(_imu);\nsimu->remove_sensor(_ft_foot_left);\nsimu->remove_sensor(_ft_foot_right);\n}\n} // namespace robots\n} // namespace robot_dart\n
"},{"location":"api/icub_8hpp/","title":"File icub.hpp","text":"

FileList > robot_dart > robots > icub.hpp

Go to the source code of this file

"},{"location":"api/icub_8hpp/#namespaces","title":"Namespaces","text":"Type Name namespace robot_dart namespace robots"},{"location":"api/icub_8hpp/#classes","title":"Classes","text":"Type Name class ICub

The documentation for this class was generated from the following file robot_dart/robots/icub.hpp

"},{"location":"api/icub_8hpp_source/","title":"File icub.hpp","text":"

File List > robot_dart > robots > icub.hpp

Go to the documentation of this file

#ifndef ROBOT_DART_ROBOTS_ICUB_HPP\n#define ROBOT_DART_ROBOTS_ICUB_HPP\n#include \"robot_dart/robot.hpp\"\n#include \"robot_dart/sensor/force_torque.hpp\"\n#include \"robot_dart/sensor/imu.hpp\"\nnamespace robot_dart {\nnamespace robots {\nclass ICub : public Robot {\npublic:\nICub(size_t frequency = 1000, const std::string& urdf = \"icub/icub.urdf\", const std::vector<std::pair<std::string, std::string>>& packages = ('icub_description', 'icub/icub_description'));\nvoid reset() override;\nconst sensor::IMU& imu() const { return *_imu; }\nconst sensor::ForceTorque& ft_foot_left() const { return *_ft_foot_left; }\nconst sensor::ForceTorque& ft_foot_right() const { return *_ft_foot_right; }\nprotected:\nstd::shared_ptr<sensor::IMU> _imu;\nstd::shared_ptr<sensor::ForceTorque> _ft_foot_left;\nstd::shared_ptr<sensor::ForceTorque> _ft_foot_right;\nvoid _post_addition(RobotDARTSimu* simu) override;\nvoid _post_removal(RobotDARTSimu* simu) override;\n};\n} // namespace robots\n} // namespace robot_dart\n#endif\n
"},{"location":"api/iiwa_8cpp/","title":"File iiwa.cpp","text":"

FileList > robot_dart > robots > iiwa.cpp

Go to the source code of this file

"},{"location":"api/iiwa_8cpp/#namespaces","title":"Namespaces","text":"Type Name namespace robot_dart namespace robots

The documentation for this class was generated from the following file robot_dart/robots/iiwa.cpp

"},{"location":"api/iiwa_8cpp_source/","title":"File iiwa.cpp","text":"

File List > robot_dart > robots > iiwa.cpp

Go to the documentation of this file

#include \"robot_dart/robots/iiwa.hpp\"\n#include \"robot_dart/robot_dart_simu.hpp\"\nnamespace robot_dart {\nnamespace robots {\nIiwa::Iiwa(size_t frequency, const std::string& urdf, const std::vector<std::pair<std::string, std::string>>& packages)\n: Robot(urdf, packages),\n_ft_wrist(std::make_shared<sensor::ForceTorque>(joint(\"iiwa_joint_ee\"), frequency))\n{\nfix_to_world();\nset_position_enforced(true);\n}\nvoid Iiwa::_post_addition(RobotDARTSimu* simu)\n{\n// We do not want to add sensors if we are a ghost robot\nif (ghost())\nreturn;\nsimu->add_sensor(_ft_wrist);\n}\nvoid Iiwa::_post_removal(RobotDARTSimu* simu)\n{\nsimu->remove_sensor(_ft_wrist);\n}\n} // namespace robots\n} // namespace robot_dart\n
"},{"location":"api/iiwa_8hpp/","title":"File iiwa.hpp","text":"

FileList > robot_dart > robots > iiwa.hpp

Go to the source code of this file

"},{"location":"api/iiwa_8hpp/#namespaces","title":"Namespaces","text":"Type Name namespace robot_dart namespace robots"},{"location":"api/iiwa_8hpp/#classes","title":"Classes","text":"Type Name class Iiwa

The documentation for this class was generated from the following file robot_dart/robots/iiwa.hpp

"},{"location":"api/iiwa_8hpp_source/","title":"File iiwa.hpp","text":"

File List > robot_dart > robots > iiwa.hpp

Go to the documentation of this file

#ifndef ROBOT_DART_ROBOTS_IIWA_HPP\n#define ROBOT_DART_ROBOTS_IIWA_HPP\n#include \"robot_dart/robot.hpp\"\n#include \"robot_dart/sensor/force_torque.hpp\"\nnamespace robot_dart {\nnamespace robots {\nclass Iiwa : public Robot {\npublic:\nIiwa(size_t frequency = 1000, const std::string& urdf = \"iiwa/iiwa.urdf\", const std::vector<std::pair<std::string, std::string>>& packages = ('iiwa_description', 'iiwa/iiwa_description'));\nconst sensor::ForceTorque& ft_wrist() const { return *_ft_wrist; }\nprotected:\nstd::shared_ptr<sensor::ForceTorque> _ft_wrist;\nvoid _post_addition(RobotDARTSimu* simu) override;\nvoid _post_removal(RobotDARTSimu* simu) override;\n};\n} // namespace robots\n} // namespace robot_dart\n#endif\n
"},{"location":"api/pendulum_8hpp/","title":"File pendulum.hpp","text":"

FileList > robot_dart > robots > pendulum.hpp

Go to the source code of this file

"},{"location":"api/pendulum_8hpp/#namespaces","title":"Namespaces","text":"Type Name namespace robot_dart namespace robots"},{"location":"api/pendulum_8hpp/#classes","title":"Classes","text":"Type Name class Pendulum

The documentation for this class was generated from the following file robot_dart/robots/pendulum.hpp

"},{"location":"api/pendulum_8hpp_source/","title":"File pendulum.hpp","text":"

File List > robot_dart > robots > pendulum.hpp

Go to the documentation of this file

#ifndef ROBOT_DART_ROBOTS_PENDULUM_HPP\n#define ROBOT_DART_ROBOTS_PENDULUM_HPP\n#include \"robot_dart/robot.hpp\"\nnamespace robot_dart {\nnamespace robots {\nclass Pendulum : public Robot {\npublic:\nPendulum(const std::string& urdf = \"pendulum.urdf\") : Robot(urdf)\n{\nfix_to_world();\nset_position_enforced(true);\nset_positions(robot_dart::make_vector({M_PI}));\n}\n};\n} // namespace robots\n} // namespace robot_dart\n#endif\n
"},{"location":"api/talos_8cpp/","title":"File talos.cpp","text":"

FileList > robot_dart > robots > talos.cpp

Go to the source code of this file

"},{"location":"api/talos_8cpp/#namespaces","title":"Namespaces","text":"Type Name namespace robot_dart namespace robots

The documentation for this class was generated from the following file robot_dart/robots/talos.cpp

"},{"location":"api/talos_8cpp_source/","title":"File talos.cpp","text":"

File List > robot_dart > robots > talos.cpp

Go to the documentation of this file

#include \"robot_dart/robots/talos.hpp\"\n#include \"robot_dart/robot_dart_simu.hpp\"\nnamespace robot_dart {\nnamespace robots {\nTalos::Talos(size_t frequency, const std::string& urdf, const std::vector<std::pair<std::string, std::string>>& packages)\n: Robot(urdf, packages),\n_imu(std::make_shared<sensor::IMU>(sensor::IMUConfig(body_node(\"imu_link\"), frequency))),\n_ft_foot_left(std::make_shared<sensor::ForceTorque>(joint(\"leg_left_6_joint\"), frequency, \"parent_to_child\")),\n_ft_foot_right(std::make_shared<sensor::ForceTorque>(joint(\"leg_right_6_joint\"), frequency, \"parent_to_child\")),\n_ft_wrist_left(std::make_shared<sensor::ForceTorque>(joint(\"wrist_left_ft_joint\"), frequency, \"parent_to_child\")),\n_ft_wrist_right(std::make_shared<sensor::ForceTorque>(joint(\"wrist_right_ft_joint\"), frequency, \"parent_to_child\")),\n_frequency(frequency)\n{\n// use position/torque limits\nset_position_enforced(true);\n// position Talos\nset_base_pose(robot_dart::make_vector({0., 0., M_PI / 2., 0., 0., 1.1}));\n}\nvoid Talos::reset()\n{\nRobot::reset();\n// position Talos\nset_base_pose(robot_dart::make_vector({0., 0., M_PI / 2., 0., 0., 1.1}));\n}\nvoid Talos::_post_addition(RobotDARTSimu* simu)\n{\n// We do not want to add sensors if we are a ghost robot\nif (ghost())\nreturn;\nsimu->add_sensor(_imu);\nsimu->add_sensor(_ft_foot_left);\nsimu->add_sensor(_ft_foot_right);\nsimu->add_sensor(_ft_wrist_left);\nsimu->add_sensor(_ft_wrist_right);\n// torques sensors\nstd::vector<std::string> joints = {\n// torso\n\"torso_1_joint\",\n\"torso_2_joint\",\n// arm_left\n\"arm_left_1_joint\", \"arm_left_2_joint\",\n\"arm_left_3_joint\", \"arm_left_4_joint\",\n// arm_right\n\"arm_right_1_joint\", \"arm_right_2_joint\",\n\"arm_right_3_joint\", \"arm_right_4_joint\",\n// leg_left\n\"leg_left_1_joint\", \"leg_left_2_joint\", \"leg_left_3_joint\",\n\"leg_left_4_joint\", \"leg_left_5_joint\", \"leg_left_6_joint\",\n// leg_right\n\"leg_right_1_joint\", \"leg_right_2_joint\", \"leg_right_3_joint\",\n\"leg_right_4_joint\", \"leg_right_5_joint\", \"leg_right_6_joint\"\n};\nfor (auto& s : joints) {\nauto t = std::make_shared<sensor::Torque>(joint(s), _frequency);\n_torques[s] = t;\nsimu->add_sensor(t);\n}\n}\nvoid Talos::_post_removal(RobotDARTSimu* simu)\n{\nsimu->remove_sensor(_imu);\nsimu->remove_sensor(_ft_foot_left);\nsimu->remove_sensor(_ft_foot_right);\nsimu->remove_sensor(_ft_wrist_left);\nsimu->remove_sensor(_ft_wrist_right);\nfor (auto& t : _torques) {\nsimu->remove_sensor(t.second);\n}\n}\nvoid TalosFastCollision::_post_addition(RobotDARTSimu* simu)\n{\nTalos::_post_addition(simu);\nauto vec = TalosFastCollision::collision_vec();\nfor (auto& t : vec) {\nsimu->set_collision_masks(simu->robots().size() - 1, std::get<0>(t), std::get<1>(t), std::get<2>(t));\n}\n}\nstd::vector<std::tuple<std::string, uint32_t, uint32_t>> TalosFastCollision::collision_vec()\n{\nstd::vector<std::tuple<std::string, uint32_t, uint32_t>> vec;\nvec.push_back(std::make_tuple(\"leg_right_6_link\", 0x1, 0x1 | 0x4 | 0x8 | 0x10 | 0x20 | 0x40 | 0x80 | 0x100 | 0x200 | 0x400 | 0x800 | 0x1000 | 0x2000 | 0x4000 | 0x8000 | 0x10000));\nvec.push_back(std::make_tuple(\"leg_right_4_link\", 0x2, 0x2 | 0x4 | 0x8 | 0x10 | 0x20 | 0x40 | 0x80 | 0x100 | 0x200 | 0x400 | 0x800 | 0x1000 | 0x2000 | 0x4000 | 0x8000 | 0x10000));\nvec.push_back(std::make_tuple(\"leg_left_6_link\", 0x4, 0x1 | 0x2 | 0x4 | 0x10 | 0x20 | 0x40 | 0x80 | 0x100 | 0x200 | 0x400 | 0x800 | 0x1000 | 0x2000 | 0x4000 | 0x8000 | 0x10000));\nvec.push_back(std::make_tuple(\"leg_left_4_link\", 0x8, 0x1 | 0x2 | 0x8 | 0x10 | 0x20 | 0x40 | 0x80 | 0x100 | 0x200 | 0x400 | 0x800 | 0x1000 | 0x2000 | 0x4000 | 0x8000 | 0x10000));\nvec.push_back(std::make_tuple(\"leg_left_1_link\", 0x10, 0x1 | 0x2 | 0x4 | 0x8 | 0x10 | 0x40 | 0x80 | 0x100 | 0x200 | 0x400 | 0x800 | 0x1000 | 0x2000 | 0x4000 | 0x8000 | 0x10000));\nvec.push_back(std::make_tuple(\"leg_left_3_link\", 0x20, 0x1 | 0x2 | 0x4 | 0x8 | 0x20 | 0x40 | 0x80 | 0x100 | 0x200 | 0x400 | 0x800 | 0x1000 | 0x2000 | 0x4000 | 0x8000 | 0x10000));\nvec.push_back(std::make_tuple(\"leg_right_1_link\", 0x40, 0x1 | 0x2 | 0x4 | 0x8 | 0x10 | 0x20 | 0x40 | 0x100 | 0x200 | 0x400 | 0x800 | 0x1000 | 0x2000 | 0x4000 | 0x8000 | 0x10000));\nvec.push_back(std::make_tuple(\"leg_right_3_link\", 0x80, 0x1 | 0x2 | 0x4 | 0x8 | 0x10 | 0x20 | 0x80 | 0x100 | 0x200 | 0x400 | 0x800 | 0x1000 | 0x2000 | 0x4000 | 0x8000 | 0x10000));\nvec.push_back(std::make_tuple(\"arm_left_7_link\", 0x100, 0x1 | 0x2 | 0x4 | 0x8 | 0x10 | 0x20 | 0x40 | 0x80 | 0x100 | 0x400 | 0x800 | 0x1000 | 0x2000 | 0x4000 | 0x8000 | 0x10000));\nvec.push_back(std::make_tuple(\"arm_left_5_link\", 0x200, 0x1 | 0x2 | 0x4 | 0x8 | 0x10 | 0x20 | 0x40 | 0x80 | 0x200 | 0x400 | 0x800 | 0x1000 | 0x2000 | 0x4000 | 0x8000 | 0x10000));\nvec.push_back(std::make_tuple(\"arm_right_7_link\", 0x400, 0x1 | 0x2 | 0x4 | 0x8 | 0x10 | 0x20 | 0x40 | 0x80 | 0x100 | 0x200 | 0x400 | 0x1000 | 0x2000 | 0x4000 | 0x8000 | 0x10000));\nvec.push_back(std::make_tuple(\"arm_right_5_link\", 0x800, 0x1 | 0x2 | 0x4 | 0x8 | 0x10 | 0x20 | 0x40 | 0x80 | 0x100 | 0x200 | 0x800 | 0x1000 | 0x2000 | 0x4000 | 0x8000 | 0x10000));\nvec.push_back(std::make_tuple(\"torso_2_link\", 0x1000, 0x1 | 0x2 | 0x4 | 0x8 | 0x10 | 0x20 | 0x40 | 0x80 | 0x100 | 0x200 | 0x800 | 0x1000 | 0x4000 | 0x8000));\nvec.push_back(std::make_tuple(\"base_link\", 0x2000, 0x1 | 0x2 | 0x4 | 0x8 | 0x10 | 0x20 | 0x40 | 0x80 | 0x100 | 0x200 | 0x800 | 0x2000 | 0x10000));\nvec.push_back(std::make_tuple(\"leg_right_2_link\", 0x4000, 0x1 | 0x2 | 0x4 | 0x8 | 0x10 | 0x20 | 0x40 | 0x80 | 0x100 | 0x200 | 0x800 | 0x1000 | 0x4000 | 0x8000 | 0x10000));\nvec.push_back(std::make_tuple(\"leg_left_2_link\", 0x8000, 0x1 | 0x2 | 0x4 | 0x8 | 0x10 | 0x20 | 0x40 | 0x80 | 0x100 | 0x200 | 0x800 | 0x1000 | 0x4000 | 0x8000 | 0x10000));\nvec.push_back(std::make_tuple(\"head_2_link\", 0x10000, 0x1 | 0x2 | 0x4 | 0x8 | 0x10 | 0x20 | 0x40 | 0x80 | 0x100 | 0x200 | 0x800 | 0x2000 | 0x4000 | 0x8000 | 0x10000));\nreturn vec;\n}\n} // namespace robots\n} // namespace robot_dart\n
"},{"location":"api/talos_8hpp/","title":"File talos.hpp","text":"

FileList > robot_dart > robots > talos.hpp

Go to the source code of this file

"},{"location":"api/talos_8hpp/#namespaces","title":"Namespaces","text":"Type Name namespace robot_dart namespace robots"},{"location":"api/talos_8hpp/#classes","title":"Classes","text":"Type Name class Talos datasheet: https://pal-robotics.com/wp-content/uploads/2019/07/Datasheet_TALOS.pdf __ class TalosFastCollision class TalosLight

The documentation for this class was generated from the following file robot_dart/robots/talos.hpp

"},{"location":"api/talos_8hpp_source/","title":"File talos.hpp","text":"

File List > robot_dart > robots > talos.hpp

Go to the documentation of this file

#ifndef ROBOT_DART_ROBOTS_TALOS_HPP\n#define ROBOT_DART_ROBOTS_TALOS_HPP\n#include \"robot_dart/robot.hpp\"\n#include \"robot_dart/sensor/force_torque.hpp\"\n#include \"robot_dart/sensor/imu.hpp\"\n#include \"robot_dart/sensor/torque.hpp\"\nnamespace robot_dart {\nnamespace robots {\nclass Talos : public Robot {\npublic:\nTalos(size_t frequency = 1000, const std::string& urdf = \"talos/talos.urdf\", const std::vector<std::pair<std::string, std::string>>& packages = ('talos_description', 'talos/talos_description'));\nvoid reset() override;\nconst sensor::IMU& imu() const { return *_imu; }\nconst sensor::ForceTorque& ft_foot_left() const { return *_ft_foot_left; }\nconst sensor::ForceTorque& ft_foot_right() const { return *_ft_foot_right; }\nconst sensor::ForceTorque& ft_wrist_left() const { return *_ft_wrist_left; }\nconst sensor::ForceTorque& ft_wrist_right() const { return *_ft_wrist_right; }\nusing torque_map_t = std::unordered_map<std::string, std::shared_ptr<sensor::Torque>>;\nconst torque_map_t& torques() const { return _torques; }\nprotected:\nstd::shared_ptr<sensor::IMU> _imu;\nstd::shared_ptr<sensor::ForceTorque> _ft_foot_left;\nstd::shared_ptr<sensor::ForceTorque> _ft_foot_right;\nstd::shared_ptr<sensor::ForceTorque> _ft_wrist_left;\nstd::shared_ptr<sensor::ForceTorque> _ft_wrist_right;\ntorque_map_t _torques;\nsize_t _frequency;\nvoid _post_addition(RobotDARTSimu* simu) override;\nvoid _post_removal(RobotDARTSimu* simu) override;\n};\nclass TalosLight : public Talos {\npublic:\nTalosLight(size_t frequency = 1000, const std::string& urdf = \"talos/talos_fast.urdf\", const std::vector<std::pair<std::string, std::string>>& packages = ('talos_description', 'talos/talos_description')) : Talos(frequency, urdf, packages) {}\n};\n// for talos_fast_collision.urdf or talos_box.urdf which have simple box collision shapes\nclass TalosFastCollision : public Talos {\npublic:\nTalosFastCollision(size_t frequency = 1000, const std::string& urdf = \"talos/talos_fast_collision.urdf\", const std::vector<std::pair<std::string, std::string>>& packages = ('talos_description', 'talos/talos_description')) : Talos(frequency, urdf, packages) { set_self_collision(); }\nstatic std::vector<std::tuple<std::string, uint32_t, uint32_t>> collision_vec();\nprotected:\nvoid _post_addition(RobotDARTSimu* simu) override;\n};\n} // namespace robots\n} // namespace robot_dart\n#endif\n
"},{"location":"api/tiago_8cpp/","title":"File tiago.cpp","text":"

FileList > robot_dart > robots > tiago.cpp

Go to the source code of this file

"},{"location":"api/tiago_8cpp/#namespaces","title":"Namespaces","text":"Type Name namespace robot_dart namespace robots

The documentation for this class was generated from the following file robot_dart/robots/tiago.cpp

"},{"location":"api/tiago_8cpp_source/","title":"File tiago.cpp","text":"

File List > robot_dart > robots > tiago.cpp

Go to the documentation of this file

#include \"robot_dart/robots/tiago.hpp\"\n#include \"robot_dart/robot_dart_simu.hpp\"\nnamespace robot_dart {\nnamespace robots {\nTiago::Tiago(size_t frequency, const std::string& urdf, const std::vector<std::pair<std::string, std::string>>& packages)\n: Robot(urdf, packages),\n_ft_wrist(std::make_shared<sensor::ForceTorque>(joint(\"gripper_tool_joint\"), frequency))\n{\nset_position_enforced(true);\n// We use servo actuators, but not for the caster joints\nset_actuator_types(\"servo\");\n// position Tiago\nset_base_pose(robot_dart::make_vector({0., 0., M_PI / 2., 0., 0., 0.}));\n}\nvoid Tiago::reset()\n{\nRobot::reset();\n// position Tiago\nset_base_pose(robot_dart::make_vector({0., 0., M_PI / 2., 0., 0., 0.}));\n}\nvoid Tiago::set_actuator_types(const std::string& type, const std::vector<std::string>& joint_names, bool override_mimic, bool override_base, bool override_caster)\n{\nauto jt = joint_names;\nif (!override_caster) {\nif (joint_names.size() == 0)\njt = Robot::joint_names();\nfor (const auto& jnt : caster_joints()) {\nauto it = std::find(jt.begin(), jt.end(), jnt);\nif (it != jt.end()) {\njt.erase(it);\n}\n}\n}\nRobot::set_actuator_types(type, jt, override_mimic, override_base);\n}\nvoid Tiago::set_actuator_type(const std::string& type, const std::string& joint_name, bool override_mimic, bool override_base, bool override_caster)\n{\nset_actuator_types(type, {joint_name}, override_mimic, override_base, override_caster);\n}\nvoid Tiago::_post_addition(RobotDARTSimu* simu)\n{\n// We do not want to add sensors if we are a ghost robot\nif (ghost())\nreturn;\nsimu->add_sensor(_ft_wrist);\n}\nvoid Tiago::_post_removal(RobotDARTSimu* simu)\n{\nsimu->remove_sensor(_ft_wrist);\n}\n} // namespace robots\n} // namespace robot_dart\n
"},{"location":"api/tiago_8hpp/","title":"File tiago.hpp","text":"

FileList > robot_dart > robots > tiago.hpp

Go to the source code of this file

"},{"location":"api/tiago_8hpp/#namespaces","title":"Namespaces","text":"Type Name namespace robot_dart namespace robots"},{"location":"api/tiago_8hpp/#classes","title":"Classes","text":"Type Name class Tiago datasheet: https://pal-robotics.com/wp-content/uploads/2021/07/Datasheet-complete_TIAGo-2021.pdf __

The documentation for this class was generated from the following file robot_dart/robots/tiago.hpp

"},{"location":"api/tiago_8hpp_source/","title":"File tiago.hpp","text":"

File List > robot_dart > robots > tiago.hpp

Go to the documentation of this file

#ifndef ROBOT_DART_ROBOTS_TIAGO_HPP\n#define ROBOT_DART_ROBOTS_TIAGO_HPP\n#include \"robot_dart/robot.hpp\"\n#include \"robot_dart/sensor/force_torque.hpp\"\nnamespace robot_dart {\nnamespace robots {\nclass Tiago : public Robot {\npublic:\nTiago(size_t frequency = 1000, const std::string& urdf = \"tiago/tiago_steel.urdf\", const std::vector<std::pair<std::string, std::string>>& packages = ('tiago_description', 'tiago/tiago_description'));\nvoid reset() override;\nconst sensor::ForceTorque& ft_wrist() const { return *_ft_wrist; }\nstd::vector<std::string> caster_joints() const { return {\"caster_back_left_2_joint\", \"caster_back_left_1_joint\", \"caster_back_right_2_joint\", \"caster_back_right_1_joint\", \"caster_front_left_2_joint\", \"caster_front_left_1_joint\", \"caster_front_right_2_joint\", \"caster_front_right_1_joint\"}; }\nvoid set_actuator_types(const std::string& type, const std::vector<std::string>& joint_names = {}, bool override_mimic = false, bool override_base = false, bool override_caster = false);\nvoid set_actuator_type(const std::string& type, const std::string& joint_name, bool override_mimic = false, bool override_base = false, bool override_caster = false);\nprotected:\nstd::shared_ptr<sensor::ForceTorque> _ft_wrist;\nvoid _post_addition(RobotDARTSimu* simu) override;\nvoid _post_removal(RobotDARTSimu* simu) override;\n};\n} // namespace robots\n} // namespace robot_dart\n#endif\n
"},{"location":"api/ur3e_8cpp/","title":"File ur3e.cpp","text":"

FileList > robot_dart > robots > ur3e.cpp

Go to the source code of this file

"},{"location":"api/ur3e_8cpp/#namespaces","title":"Namespaces","text":"Type Name namespace robot_dart namespace robots

The documentation for this class was generated from the following file robot_dart/robots/ur3e.cpp

"},{"location":"api/ur3e_8cpp_source/","title":"File ur3e.cpp","text":"

File List > robot_dart > robots > ur3e.cpp

Go to the documentation of this file

#include \"robot_dart/robots/ur3e.hpp\"\n#include \"robot_dart/robot_dart_simu.hpp\"\nnamespace robot_dart {\nnamespace robots {\nUr3e::Ur3e(size_t frequency, const std::string& urdf, const std::vector<std::pair<std::string, std::string>>& packages)\n: Robot(urdf, packages),\n_ft_wrist(std::make_shared<sensor::ForceTorque>(joint(\"wrist_3-flange\"), frequency))\n{\nfix_to_world();\nset_position_enforced(true);\nset_color_mode(\"material\");\n}\nvoid Ur3e::_post_addition(RobotDARTSimu* simu)\n{\n// We do not want to add sensors if we are a ghost robot\nif (ghost())\nreturn;\nsimu->add_sensor(_ft_wrist);\n}\nvoid Ur3e::_post_removal(RobotDARTSimu* simu)\n{\nsimu->remove_sensor(_ft_wrist);\n}\n} // namespace robots\n} // namespace robot_dart\n
"},{"location":"api/ur3e_8hpp/","title":"File ur3e.hpp","text":"

FileList > robot_dart > robots > ur3e.hpp

Go to the source code of this file

"},{"location":"api/ur3e_8hpp/#namespaces","title":"Namespaces","text":"Type Name namespace robot_dart namespace robots"},{"location":"api/ur3e_8hpp/#classes","title":"Classes","text":"Type Name class Ur3e class Ur3eHand

The documentation for this class was generated from the following file robot_dart/robots/ur3e.hpp

"},{"location":"api/ur3e_8hpp_source/","title":"File ur3e.hpp","text":"

File List > robot_dart > robots > ur3e.hpp

Go to the documentation of this file

#ifndef ROBOT_DART_ROBOTS_UR3E_HPP\n#define ROBOT_DART_ROBOTS_UR3E_HPP\n#include \"robot_dart/robot.hpp\"\n#include \"robot_dart/sensor/force_torque.hpp\"\nnamespace robot_dart {\nnamespace robots {\nclass Ur3e : public Robot {\npublic:\nUr3e(size_t frequency = 1000, const std::string& urdf = \"ur3e/ur3e.urdf\", const std::vector<std::pair<std::string, std::string>>& packages = ('ur3e_description', 'ur3e/ur3e_description'));\nconst sensor::ForceTorque& ft_wrist() const { return *_ft_wrist; }\nprotected:\nstd::shared_ptr<sensor::ForceTorque> _ft_wrist;\nvoid _post_addition(RobotDARTSimu* simu) override;\nvoid _post_removal(RobotDARTSimu* simu) override;\n};\nclass Ur3eHand : public Ur3e {\npublic:\nUr3eHand(size_t frequency = 1000, const std::string& urdf = \"ur3e/ur3e_with_schunk_hand.urdf\", const std::vector<std::pair<std::string, std::string>>& packages = ('ur3e_description', 'ur3e/ur3e_description')) : Ur3e(frequency, urdf, packages) {}\n};\n} // namespace robots\n} // namespace robot_dart\n#endif\n
"},{"location":"api/vx300_8hpp/","title":"File vx300.hpp","text":"

FileList > robot_dart > robots > vx300.hpp

Go to the source code of this file

"},{"location":"api/vx300_8hpp/#namespaces","title":"Namespaces","text":"Type Name namespace robot_dart namespace robots"},{"location":"api/vx300_8hpp/#classes","title":"Classes","text":"Type Name class Vx300

The documentation for this class was generated from the following file robot_dart/robots/vx300.hpp

"},{"location":"api/vx300_8hpp_source/","title":"File vx300.hpp","text":"

File List > robot_dart > robots > vx300.hpp

Go to the documentation of this file

#ifndef ROBOT_DART_ROBOTS_VX300_HPP\n#define ROBOT_DART_ROBOTS_VX300_HPP\n#include \"robot_dart/robot.hpp\"\nnamespace robot_dart {\nnamespace robots {\nclass Vx300 : public Robot {\npublic:\nVx300(const std::string& urdf = \"vx300/vx300.urdf\", const std::vector<std::pair<std::string, std::string>>& packages = ('interbotix_xsarm_descriptions', 'vx300')) : Robot(urdf, packages)\n{\nfix_to_world();\nset_position_enforced(true);\nset_color_mode(\"aspect\");\n}\n};\n} // namespace robots\n} // namespace robot_dart\n#endif\n
"},{"location":"api/dir_d1adb19f0b40b70b30ee0daf1901679b/","title":"Dir robot_dart/sensor","text":"

FileList > robot_dart > sensor

"},{"location":"api/dir_d1adb19f0b40b70b30ee0daf1901679b/#files","title":"Files","text":"Type Name file force_torque.cpp file force_torque.hpp file imu.cpp file imu.hpp file sensor.cpp file sensor.hpp file torque.cpp file torque.hpp

The documentation for this class was generated from the following file robot_dart/sensor/

"},{"location":"api/force__torque_8cpp/","title":"File force_torque.cpp","text":"

FileList > robot_dart > sensor > force_torque.cpp

Go to the source code of this file

"},{"location":"api/force__torque_8cpp/#namespaces","title":"Namespaces","text":"Type Name namespace robot_dart namespace sensor

The documentation for this class was generated from the following file robot_dart/sensor/force_torque.cpp

"},{"location":"api/force__torque_8cpp_source/","title":"File force_torque.cpp","text":"

File List > robot_dart > sensor > force_torque.cpp

Go to the documentation of this file

#include \"force_torque.hpp\"\n#include <robot_dart/utils_headers_dart_dynamics.hpp>\nnamespace robot_dart {\nnamespace sensor {\nForceTorque::ForceTorque(dart::dynamics::Joint* joint, size_t frequency, const std::string& direction) : Sensor(frequency), _direction(direction)\n{\nattach_to_joint(joint, Eigen::Isometry3d::Identity());\n}\nvoid ForceTorque::init()\n{\n_wrench.setZero();\nattach_to_joint(_joint_attached, Eigen::Isometry3d::Identity());\n_active = true;\n}\nvoid ForceTorque::calculate(double)\n{\nif (!_attached_to_joint)\nreturn; // cannot compute anything if not attached to a joint\nEigen::Vector6d wrench = Eigen::Vector6d::Zero();\nauto child_body = _joint_attached->getChildBodyNode();\nROBOT_DART_ASSERT(child_body != nullptr, \"Child BodyNode is nullptr\", );\nwrench = -dart::math::dAdT(_joint_attached->getTransformFromChildBodyNode(), child_body->getBodyForce());\n// We always compute things in SENSOR frame (aka joint frame)\nif (_direction == \"parent_to_child\") {\n_wrench = wrench;\n}\nelse // \"child_to_parent\" (default)\n{\n_wrench = -wrench;\n}\n}\nstd::string ForceTorque::type() const { return \"ft\"; }\nEigen::Vector3d ForceTorque::force() const\n{\nreturn _wrench.tail(3);\n}\nEigen::Vector3d ForceTorque::torque() const\n{\nreturn _wrench.head(3);\n}\nconst Eigen::Vector6d& ForceTorque::wrench() const\n{\nreturn _wrench;\n}\n} // namespace sensor\n} // namespace robot_dart\n
"},{"location":"api/force__torque_8hpp/","title":"File force_torque.hpp","text":"

FileList > robot_dart > sensor > force_torque.hpp

Go to the source code of this file

"},{"location":"api/force__torque_8hpp/#namespaces","title":"Namespaces","text":"Type Name namespace robot_dart namespace sensor"},{"location":"api/force__torque_8hpp/#classes","title":"Classes","text":"Type Name class ForceTorque

The documentation for this class was generated from the following file robot_dart/sensor/force_torque.hpp

"},{"location":"api/force__torque_8hpp_source/","title":"File force_torque.hpp","text":"

File List > robot_dart > sensor > force_torque.hpp

Go to the documentation of this file

#ifndef ROBOT_DART_SENSOR_FORCE_TORQUE_HPP\n#define ROBOT_DART_SENSOR_FORCE_TORQUE_HPP\n#include <robot_dart/sensor/sensor.hpp>\nnamespace robot_dart {\nnamespace sensor {\nclass ForceTorque : public Sensor {\npublic:\nForceTorque(dart::dynamics::Joint* joint, size_t frequency = 1000, const std::string& direction = \"child_to_parent\");\nForceTorque(const std::shared_ptr<Robot>& robot, const std::string& joint_name, size_t frequency = 1000, const std::string& direction = \"child_to_parent\") : ForceTorque(robot->joint(joint_name), frequency, direction) {}\nvoid init() override;\nvoid calculate(double) override;\nstd::string type() const override;\nEigen::Vector3d force() const;\nEigen::Vector3d torque() const;\nconst Eigen::Vector6d& wrench() const;\nvoid attach_to_body(dart::dynamics::BodyNode*, const Eigen::Isometry3d&) override\n{\nROBOT_DART_WARNING(true, \"You cannot attach a force/torque sensor to a body!\");\n}\nprotected:\nstd::string _direction;\nEigen::Vector6d _wrench;\n};\n} // namespace sensor\n} // namespace robot_dart\n#endif\n
"},{"location":"api/imu_8cpp/","title":"File imu.cpp","text":"

FileList > robot_dart > sensor > imu.cpp

Go to the source code of this file

"},{"location":"api/imu_8cpp/#namespaces","title":"Namespaces","text":"Type Name namespace robot_dart namespace sensor

The documentation for this class was generated from the following file robot_dart/sensor/imu.cpp

"},{"location":"api/imu_8cpp_source/","title":"File imu.cpp","text":"

File List > robot_dart > sensor > imu.cpp

Go to the documentation of this file

#include \"imu.hpp\"\n#include <robot_dart/robot_dart_simu.hpp>\n#include <robot_dart/utils_headers_dart_dynamics.hpp>\nnamespace robot_dart {\nnamespace sensor {\nIMU::IMU(const IMUConfig& config) : Sensor(config.frequency), _config(config) {}\nvoid IMU::init()\n{\n_angular_vel.setZero();\n_linear_accel.setZero();\nattach_to_body(_config.body, Eigen::Isometry3d::Identity());\nif (_simu)\n_active = true;\n}\nvoid IMU::calculate(double)\n{\nif (!_attached_to_body)\nreturn; // cannot compute anything if not attached to a link\nROBOT_DART_EXCEPTION_ASSERT(_simu, \"Simulation pointer is null!\");\nEigen::Vector3d tmp = dart::math::logMap(_body_attached->getTransform(dart::dynamics::Frame::World(), _body_attached).linear().matrix());\n_angular_pos = Eigen::AngleAxisd(tmp.norm(), tmp.normalized());\n_angular_vel = _body_attached->getSpatialVelocity().head(3); // angular velocity with respect to the world, in local coordinates\n_linear_accel = _body_attached->getSpatialAcceleration().tail(3); // linear acceleration with respect to the world, in local coordinates\n// add biases\n_angular_vel += _config.gyro_bias;\n_linear_accel += _config.accel_bias;\n// add gravity to acceleration\n_linear_accel -= _world_pose.linear().transpose() * _simu->gravity();\n}\nstd::string IMU::type() const { return \"imu\"; }\nconst Eigen::AngleAxisd& IMU::angular_position() const\n{\nreturn _angular_pos;\n}\nEigen::Vector3d IMU::angular_position_vec() const\n{\nreturn _angular_pos.angle() * _angular_pos.axis();\n}\nconst Eigen::Vector3d& IMU::angular_velocity() const\n{\nreturn _angular_vel;\n}\nconst Eigen::Vector3d& IMU::linear_acceleration() const\n{\nreturn _linear_accel;\n}\n} // namespace sensor\n} // namespace robot_dart\n
"},{"location":"api/imu_8hpp/","title":"File imu.hpp","text":"

FileList > robot_dart > sensor > imu.hpp

Go to the source code of this file

"},{"location":"api/imu_8hpp/#namespaces","title":"Namespaces","text":"Type Name namespace robot_dart namespace sensor"},{"location":"api/imu_8hpp/#classes","title":"Classes","text":"Type Name class IMU struct IMUConfig

The documentation for this class was generated from the following file robot_dart/sensor/imu.hpp

"},{"location":"api/imu_8hpp_source/","title":"File imu.hpp","text":"

File List > robot_dart > sensor > imu.hpp

Go to the documentation of this file

#ifndef ROBOT_DART_SENSOR_IMU_HPP\n#define ROBOT_DART_SENSOR_IMU_HPP\n#include <robot_dart/sensor/sensor.hpp>\nnamespace robot_dart {\nnamespace sensor {\n// TO-DO: Implement some noise models (e.g., https://github.com/ethz-asl/kalibr/wiki/IMU-Noise-Model)\nstruct IMUConfig {\nIMUConfig(dart::dynamics::BodyNode* b, size_t f) : gyro_bias(Eigen::Vector3d::Zero()), accel_bias(Eigen::Vector3d::Zero()), body(b), frequency(f){};\nIMUConfig(const Eigen::Vector3d& gyro_bias, const Eigen::Vector3d& accel_bias, dart::dynamics::BodyNode* b, size_t f) : gyro_bias(gyro_bias), accel_bias(accel_bias), body(b), frequency(f){};\nIMUConfig() : gyro_bias(Eigen::Vector3d::Zero()), accel_bias(Eigen::Vector3d::Zero()), body(nullptr), frequency(200) {}\n// We assume fixed bias; TO-DO: Make this time-dependent\nEigen::Vector3d gyro_bias = Eigen::Vector3d::Zero();\nEigen::Vector3d accel_bias = Eigen::Vector3d::Zero();\n// // We assume white Gaussian noise // TO-DO: Implement this\n// Eigen::Vector3d _gyro_std = Eigen::Vector3d::Zero();\n// Eigen::Vector3d _accel_std = Eigen::Vector3d::Zero();\n// BodyNode/Link attached to\ndart::dynamics::BodyNode* body = nullptr;\n// Eigen::Isometry3d _tf = Eigen::Isometry3d::Identity();\n// Frequency\nsize_t frequency = 200;\n};\nclass IMU : public Sensor {\npublic:\nIMU(const IMUConfig& config);\nvoid init() override;\nvoid calculate(double) override;\nstd::string type() const override;\nconst Eigen::AngleAxisd& angular_position() const;\nEigen::Vector3d angular_position_vec() const;\nconst Eigen::Vector3d& angular_velocity() const;\nconst Eigen::Vector3d& linear_acceleration() const;\nvoid attach_to_joint(dart::dynamics::Joint*, const Eigen::Isometry3d&) override\n{\nROBOT_DART_WARNING(true, \"You cannot attach an IMU sensor to a joint!\");\n}\nprotected:\n// double _prev_time = 0.;\nIMUConfig _config;\nEigen::AngleAxisd _angular_pos; // TO-DO: Check how to do this as close as possible to real sensors\nEigen::Vector3d _angular_vel;\nEigen::Vector3d _linear_accel;\n};\n} // namespace sensor\n} // namespace robot_dart\n#endif\n
"},{"location":"api/sensor_8cpp/","title":"File sensor.cpp","text":"

FileList > robot_dart > sensor > sensor.cpp

Go to the source code of this file

"},{"location":"api/sensor_8cpp/#namespaces","title":"Namespaces","text":"Type Name namespace robot_dart namespace sensor

The documentation for this class was generated from the following file robot_dart/sensor/sensor.cpp

"},{"location":"api/sensor_8cpp_source/","title":"File sensor.cpp","text":"

File List > robot_dart > sensor > sensor.cpp

Go to the documentation of this file

#include \"sensor.hpp\"\n#include \"robot_dart/robot_dart_simu.hpp\"\n#include \"robot_dart/utils.hpp\"\n#include \"robot_dart/utils_headers_dart_dynamics.hpp\"\nnamespace robot_dart {\nnamespace sensor {\nSensor::Sensor(size_t freq) : _active(false), _frequency(freq), _world_pose(Eigen::Isometry3d::Identity()), _attaching_to_body(false), _attached_to_body(false), _attaching_to_joint(false), _attached_to_joint(false) {}\nvoid Sensor::activate(bool enable)\n{\n_active = false;\nif (enable) {\ninit();\n}\n}\nbool Sensor::active() const\n{\nreturn _active;\n}\nvoid Sensor::set_simu(RobotDARTSimu* simu)\n{\nROBOT_DART_EXCEPTION_ASSERT(simu, \"Simulation pointer is null!\");\n_simu = simu;\nbool check = static_cast<int>(_frequency) > simu->physics_freq();\nROBOT_DART_WARNING(check, \"Sensor frequency is bigger than simulation physics. Setting it to simulation rate!\");\nif (check)\n_frequency = simu->physics_freq();\n}\nconst RobotDARTSimu* Sensor::simu() const\n{\nreturn _simu;\n}\nsize_t Sensor::frequency() const { return _frequency; }\nvoid Sensor::set_frequency(size_t freq) { _frequency = freq; }\nvoid Sensor::set_pose(const Eigen::Isometry3d& tf) { _world_pose = tf; }\nconst Eigen::Isometry3d& Sensor::pose() const { return _world_pose; }\nvoid Sensor::detach()\n{\n_attached_to_body = false;\n_attached_to_joint = false;\n_body_attached = nullptr;\n_joint_attached = nullptr;\n_active = false;\n}\nvoid Sensor::refresh(double t)\n{\nif (!_active)\nreturn;\nif (_attaching_to_body && !_attached_to_body) {\nattach_to_body(_body_attached, _attached_tf);\n}\nelse if (_attaching_to_joint && !_attached_to_joint) {\nattach_to_joint(_joint_attached, _attached_tf);\n}\nif (_attached_to_body && _body_attached) {\n_world_pose = _body_attached->getWorldTransform() * _attached_tf;\n}\nelse if (_attached_to_joint && _joint_attached) {\ndart::dynamics::BodyNode* body = nullptr;\nEigen::Isometry3d tf = Eigen::Isometry3d::Identity();\nif (_joint_attached->getParentBodyNode()) {\nbody = _joint_attached->getParentBodyNode();\ntf = _joint_attached->getTransformFromParentBodyNode();\n}\nelse if (_joint_attached->getChildBodyNode()) {\nbody = _joint_attached->getChildBodyNode();\ntf = _joint_attached->getTransformFromChildBodyNode();\n}\nif (body)\n_world_pose = body->getWorldTransform() * tf * _attached_tf;\n}\ncalculate(t);\n}\nvoid Sensor::attach_to_body(dart::dynamics::BodyNode* body, const Eigen::Isometry3d& tf)\n{\n_body_attached = body;\n_attached_tf = tf;\nif (_body_attached) {\n_attaching_to_body = false;\n_attached_to_body = true;\n_attaching_to_joint = false;\n_attached_to_joint = false;\n_joint_attached = nullptr;\n}\nelse { // we cannot keep attaching to a null BodyNode\n_attaching_to_body = false;\n_attached_to_body = false;\n}\n}\nvoid Sensor::attach_to_joint(dart::dynamics::Joint* joint, const Eigen::Isometry3d& tf)\n{\n_joint_attached = joint;\n_attached_tf = tf;\nif (_joint_attached) {\n_attaching_to_joint = false;\n_attached_to_joint = true;\n_attaching_to_body = false;\n_attached_to_body = false;\n}\nelse { // we cannot keep attaching to a null Joint\n_attaching_to_joint = false;\n_attached_to_joint = false;\n}\n}\nconst std::string& Sensor::attached_to() const\n{\nROBOT_DART_EXCEPTION_ASSERT(_attached_to_body || _attached_to_joint, \"Joint is not attached to anything\");\nif (_attached_to_body)\nreturn _body_attached->getName();\n// attached to joint\nreturn _joint_attached->getName();\n}\n} // namespace sensor\n} // namespace robot_dart\n
"},{"location":"api/sensor_8hpp/","title":"File sensor.hpp","text":"

FileList > robot_dart > sensor > sensor.hpp

Go to the source code of this file

"},{"location":"api/sensor_8hpp/#namespaces","title":"Namespaces","text":"Type Name namespace dart namespace dynamics namespace robot_dart namespace sensor"},{"location":"api/sensor_8hpp/#classes","title":"Classes","text":"Type Name class Sensor

The documentation for this class was generated from the following file robot_dart/sensor/sensor.hpp

"},{"location":"api/sensor_8hpp_source/","title":"File sensor.hpp","text":"

File List > robot_dart > sensor > sensor.hpp

Go to the documentation of this file

#ifndef ROBOT_DART_SENSOR_SENSOR_HPP\n#define ROBOT_DART_SENSOR_SENSOR_HPP\n#include <robot_dart/robot.hpp>\n#include <robot_dart/utils.hpp>\n#include <memory>\n#include <vector>\nnamespace dart {\nnamespace dynamics {\nclass BodyNode;\nclass Joint;\n} // namespace dynamics\n} // namespace dart\nnamespace robot_dart {\nclass RobotDARTSimu;\nnamespace sensor {\nclass Sensor {\npublic:\nSensor(size_t freq = 40);\nvirtual ~Sensor() {}\nvoid activate(bool enable = true);\nbool active() const;\nvoid set_simu(RobotDARTSimu* simu);\nconst RobotDARTSimu* simu() const;\nsize_t frequency() const;\nvoid set_frequency(size_t freq);\nvoid set_pose(const Eigen::Isometry3d& tf);\nconst Eigen::Isometry3d& pose() const;\nvoid refresh(double t);\nvirtual void init() = 0;\n// TO-DO: Maybe make this const?\nvirtual void calculate(double) = 0;\nvirtual std::string type() const = 0;\nvirtual void attach_to_body(dart::dynamics::BodyNode* body, const Eigen::Isometry3d& tf = Eigen::Isometry3d::Identity());\nvoid attach_to_body(const std::shared_ptr<Robot>& robot, const std::string& body_name, const Eigen::Isometry3d& tf = Eigen::Isometry3d::Identity()) { attach_to_body(robot->body_node(body_name), tf); }\nvirtual void attach_to_joint(dart::dynamics::Joint* joint, const Eigen::Isometry3d& tf = Eigen::Isometry3d::Identity());\nvoid attach_to_joint(const std::shared_ptr<Robot>& robot, const std::string& joint_name, const Eigen::Isometry3d& tf = Eigen::Isometry3d::Identity()) { attach_to_joint(robot->joint(joint_name), tf); }\nvoid detach();\nconst std::string& attached_to() const;\nprotected:\nRobotDARTSimu* _simu = nullptr;\nbool _active;\nsize_t _frequency;\nEigen::Isometry3d _world_pose;\nbool _attaching_to_body = false, _attached_to_body = false;\nbool _attaching_to_joint = false, _attached_to_joint = false;\nEigen::Isometry3d _attached_tf;\ndart::dynamics::BodyNode* _body_attached;\ndart::dynamics::Joint* _joint_attached;\n};\n} // namespace sensor\n} // namespace robot_dart\n#endif\n
"},{"location":"api/torque_8cpp/","title":"File torque.cpp","text":"

FileList > robot_dart > sensor > torque.cpp

Go to the source code of this file

"},{"location":"api/torque_8cpp/#namespaces","title":"Namespaces","text":"Type Name namespace robot_dart namespace sensor

The documentation for this class was generated from the following file robot_dart/sensor/torque.cpp

"},{"location":"api/torque_8cpp_source/","title":"File torque.cpp","text":"

File List > robot_dart > sensor > torque.cpp

Go to the documentation of this file

#include \"torque.hpp\"\n#include <robot_dart/robot_dart_simu.hpp>\n#include <robot_dart/utils_headers_dart_dynamics.hpp>\nnamespace robot_dart {\nnamespace sensor {\nTorque::Torque(dart::dynamics::Joint* joint, size_t frequency) : Sensor(frequency), _torques(joint->getNumDofs())\n{\nattach_to_joint(joint, Eigen::Isometry3d::Identity());\n}\nvoid Torque::init()\n{\n_torques.setZero();\nattach_to_joint(_joint_attached, Eigen::Isometry3d::Identity());\n_active = true;\n}\nvoid Torque::calculate(double)\n{\nif (!_attached_to_joint)\nreturn; // cannot compute anything if not attached to a joint\nEigen::Vector6d wrench = Eigen::Vector6d::Zero();\nauto child_body = _joint_attached->getChildBodyNode();\nROBOT_DART_ASSERT(child_body != nullptr, \"Child BodyNode is nullptr\", );\nwrench = child_body->getBodyForce();\n// get forces for only the only degrees of freedom in this joint\n_torques = _joint_attached->getRelativeJacobian().transpose() * wrench;\n}\nstd::string Torque::type() const { return \"t\"; }\nconst Eigen::VectorXd& Torque::torques() const\n{\nreturn _torques;\n}\n} // namespace sensor\n} // namespace robot_dart\n
"},{"location":"api/torque_8hpp/","title":"File torque.hpp","text":"

FileList > robot_dart > sensor > torque.hpp

Go to the source code of this file

"},{"location":"api/torque_8hpp/#namespaces","title":"Namespaces","text":"Type Name namespace robot_dart namespace sensor"},{"location":"api/torque_8hpp/#classes","title":"Classes","text":"Type Name class Torque

The documentation for this class was generated from the following file robot_dart/sensor/torque.hpp

"},{"location":"api/torque_8hpp_source/","title":"File torque.hpp","text":"

File List > robot_dart > sensor > torque.hpp

Go to the documentation of this file

#ifndef ROBOT_DART_SENSOR_TORQUE_HPP\n#define ROBOT_DART_SENSOR_TORQUE_HPP\n#include <robot_dart/sensor/sensor.hpp>\nnamespace robot_dart {\nnamespace sensor {\nclass Torque : public Sensor {\npublic:\nTorque(dart::dynamics::Joint* joint, size_t frequency = 1000);\nTorque(const std::shared_ptr<Robot>& robot, const std::string& joint_name, size_t frequency = 1000) : Torque(robot->joint(joint_name), frequency) {}\nvoid init() override;\nvoid calculate(double) override;\nstd::string type() const override;\nconst Eigen::VectorXd& torques() const;\nvoid attach_to_body(dart::dynamics::BodyNode*, const Eigen::Isometry3d&) override\n{\nROBOT_DART_WARNING(true, \"You cannot attach a torque sensor to a body!\");\n}\nprotected:\nEigen::VectorXd _torques;\n};\n} // namespace sensor\n} // namespace robot_dart\n#endif\n
"},{"location":"api/robot__dart__simu_8cpp/","title":"File robot_dart_simu.cpp","text":"

FileList > robot_dart > robot_dart_simu.cpp

Go to the source code of this file

"},{"location":"api/robot__dart__simu_8cpp/#namespaces","title":"Namespaces","text":"Type Name namespace robot_dart namespace collision_filter"},{"location":"api/robot__dart__simu_8cpp/#classes","title":"Classes","text":"Type Name class BitmaskContactFilter struct Masks

The documentation for this class was generated from the following file robot_dart/robot_dart_simu.cpp

"},{"location":"api/robot__dart__simu_8cpp_source/","title":"File robot_dart_simu.cpp","text":"

File List > robot_dart > robot_dart_simu.cpp

Go to the documentation of this file

#include \"robot_dart_simu.hpp\"\n#include \"gui_data.hpp\"\n#include \"utils.hpp\"\n#include \"utils_headers_dart_collision.hpp\"\n#include \"utils_headers_dart_dynamics.hpp\"\n#include <sstream>\nnamespace robot_dart {\nnamespace collision_filter {\n// This is inspired from Swift: https://developer.apple.com/documentation/spritekit/skphysicsbody#//apple_ref/occ/instp/SKPhysicsBody/collisionBitMask\n// https://stackoverflow.com/questions/39063949/cant-understand-how-collision-bit-mask-works\nclass BitmaskContactFilter : public dart::collision::BodyNodeCollisionFilter {\npublic:\nusing DartCollisionConstPtr = const dart::collision::CollisionObject*;\nusing DartShapeConstPtr = const dart::dynamics::ShapeNode*;\nstruct Masks {\nuint32_t collision_mask = 0xffffffff;\nuint32_t category_mask = 0xffffffff;\n};\nvirtual ~BitmaskContactFilter() = default;\n// This function follows DART's coding style as it needs to override a function\nbool ignoresCollision(DartCollisionConstPtr object1, DartCollisionConstPtr object2) const override\n{\nauto shape_node1 = object1->getShapeFrame()->asShapeNode();\nauto shape_node2 = object2->getShapeFrame()->asShapeNode();\nif (dart::collision::BodyNodeCollisionFilter::ignoresCollision(object1, object2))\nreturn true;\nauto shape1_iter = _bitmask_map.find(shape_node1);\nauto shape2_iter = _bitmask_map.find(shape_node2);\nif (shape1_iter != _bitmask_map.end() && shape2_iter != _bitmask_map.end()) {\nauto col_mask1 = shape1_iter->second.collision_mask;\nauto cat_mask1 = shape1_iter->second.category_mask;\nauto col_mask2 = shape2_iter->second.collision_mask;\nauto cat_mask2 = shape2_iter->second.category_mask;\nif ((col_mask1 & cat_mask2) == 0 && (col_mask2 & cat_mask1) == 0)\nreturn true;\n}\nreturn false;\n}\nvoid add_to_map(DartShapeConstPtr shape, uint32_t col_mask, uint32_t cat_mask)\n{\n_bitmask_map[shape] = {col_mask, cat_mask};\n}\nvoid add_to_map(dart::dynamics::SkeletonPtr skel, uint32_t col_mask, uint32_t cat_mask)\n{\nfor (std::size_t i = 0; i < skel->getNumShapeNodes(); ++i) {\nauto shape = skel->getShapeNode(i);\nthis->add_to_map(shape, col_mask, cat_mask);\n}\n}\nvoid remove_from_map(DartShapeConstPtr shape)\n{\nauto shape_iter = _bitmask_map.find(shape);\nif (shape_iter != _bitmask_map.end())\n_bitmask_map.erase(shape_iter);\n}\nvoid remove_from_map(dart::dynamics::SkeletonPtr skel)\n{\nfor (std::size_t i = 0; i < skel->getNumShapeNodes(); ++i) {\nauto shape = skel->getShapeNode(i);\nthis->remove_from_map(shape);\n}\n}\nvoid clear_all() { _bitmask_map.clear(); }\nMasks mask(DartShapeConstPtr shape) const\n{\nauto shape_iter = _bitmask_map.find(shape);\nif (shape_iter != _bitmask_map.end())\nreturn shape_iter->second;\nreturn {0xffffffff, 0xffffffff};\n}\nprivate:\n// We need ShapeNodes and not BodyNodes, since in DART collision checking is performed in ShapeNode-level\n// in RobotDARTSimu, we only allow setting one mask per BodyNode; maybe we can improve the performance of this slightly\nstd::unordered_map<DartShapeConstPtr, Masks> _bitmask_map;\n};\n} // namespace collision_filter\nRobotDARTSimu::RobotDARTSimu(double timestep) : _world(std::make_shared<dart::simulation::World>()),\n_old_index(0),\n_break(false),\n_scheduler(timestep),\n_physics_freq(std::round(1. / timestep)),\n_control_freq(_physics_freq)\n{\n_world->getConstraintSolver()->setCollisionDetector(dart::collision::DARTCollisionDetector::create());\n_world->getConstraintSolver()->getCollisionOption().collisionFilter = std::make_shared<collision_filter::BitmaskContactFilter>();\n_world->setTimeStep(timestep);\n_world->setTime(0.0);\n_graphics = std::make_shared<gui::Base>();\n_gui_data.reset(new simu::GUIData());\n}\nRobotDARTSimu::~RobotDARTSimu()\n{\n_robots.clear();\n_sensors.clear();\n}\nvoid RobotDARTSimu::run(double max_duration, bool reset_commands, bool force_position_bounds)\n{\n_break = false;\ndouble old_time = _world->getTime();\ndouble factor = _world->getTimeStep() / 2.;\nwhile ((_world->getTime() - old_time - max_duration) < -factor) {\nif (step(reset_commands, force_position_bounds))\nbreak;\n}\n}\nbool RobotDARTSimu::step_world(bool reset_commands, bool force_position_bounds)\n{\nif (_scheduler(_physics_freq)) {\n_world->step(reset_commands);\nif (force_position_bounds)\nfor (auto& r : _robots)\nr->force_position_bounds();\n}\n// Update graphics\nif (_scheduler(_graphics_freq)) {\n// Update default texts\nif (_text_panel) { // Need to re-transform as the size of the window might have changed\nEigen::Affine2d tf = Eigen::Affine2d::Identity();\ntf.translate(Eigen::Vector2d(-static_cast<double>(_graphics->width()) / 2., _graphics->height() / 2.));\n_text_panel->transformation = tf;\n}\nif (_status_bar) {\n_status_bar->text = status_bar_text(); // this is dynamic text (timings)\nEigen::Affine2d tf = Eigen::Affine2d::Identity();\ntf.translate(Eigen::Vector2d(-static_cast<double>(_graphics->width()) / 2., -static_cast<double>(_graphics->height() / 2.)));\n_status_bar->transformation = tf;\n}\n// Update robot-specific GUI data\nfor (auto& robot : _robots) {\n_gui_data->update_robot(robot);\n}\n_graphics->refresh();\n}\n// update sensors\nfor (auto& sensor : _sensors) {\nif (sensor->active() && _scheduler(sensor->frequency())) {\nsensor->refresh(_world->getTime());\n}\n}\n_old_index++;\n_scheduler.step();\nreturn _break || _graphics->done();\n}\nbool RobotDARTSimu::step(bool reset_commands, bool force_position_bounds)\n{\nif (_scheduler(_control_freq)) {\nfor (auto& robot : _robots) {\nrobot->update(_world->getTime());\n}\n}\nreturn step_world(reset_commands, force_position_bounds);\n}\nstd::shared_ptr<gui::Base> RobotDARTSimu::graphics() const\n{\nreturn _graphics;\n}\nvoid RobotDARTSimu::set_graphics(const std::shared_ptr<gui::Base>& graphics)\n{\n_graphics = graphics;\n_graphics->set_simu(this);\n_graphics->set_fps(_graphics_freq);\n}\ndart::simulation::WorldPtr RobotDARTSimu::world()\n{\nreturn _world;\n}\nvoid RobotDARTSimu::add_sensor(const std::shared_ptr<sensor::Sensor>& sensor)\n{\n_sensors.push_back(sensor);\nsensor->set_simu(this);\nsensor->init();\n}\nstd::vector<std::shared_ptr<sensor::Sensor>> RobotDARTSimu::sensors() const\n{\nreturn _sensors;\n}\nstd::shared_ptr<sensor::Sensor> RobotDARTSimu::sensor(size_t index) const\n{\nROBOT_DART_ASSERT(index < _sensors.size(), \"Sensor index out of bounds\", nullptr);\nreturn _sensors[index];\n}\nvoid RobotDARTSimu::remove_sensor(const std::shared_ptr<sensor::Sensor>& sensor)\n{\nauto it = std::find(_sensors.begin(), _sensors.end(), sensor);\nif (it != _sensors.end()) {\n_sensors.erase(it);\n}\n}\nvoid RobotDARTSimu::remove_sensor(size_t index)\n{\nROBOT_DART_ASSERT(index < _sensors.size(), \"Sensor index out of bounds\", );\n_sensors.erase(_sensors.begin() + index);\n}\nvoid RobotDARTSimu::remove_sensors(const std::string& type)\n{\nfor (int i = 0; i < static_cast<int>(_sensors.size()); i++) {\nauto& sensor = _sensors[i];\nif (sensor->type() == type) {\n_sensors.erase(_sensors.begin() + i);\ni--;\n}\n}\n}\nvoid RobotDARTSimu::clear_sensors()\n{\n_sensors.clear();\n}\ndouble RobotDARTSimu::timestep() const\n{\nreturn _world->getTimeStep();\n}\nvoid RobotDARTSimu::set_timestep(double timestep, bool update_control_freq)\n{\n_world->setTimeStep(timestep);\n_physics_freq = std::round(1. / timestep);\nif (update_control_freq)\n_control_freq = _physics_freq;\n_scheduler.reset(timestep, _scheduler.sync(), _scheduler.current_time(), _scheduler.real_time());\n}\nEigen::Vector3d RobotDARTSimu::gravity() const\n{\nreturn _world->getGravity();\n}\nvoid RobotDARTSimu::set_gravity(const Eigen::Vector3d& gravity)\n{\n_world->setGravity(gravity);\n}\nvoid RobotDARTSimu::stop_sim(bool disable)\n{\n_break = disable;\n}\nbool RobotDARTSimu::halted_sim() const\n{\nreturn _break;\n}\nsize_t RobotDARTSimu::num_robots() const\n{\nreturn _robots.size();\n}\nconst std::vector<std::shared_ptr<Robot>>& RobotDARTSimu::robots() const\n{\nreturn _robots;\n}\nstd::shared_ptr<Robot> RobotDARTSimu::robot(size_t index) const\n{\nROBOT_DART_ASSERT(index < _robots.size(), \"Robot index out of bounds\", nullptr);\nreturn _robots[index];\n}\nint RobotDARTSimu::robot_index(const std::shared_ptr<Robot>& robot) const\n{\nauto it = std::find(_robots.begin(), _robots.end(), robot);\nROBOT_DART_ASSERT(it != _robots.end(), \"Robot index out of bounds\", -1);\nreturn std::distance(_robots.begin(), it);\n}\nvoid RobotDARTSimu::add_robot(const std::shared_ptr<Robot>& robot)\n{\nif (robot->skeleton()) {\n_robots.push_back(robot);\n_world->addSkeleton(robot->skeleton());\nrobot->_post_addition(this);\n_gui_data->update_robot(robot);\n}\n}\nvoid RobotDARTSimu::add_visual_robot(const std::shared_ptr<Robot>& robot)\n{\nif (robot->skeleton()) {\n// make robot a pure visual one -- assuming that the color is already set\n// visual robots do not do physics updates\nrobot->skeleton()->setMobile(false);\nfor (auto& bd : robot->skeleton()->getBodyNodes()) {\n// visual robots do not have collisions\nauto& collision_shapes = bd->getShapeNodesWith<dart::dynamics::CollisionAspect>();\nfor (auto& shape : collision_shapes) {\nshape->removeAspect<dart::dynamics::CollisionAspect>();\n}\n}\n// visual robots, by default, use the color from the VisualAspect\nrobot->set_color_mode(\"aspect\");\n// visual robots do not cast shadows\nrobot->set_cast_shadows(false);\n// set the ghost/visual flag\nrobot->set_ghost(true);\nrobot->_post_addition(this);\n_robots.push_back(robot);\n_world->addSkeleton(robot->skeleton());\n_gui_data->update_robot(robot);\n}\n}\nvoid RobotDARTSimu::remove_robot(const std::shared_ptr<Robot>& robot)\n{\nauto it = std::find(_robots.begin(), _robots.end(), robot);\nif (it != _robots.end()) {\nrobot->_post_removal(this);\n_gui_data->remove_robot(robot);\n_world->removeSkeleton(robot->skeleton());\n_robots.erase(it);\n}\n}\nvoid RobotDARTSimu::remove_robot(size_t index)\n{\nROBOT_DART_ASSERT(index < _robots.size(), \"Robot index out of bounds\", );\n_robots[index]->_post_removal(this);\n_gui_data->remove_robot(_robots[index]);\n_world->removeSkeleton(_robots[index]->skeleton());\n_robots.erase(_robots.begin() + index);\n}\nvoid RobotDARTSimu::clear_robots()\n{\nfor (auto& robot : _robots) {\nrobot->_post_removal(this);\n_gui_data->remove_robot(robot);\n_world->removeSkeleton(robot->skeleton());\n}\n_robots.clear();\n}\nsimu::GUIData* RobotDARTSimu::gui_data() { return &(*_gui_data); }\nvoid RobotDARTSimu::enable_text_panel(bool enable, double font_size) { _enable(_text_panel, enable, font_size); }\nvoid RobotDARTSimu::enable_status_bar(bool enable, double font_size)\n{\n_enable(_status_bar, enable, font_size);\nif (enable) {\n_status_bar->alignment = (1 | 1 << 3); // alignment of status bar should be LineLeft\n_status_bar->draw_background = true; // we want to draw a background\n_status_bar->background_color = Eigen::Vector4d(0, 0, 0, 0.75); // black-transparent bar\n}\n}\nvoid RobotDARTSimu::_enable(std::shared_ptr<simu::TextData>& text, bool enable, double font_size)\n{\nif (!text && enable) {\ntext = _gui_data->add_text(\"\");\n}\nelse if (!enable) {\nif (text)\n_gui_data->remove_text(text);\ntext = nullptr;\n}\nif (text && font_size > 0)\ntext->font_size = font_size;\n}\nvoid RobotDARTSimu::set_text_panel(const std::string& str)\n{\nROBOT_DART_ASSERT(_text_panel, \"Panel text object not created. Use enable_text_panel() to create it.\", );\n_text_panel->text = str;\n}\nstd::string RobotDARTSimu::text_panel_text() const\n{\nROBOT_DART_ASSERT(_text_panel, \"Panel text object not created. Returning empty string.\", \"\");\nreturn _text_panel->text;\n}\nstd::string RobotDARTSimu::status_bar_text() const\n{\nstd::ostringstream out;\nout.precision(3);\ndouble rt = _scheduler.real_time();\nout << std::fixed << \"[simulation time: \" << _world->getTime()\n<< \"s ] [\"\n<< \"wall time: \" << rt << \"s] [\";\nout.precision(1);\nout << _scheduler.real_time_factor() << \"x]\";\nout << \" [it: \" << _scheduler.it_duration() * 1e3 << \" ms]\";\nout << (_scheduler.sync() ? \" [sync]\" : \" [no-sync]\");\nreturn out.str();\n}\nstd::shared_ptr<simu::TextData> RobotDARTSimu::add_text(const std::string& text, const Eigen::Affine2d& tf, Eigen::Vector4d color, std::uint8_t alignment, bool draw_bg, Eigen::Vector4d bg_color, double font_size)\n{\nreturn _gui_data->add_text(text, tf, color, alignment, draw_bg, bg_color, font_size);\n}\nstd::shared_ptr<Robot> RobotDARTSimu::add_floor(double floor_width, double floor_height, const Eigen::Isometry3d& tf, const std::string& floor_name)\n{\nROBOT_DART_ASSERT((_world->getSkeleton(floor_name) == nullptr), \"We cannot have 2 floors with the name '\" + floor_name + \"'\", nullptr);\nROBOT_DART_ASSERT((floor_width > 0. && floor_height > 0.), \"Floor dimensions should be bigger than zero!\", nullptr);\ndart::dynamics::SkeletonPtr floor_skel = dart::dynamics::Skeleton::create(floor_name);\n// Give the floor a body\ndart::dynamics::BodyNodePtr body = floor_skel->createJointAndBodyNodePair<dart::dynamics::WeldJoint>(nullptr).second;\n// Give the body a shape\nauto box = std::make_shared<dart::dynamics::BoxShape>(Eigen::Vector3d(floor_width, floor_width, floor_height));\nauto box_node = body->createShapeNodeWith<dart::dynamics::VisualAspect, dart::dynamics::CollisionAspect, dart::dynamics::DynamicsAspect>(box);\nbox_node->getVisualAspect()->setColor(dart::Color::Gray());\n// Put the body into position\nEigen::Isometry3d new_tf = tf;\nnew_tf.translate(Eigen::Vector3d(0., 0., -floor_height / 2.0));\nbody->getParentJoint()->setTransformFromParentBodyNode(new_tf);\nauto floor_robot = std::make_shared<Robot>(floor_skel, floor_name);\nadd_robot(floor_robot);\nreturn floor_robot;\n}\nstd::shared_ptr<Robot> RobotDARTSimu::add_checkerboard_floor(double floor_width, double floor_height, double size, const Eigen::Isometry3d& tf, const std::string& floor_name, const Eigen::Vector4d& first_color, const Eigen::Vector4d& second_color)\n{\nROBOT_DART_ASSERT((_world->getSkeleton(floor_name) == nullptr), \"We cannot have 2 floors with the name '\" + floor_name + \"'\", nullptr);\nROBOT_DART_ASSERT((floor_width > 0. && floor_height > 0. && size > 0.), \"Floor dimensions should be bigger than zero!\", nullptr);\n// Add main floor skeleton\ndart::dynamics::SkeletonPtr main_floor_skel = dart::dynamics::Skeleton::create(floor_name + \"_main\");\n// Give the floor a body\ndart::dynamics::BodyNodePtr main_body = main_floor_skel->createJointAndBodyNodePair<dart::dynamics::WeldJoint>(nullptr).second;\n// Give the body a shape\nauto box = std::make_shared<dart::dynamics::BoxShape>(Eigen::Vector3d(floor_width, floor_width, floor_height));\n// No visual shape for this one; only collision and dynamics\nmain_body->createShapeNodeWith<dart::dynamics::CollisionAspect, dart::dynamics::DynamicsAspect>(box);\n// Put the body into position\nEigen::Isometry3d new_tf = tf;\nnew_tf.translate(Eigen::Vector3d(0., 0., -floor_height / 2.0));\nmain_body->getParentJoint()->setTransformFromParentBodyNode(new_tf);\n// Add visual bodies just for visualization\nint step = std::ceil(floor_width / size);\nint c = 0;\nfor (int i = 0; i < step; i++) {\nc = i;\nfor (int j = 0; j < step; j++) {\nEigen::Vector3d init_pose;\ninit_pose << -floor_width / 2. + size / 2 + i * size, -floor_width / 2. + size / 2 + j * size, 0.;\nint id = i * step + j;\ndart::dynamics::WeldJoint::Properties properties;\nproperties.mName = \"joint_\" + std::to_string(id);\ndart::dynamics::BodyNode::Properties bd_properties;\nbd_properties.mName = \"body_\" + std::to_string(id);\ndart::dynamics::BodyNodePtr body = main_body->createChildJointAndBodyNodePair<dart::dynamics::WeldJoint>(properties, bd_properties).second;\nauto box = std::make_shared<dart::dynamics::BoxShape>(Eigen::Vector3d(size, size, floor_height));\n// no collision/dynamics for these ones; only visual shape\nauto box_node = body->createShapeNodeWith<dart::dynamics::VisualAspect>(box);\nif (c % 2 == 0)\nbox_node->getVisualAspect()->setColor(second_color);\nelse\nbox_node->getVisualAspect()->setColor(first_color);\n// Put the body into position\nEigen::Isometry3d tf(Eigen::Isometry3d::Identity());\ntf.translation() = init_pose;\nbody->getParentJoint()->setTransformFromParentBodyNode(tf);\nc++;\n}\n}\nauto floor_robot = std::make_shared<Robot>(main_floor_skel, floor_name);\nadd_robot(floor_robot);\nreturn floor_robot;\n}\nvoid RobotDARTSimu::set_collision_detector(const std::string& collision_detector)\n{\nstd::string coll = collision_detector;\nfor (auto& c : coll)\nc = tolower(c);\nif (coll == \"dart\")\n_world->getConstraintSolver()->setCollisionDetector(dart::collision::DARTCollisionDetector::create());\nelse if (coll == \"fcl\")\n_world->getConstraintSolver()->setCollisionDetector(dart::collision::FCLCollisionDetector::create());\nelse if (coll == \"bullet\") {\n#if (HAVE_BULLET == 1)\n_world->getConstraintSolver()->setCollisionDetector(dart::collision::BulletCollisionDetector::create());\n#else\nROBOT_DART_WARNING(true, \"DART is not installed with Bullet! Cannot set BulletCollisionDetector!\");\n#endif\n}\nelse if (coll == \"ode\") {\n#if (HAVE_ODE == 1)\n_world->getConstraintSolver()->setCollisionDetector(dart::collision::OdeCollisionDetector::create());\n#else\nROBOT_DART_WARNING(true, \"DART is not installed with ODE! Cannot set OdeCollisionDetector!\");\n#endif\n}\n}\nconst std::string& RobotDARTSimu::collision_detector() const { return _world->getConstraintSolver()->getCollisionDetector()->getType(); }\nvoid RobotDARTSimu::set_collision_masks(size_t robot_index, uint32_t category_mask, uint32_t collision_mask)\n{\nROBOT_DART_ASSERT(robot_index < _robots.size(), \"Robot index out of bounds\", );\nauto coll_filter = std::static_pointer_cast<collision_filter::BitmaskContactFilter>(_world->getConstraintSolver()->getCollisionOption().collisionFilter);\ncoll_filter->add_to_map(_robots[robot_index]->skeleton(), collision_mask, category_mask);\n}\nvoid RobotDARTSimu::set_collision_masks(size_t robot_index, const std::string& body_name, uint32_t category_mask, uint32_t collision_mask)\n{\nROBOT_DART_ASSERT(robot_index < _robots.size(), \"Robot index out of bounds\", );\nauto bd = _robots[robot_index]->skeleton()->getBodyNode(body_name);\nROBOT_DART_ASSERT(bd != nullptr, \"BodyNode does not exist in skeleton!\", );\nauto coll_filter = std::static_pointer_cast<collision_filter::BitmaskContactFilter>(_world->getConstraintSolver()->getCollisionOption().collisionFilter);\nfor (auto& shape : bd->getShapeNodes())\ncoll_filter->add_to_map(shape, collision_mask, category_mask);\n}\nvoid RobotDARTSimu::set_collision_masks(size_t robot_index, size_t body_index, uint32_t category_mask, uint32_t collision_mask)\n{\nROBOT_DART_ASSERT(robot_index < _robots.size(), \"Robot index out of bounds\", );\nauto skel = _robots[robot_index]->skeleton();\nROBOT_DART_ASSERT(body_index < skel->getNumBodyNodes(), \"BodyNode index out of bounds\", );\nauto bd = skel->getBodyNode(body_index);\nauto coll_filter = std::static_pointer_cast<collision_filter::BitmaskContactFilter>(_world->getConstraintSolver()->getCollisionOption().collisionFilter);\nfor (auto& shape : bd->getShapeNodes())\ncoll_filter->add_to_map(shape, collision_mask, category_mask);\n}\nuint32_t RobotDARTSimu::collision_mask(size_t robot_index, const std::string& body_name)\n{\nROBOT_DART_ASSERT(robot_index < _robots.size(), \"Robot index out of bounds\", 0xffffffff);\nauto bd = _robots[robot_index]->skeleton()->getBodyNode(body_name);\nROBOT_DART_ASSERT(bd != nullptr, \"BodyNode does not exist in skeleton!\", 0xffffffff);\nauto coll_filter = std::static_pointer_cast<collision_filter::BitmaskContactFilter>(_world->getConstraintSolver()->getCollisionOption().collisionFilter);\nuint32_t mask = 0xffffffff;\nfor (auto& shape : bd->getShapeNodes())\nmask &= coll_filter->mask(shape).collision_mask;\nreturn mask;\n}\nuint32_t RobotDARTSimu::collision_mask(size_t robot_index, size_t body_index)\n{\nROBOT_DART_ASSERT(robot_index < _robots.size(), \"Robot index out of bounds\", 0xffffffff);\nauto skel = _robots[robot_index]->skeleton();\nROBOT_DART_ASSERT(body_index < skel->getNumBodyNodes(), \"BodyNode index out of bounds\", 0xffffffff);\nauto bd = skel->getBodyNode(body_index);\nauto coll_filter = std::static_pointer_cast<collision_filter::BitmaskContactFilter>(_world->getConstraintSolver()->getCollisionOption().collisionFilter);\nuint32_t mask = 0xffffffff;\nfor (auto& shape : bd->getShapeNodes())\nmask &= coll_filter->mask(shape).collision_mask;\nreturn mask;\n}\nuint32_t RobotDARTSimu::collision_category(size_t robot_index, const std::string& body_name)\n{\nROBOT_DART_ASSERT(robot_index < _robots.size(), \"Robot index out of bounds\", 0xffffffff);\nauto bd = _robots[robot_index]->skeleton()->getBodyNode(body_name);\nROBOT_DART_ASSERT(bd != nullptr, \"BodyNode does not exist in skeleton!\", 0xffffffff);\nauto coll_filter = std::static_pointer_cast<collision_filter::BitmaskContactFilter>(_world->getConstraintSolver()->getCollisionOption().collisionFilter);\nuint32_t mask = 0xffffffff;\nfor (auto& shape : bd->getShapeNodes())\nmask &= coll_filter->mask(shape).category_mask;\nreturn mask;\n}\nuint32_t RobotDARTSimu::collision_category(size_t robot_index, size_t body_index)\n{\nROBOT_DART_ASSERT(robot_index < _robots.size(), \"Robot index out of bounds\", 0xffffffff);\nauto skel = _robots[robot_index]->skeleton();\nROBOT_DART_ASSERT(body_index < skel->getNumBodyNodes(), \"BodyNode index out of bounds\", 0xffffffff);\nauto bd = skel->getBodyNode(body_index);\nauto coll_filter = std::static_pointer_cast<collision_filter::BitmaskContactFilter>(_world->getConstraintSolver()->getCollisionOption().collisionFilter);\nuint32_t mask = 0xffffffff;\nfor (auto& shape : bd->getShapeNodes())\nmask &= coll_filter->mask(shape).category_mask;\nreturn mask;\n}\nstd::pair<uint32_t, uint32_t> RobotDARTSimu::collision_masks(size_t robot_index, const std::string& body_name)\n{\nstd::pair<uint32_t, uint32_t> mask = {0xffffffff, 0xffffffff};\nROBOT_DART_ASSERT(robot_index < _robots.size(), \"Robot index out of bounds\", mask);\nauto bd = _robots[robot_index]->skeleton()->getBodyNode(body_name);\nROBOT_DART_ASSERT(bd != nullptr, \"BodyNode does not exist in skeleton!\", mask);\nauto coll_filter = std::static_pointer_cast<collision_filter::BitmaskContactFilter>(_world->getConstraintSolver()->getCollisionOption().collisionFilter);\nfor (auto& shape : bd->getShapeNodes()) {\nmask.first &= coll_filter->mask(shape).collision_mask;\nmask.second &= coll_filter->mask(shape).category_mask;\n}\nreturn mask;\n}\nstd::pair<uint32_t, uint32_t> RobotDARTSimu::collision_masks(size_t robot_index, size_t body_index)\n{\nstd::pair<uint32_t, uint32_t> mask = {0xffffffff, 0xffffffff};\nROBOT_DART_ASSERT(robot_index < _robots.size(), \"Robot index out of bounds\", mask);\nauto skel = _robots[robot_index]->skeleton();\nROBOT_DART_ASSERT(body_index < skel->getNumBodyNodes(), \"BodyNode index out of bounds\", mask);\nauto bd = skel->getBodyNode(body_index);\nauto coll_filter = std::static_pointer_cast<collision_filter::BitmaskContactFilter>(_world->getConstraintSolver()->getCollisionOption().collisionFilter);\nfor (auto& shape : bd->getShapeNodes()) {\nmask.first &= coll_filter->mask(shape).collision_mask;\nmask.second &= coll_filter->mask(shape).category_mask;\n}\nreturn mask;\n}\nvoid RobotDARTSimu::remove_collision_masks(size_t robot_index)\n{\nROBOT_DART_ASSERT(robot_index < _robots.size(), \"Robot index out of bounds\", );\nauto coll_filter = std::static_pointer_cast<collision_filter::BitmaskContactFilter>(_world->getConstraintSolver()->getCollisionOption().collisionFilter);\ncoll_filter->remove_from_map(_robots[robot_index]->skeleton());\n}\nvoid RobotDARTSimu::remove_collision_masks(size_t robot_index, const std::string& body_name)\n{\nROBOT_DART_ASSERT(robot_index < _robots.size(), \"Robot index out of bounds\", );\nauto bd = _robots[robot_index]->skeleton()->getBodyNode(body_name);\nROBOT_DART_ASSERT(bd != nullptr, \"BodyNode does not exist in skeleton!\", );\nauto coll_filter = std::static_pointer_cast<collision_filter::BitmaskContactFilter>(_world->getConstraintSolver()->getCollisionOption().collisionFilter);\nfor (auto& shape : bd->getShapeNodes())\ncoll_filter->remove_from_map(shape);\n}\nvoid RobotDARTSimu::remove_collision_masks(size_t robot_index, size_t body_index)\n{\nROBOT_DART_ASSERT(robot_index < _robots.size(), \"Robot index out of bounds\", );\nauto skel = _robots[robot_index]->skeleton();\nROBOT_DART_ASSERT(body_index < skel->getNumBodyNodes(), \"BodyNode index out of bounds\", );\nauto bd = skel->getBodyNode(body_index);\nauto coll_filter = std::static_pointer_cast<collision_filter::BitmaskContactFilter>(_world->getConstraintSolver()->getCollisionOption().collisionFilter);\nfor (auto& shape : bd->getShapeNodes())\ncoll_filter->remove_from_map(shape);\n}\nvoid RobotDARTSimu::remove_all_collision_masks()\n{\nauto coll_filter = std::static_pointer_cast<collision_filter::BitmaskContactFilter>(_world->getConstraintSolver()->getCollisionOption().collisionFilter);\ncoll_filter->clear_all();\n}\n} // namespace robot_dart\n
"},{"location":"api/robot__dart__simu_8hpp/","title":"File robot_dart_simu.hpp","text":"

FileList > robot_dart > robot_dart_simu.hpp

Go to the source code of this file

"},{"location":"api/robot__dart__simu_8hpp/#namespaces","title":"Namespaces","text":"Type Name namespace robot_dart namespace simu"},{"location":"api/robot__dart__simu_8hpp/#classes","title":"Classes","text":"Type Name class RobotDARTSimu struct TextData

The documentation for this class was generated from the following file robot_dart/robot_dart_simu.hpp

"},{"location":"api/robot__dart__simu_8hpp_source/","title":"File robot_dart_simu.hpp","text":"

File List > robot_dart > robot_dart_simu.hpp

Go to the documentation of this file

#ifndef ROBOT_DART_SIMU_HPP\n#define ROBOT_DART_SIMU_HPP\n#include <robot_dart/gui/base.hpp>\n#include <robot_dart/robot.hpp>\n#include <robot_dart/scheduler.hpp>\n#include <robot_dart/sensor/sensor.hpp>\nnamespace robot_dart {\nnamespace simu {\nstruct GUIData;\n// We use the Abode Source Sans Pro font: https://github.com/adobe-fonts/source-sans-pro\n// This font is licensed under SIL Open Font License 1.1: https://github.com/adobe-fonts/source-sans-pro/blob/release/LICENSE.md\nstruct TextData {\nstd::string text;\nEigen::Affine2d transformation;\nEigen::Vector4d color;\nstd::uint8_t alignment;\nbool draw_background;\nEigen::Vector4d background_color;\ndouble font_size = 28.;\n};\n} // namespace simu\nclass RobotDARTSimu {\npublic:\nusing robot_t = std::shared_ptr<Robot>;\nRobotDARTSimu(double timestep = 0.015);\n~RobotDARTSimu();\nvoid run(double max_duration = 5.0, bool reset_commands = false, bool force_position_bounds = true);\nbool step_world(bool reset_commands = false, bool force_position_bounds = true);\nbool step(bool reset_commands = false, bool force_position_bounds = true);\nScheduler& scheduler() { return _scheduler; }\nconst Scheduler& scheduler() const { return _scheduler; }\nbool schedule(int freq) { return _scheduler(freq); }\nint physics_freq() const { return _physics_freq; }\nint control_freq() const { return _control_freq; }\nvoid set_control_freq(int frequency)\n{\nROBOT_DART_EXCEPTION_INTERNAL_ASSERT(\nfrequency <= _physics_freq && \"Control frequency needs to be less than physics frequency\");\n_control_freq = frequency;\n}\nint graphics_freq() const { return _graphics_freq; }\nvoid set_graphics_freq(int frequency)\n{\nROBOT_DART_EXCEPTION_INTERNAL_ASSERT(\nfrequency <= _physics_freq && \"Graphics frequency needs to be less than physics frequency\");\n_graphics_freq = frequency;\n_graphics->set_fps(_graphics_freq);\n}\nstd::shared_ptr<gui::Base> graphics() const;\nvoid set_graphics(const std::shared_ptr<gui::Base>& graphics);\ndart::simulation::WorldPtr world();\ntemplate <typename T, typename... Args>\nstd::shared_ptr<T> add_sensor(Args&&... args)\n{\nadd_sensor(std::make_shared<T>(std::forward<Args>(args)...));\nreturn std::static_pointer_cast<T>(_sensors.back());\n}\nvoid add_sensor(const std::shared_ptr<sensor::Sensor>& sensor);\nstd::vector<std::shared_ptr<sensor::Sensor>> sensors() const;\nstd::shared_ptr<sensor::Sensor> sensor(size_t index) const;\nvoid remove_sensor(const std::shared_ptr<sensor::Sensor>& sensor);\nvoid remove_sensor(size_t index);\nvoid remove_sensors(const std::string& type);\nvoid clear_sensors();\ndouble timestep() const;\nvoid set_timestep(double timestep, bool update_control_freq = true);\nEigen::Vector3d gravity() const;\nvoid set_gravity(const Eigen::Vector3d& gravity);\nvoid stop_sim(bool disable = true);\nbool halted_sim() const;\nsize_t num_robots() const;\nconst std::vector<robot_t>& robots() const;\nrobot_t robot(size_t index) const;\nint robot_index(const robot_t& robot) const;\nvoid add_robot(const robot_t& robot);\nvoid add_visual_robot(const robot_t& robot);\nvoid remove_robot(const robot_t& robot);\nvoid remove_robot(size_t index);\nvoid clear_robots();\nsimu::GUIData* gui_data();\nvoid enable_text_panel(bool enable = true, double font_size = -1);\nstd::string text_panel_text() const;\nvoid set_text_panel(const std::string& str);\nvoid enable_status_bar(bool enable = true, double font_size = -1);\nstd::string status_bar_text() const;\nstd::shared_ptr<simu::TextData> add_text(const std::string& text, const Eigen::Affine2d& tf = Eigen::Affine2d::Identity(), Eigen::Vector4d color = Eigen::Vector4d(1, 1, 1, 1), std::uint8_t alignment = (1 | 3 << 3), bool draw_bg = false, Eigen::Vector4d bg_color = Eigen::Vector4d(0, 0, 0, 0.75), double font_size = 28);\nstd::shared_ptr<Robot> add_floor(double floor_width = 10.0, double floor_height = 0.1, const Eigen::Isometry3d& tf = Eigen::Isometry3d::Identity(), const std::string& floor_name = \"floor\");\nstd::shared_ptr<Robot> add_checkerboard_floor(double floor_width = 10.0, double floor_height = 0.1, double size = 1., const Eigen::Isometry3d& tf = Eigen::Isometry3d::Identity(), const std::string& floor_name = \"checkerboard_floor\", const Eigen::Vector4d& first_color = dart::Color::White(1.), const Eigen::Vector4d& second_color = dart::Color::Gray(1.));\nvoid set_collision_detector(const std::string& collision_detector); // collision_detector can be \"DART\", \"FCL\", \"Ode\" or \"Bullet\" (case does not matter)\nconst std::string& collision_detector() const;\n// Bitmask collision filtering\nvoid set_collision_masks(size_t robot_index, uint32_t category_mask, uint32_t collision_mask);\nvoid set_collision_masks(size_t robot_index, const std::string& body_name, uint32_t category_mask, uint32_t collision_mask);\nvoid set_collision_masks(size_t robot_index, size_t body_index, uint32_t category_mask, uint32_t collision_mask);\nuint32_t collision_mask(size_t robot_index, const std::string& body_name);\nuint32_t collision_mask(size_t robot_index, size_t body_index);\nuint32_t collision_category(size_t robot_index, const std::string& body_name);\nuint32_t collision_category(size_t robot_index, size_t body_index);\nstd::pair<uint32_t, uint32_t> collision_masks(size_t robot_index, const std::string& body_name);\nstd::pair<uint32_t, uint32_t> collision_masks(size_t robot_index, size_t body_index);\nvoid remove_collision_masks(size_t robot_index);\nvoid remove_collision_masks(size_t robot_index, const std::string& body_name);\nvoid remove_collision_masks(size_t robot_index, size_t body_index);\nvoid remove_all_collision_masks();\nprotected:\nvoid _enable(std::shared_ptr<simu::TextData>& text, bool enable, double font_size);\ndart::simulation::WorldPtr _world;\nsize_t _old_index;\nbool _break;\nstd::vector<std::shared_ptr<sensor::Sensor>> _sensors;\nstd::vector<robot_t> _robots;\nstd::shared_ptr<gui::Base> _graphics;\nstd::unique_ptr<simu::GUIData> _gui_data;\nstd::shared_ptr<simu::TextData> _text_panel = nullptr;\nstd::shared_ptr<simu::TextData> _status_bar = nullptr;\nScheduler _scheduler;\nint _physics_freq = -1, _control_freq = -1, _graphics_freq = 40;\n};\n} // namespace robot_dart\n#endif\n
"},{"location":"api/robot__pool_8cpp/","title":"File robot_pool.cpp","text":"

FileList > robot_dart > robot_pool.cpp

Go to the source code of this file

"},{"location":"api/robot__pool_8cpp/#namespaces","title":"Namespaces","text":"Type Name namespace robot_dart

The documentation for this class was generated from the following file robot_dart/robot_pool.cpp

"},{"location":"api/robot__pool_8cpp_source/","title":"File robot_pool.cpp","text":"

File List > robot_dart > robot_pool.cpp

Go to the documentation of this file

#include <robot_dart/robot_pool.hpp>\nnamespace robot_dart {\nRobotPool::RobotPool(const std::function<std::shared_ptr<Robot>()>& robot_creator, size_t pool_size, bool verbose) : _robot_creator(robot_creator), _pool_size(pool_size), _verbose(verbose)\n{\nif (_verbose) {\nstd::cout << \"Creating a pool of \" << pool_size << \" robots: \";\nstd::cout.flush();\n}\nfor (size_t i = 0; i < _pool_size; ++i) {\nif (_verbose) {\nstd::cout << \"[\" << i << \"]\";\nstd::cout.flush();\n}\nauto robot = robot_creator();\n_model_filename = robot->model_filename();\n_reset_robot(robot);\n_skeletons.push_back(robot->skeleton());\n}\nfor (size_t i = 0; i < _pool_size; i++)\n_free.push_back(true);\nif (_verbose)\nstd::cout << std::endl;\n}\nstd::shared_ptr<Robot> RobotPool::get_robot(const std::string& name)\n{\nwhile (true) {\nstd::lock_guard<std::mutex> lock(_skeleton_mutex);\nfor (size_t i = 0; i < _pool_size; i++)\nif (_free[i]) {\n_free[i] = false;\nreturn std::make_shared<Robot>(_skeletons[i], name);\n}\n}\n}\nvoid RobotPool::free_robot(const std::shared_ptr<Robot>& robot)\n{\nstd::lock_guard<std::mutex> lock(_skeleton_mutex);\nfor (size_t i = 0; i < _pool_size; i++) {\nif (_skeletons[i] == robot->skeleton()) {\n_reset_robot(robot);\n_free[i] = true;\nbreak;\n}\n}\n}\nvoid RobotPool::_reset_robot(const std::shared_ptr<Robot>& robot)\n{\nrobot->reset();\n}\n} // namespace robot_dart\n
"},{"location":"api/robot__pool_8hpp/","title":"File robot_pool.hpp","text":"

FileList > robot_dart > robot_pool.hpp

Go to the source code of this file

"},{"location":"api/robot__pool_8hpp/#namespaces","title":"Namespaces","text":"Type Name namespace robot_dart"},{"location":"api/robot__pool_8hpp/#classes","title":"Classes","text":"Type Name class RobotPool

The documentation for this class was generated from the following file robot_dart/robot_pool.hpp

"},{"location":"api/robot__pool_8hpp_source/","title":"File robot_pool.hpp","text":"

File List > robot_dart > robot_pool.hpp

Go to the documentation of this file

#ifndef ROBOT_DART_ROBOT_POOL\n#define ROBOT_DART_ROBOT_POOL\n#include <functional>\n#include <memory>\n#include <mutex>\n#include <vector>\n#include <robot_dart/robot.hpp>\nnamespace robot_dart {\nclass RobotPool {\npublic:\nusing robot_creator_t = std::function<std::shared_ptr<Robot>()>;\nRobotPool(const robot_creator_t& robot_creator, size_t pool_size = 32, bool verbose = true);\nvirtual ~RobotPool() {}\nRobotPool(const RobotPool&) = delete;\nvoid operator=(const RobotPool&) = delete;\nvirtual std::shared_ptr<Robot> get_robot(const std::string& name = \"robot\");\nvirtual void free_robot(const std::shared_ptr<Robot>& robot);\nconst std::string& model_filename() const { return _model_filename; }\nprotected:\nrobot_creator_t _robot_creator;\nsize_t _pool_size;\nbool _verbose;\nstd::vector<dart::dynamics::SkeletonPtr> _skeletons;\nstd::vector<bool> _free;\nstd::mutex _skeleton_mutex;\nstd::string _model_filename;\nvirtual void _reset_robot(const std::shared_ptr<Robot>& robot);\n};\n} // namespace robot_dart\n#endif\n
"},{"location":"api/scheduler_8cpp/","title":"File scheduler.cpp","text":"

FileList > robot_dart > scheduler.cpp

Go to the source code of this file

"},{"location":"api/scheduler_8cpp/#namespaces","title":"Namespaces","text":"Type Name namespace robot_dart

The documentation for this class was generated from the following file robot_dart/scheduler.cpp

"},{"location":"api/scheduler_8cpp_source/","title":"File scheduler.cpp","text":"

File List > robot_dart > scheduler.cpp

Go to the documentation of this file

#include <robot_dart/scheduler.hpp>\nnamespace robot_dart {\nbool Scheduler::schedule(int frequency)\n{\nif (_max_frequency == -1) {\n_start_time = clock_t::now();\n_last_iteration_time = _start_time;\n}\n_max_frequency = std::max(_max_frequency, frequency);\ndouble period = std::round((1. / frequency) / _dt);\nROBOT_DART_EXCEPTION_INTERNAL_ASSERT(\nperiod >= 1. && \"Time-step is too big for required frequency.\");\nif (_current_step % int(period) == 0)\nreturn true;\nreturn false;\n}\nvoid Scheduler::reset(double dt, bool sync, double current_time, double real_time)\n{\nROBOT_DART_EXCEPTION_INTERNAL_ASSERT(dt > 0. && \"Time-step needs to be bigger than zero.\");\n_current_time = 0.;\n_real_time = 0.;\n_simu_start_time = current_time;\n_real_start_time = real_time;\n_current_step = 0;\n_max_frequency = -1;\n_average_it_duration = 0.;\n_dt = dt;\n_sync = sync;\n}\ndouble Scheduler::step()\n{\n_current_time += _dt;\n_current_step += 1;\nauto end = clock_t::now();\n_it_duration = std::chrono::duration<double, std::micro>(end - _last_iteration_time).count();\n_last_iteration_time = end;\n_average_it_duration = _average_it_duration + (_it_duration - _average_it_duration) / _current_step;\nstd::chrono::duration<double, std::micro> real = end - _start_time;\nif (_sync) {\nauto expected = std::chrono::microseconds(int(_current_time * 1e6));\nstd::chrono::duration<double, std::micro> adjust = expected - real;\nif (adjust.count() > 0)\nstd::this_thread::sleep_for(adjust);\n}\n_real_time = real.count() * 1e-6;\nreturn _real_start_time + _real_time;\n}\n} // namespace robot_dart\n
"},{"location":"api/scheduler_8hpp/","title":"File scheduler.hpp","text":"

FileList > robot_dart > scheduler.hpp

Go to the source code of this file

"},{"location":"api/scheduler_8hpp/#namespaces","title":"Namespaces","text":"Type Name namespace robot_dart"},{"location":"api/scheduler_8hpp/#classes","title":"Classes","text":"Type Name class Scheduler

The documentation for this class was generated from the following file robot_dart/scheduler.hpp

"},{"location":"api/scheduler_8hpp_source/","title":"File scheduler.hpp","text":"

File List > robot_dart > scheduler.hpp

Go to the documentation of this file

#ifndef ROBOT_DART_SCHEDULER_HPP\n#define ROBOT_DART_SCHEDULER_HPP\n#include <robot_dart/utils.hpp>\n#include <chrono>\n#include <thread>\nnamespace robot_dart {\nclass Scheduler {\nprotected:\nusing clock_t = std::chrono::high_resolution_clock;\npublic:\nScheduler(double dt, bool sync = false) : _dt(dt), _sync(sync)\n{\nROBOT_DART_EXCEPTION_INTERNAL_ASSERT(_dt > 0. && \"Time-step needs to be bigger than zero.\");\n}\nbool operator()(int frequency) { return schedule(frequency); };\nbool schedule(int frequency);\ndouble step();\nvoid reset(double dt, bool sync = false, double current_time = 0., double real_time = 0.);\nvoid set_sync(bool enable) { _sync = enable; }\nbool sync() const { return _sync; }\ndouble current_time() const { return _simu_start_time + _current_time; }\ndouble next_time() const { return _simu_start_time + _current_time + _dt; }\ndouble real_time() const { return _real_start_time + _real_time; }\ndouble dt() const { return _dt; }\n// 0.8x => we are simulating at 80% of real time\ndouble real_time_factor() const { return _dt / it_duration(); }\n// time for a single iteration (wall-clock)\ndouble it_duration() const { return _average_it_duration * 1e-6; }\n// time of the last iteration (wall-clock)\ndouble last_it_duration() const { return _it_duration * 1e-6; }\nprotected:\ndouble _current_time = 0., _simu_start_time = 0., _real_time = 0., _real_start_time = 0., _it_duration = 0.;\ndouble _average_it_duration = 0.;\ndouble _dt;\nint _current_step = 0;\nbool _sync;\nint _max_frequency = -1;\nclock_t::time_point _start_time;\nclock_t::time_point _last_iteration_time;\n};\n} // namespace robot_dart\n#endif\n
"},{"location":"api/utils_8hpp/","title":"File utils.hpp","text":"

FileList > robot_dart > utils.hpp

Go to the source code of this file

"},{"location":"api/utils_8hpp/#namespaces","title":"Namespaces","text":"Type Name namespace robot_dart"},{"location":"api/utils_8hpp/#classes","title":"Classes","text":"Type Name class Assertion"},{"location":"api/utils_8hpp/#macros","title":"Macros","text":"Type Name define M_PIf static_cast<float>(M_PI) define ROBOT_DART_ASSERT (condition, message, returnValue) define ROBOT_DART_EXCEPTION_ASSERT (condition, message) define ROBOT_DART_EXCEPTION_INTERNAL_ASSERT (condition) define ROBOT_DART_INTERNAL_ASSERT (condition) define ROBOT_DART_SHOW_WARNINGS true define ROBOT_DART_UNUSED_VARIABLE (var) (void)(var) define ROBOT_DART_WARNING (condition, message)"},{"location":"api/utils_8hpp/#macro-definition-documentation","title":"Macro Definition Documentation","text":""},{"location":"api/utils_8hpp/#define-m_pif","title":"define M_PIf","text":"
#define M_PIf static_cast<float>(M_PI)\n
"},{"location":"api/utils_8hpp/#define-robot_dart_assert","title":"define ROBOT_DART_ASSERT","text":"
#define ROBOT_DART_ASSERT (\ncondition,\nmessage,\nreturnValue\n) do {                                                                                                             \\\n        if (!(condition)) {                                                                                          \\\n            std::cerr << __LINE__ << \" \" << __FILE__ << \" -> robot_dart assertion failed: \" << message << std::endl; \\\n            return returnValue;                                                                                      \\\n        }                                                                                                            \\\n    } while (false)\n
"},{"location":"api/utils_8hpp/#define-robot_dart_exception_assert","title":"define ROBOT_DART_EXCEPTION_ASSERT","text":"
#define ROBOT_DART_EXCEPTION_ASSERT (\ncondition,\nmessage\n) do {                                                \\\n        if (!(condition)) {                             \\\n            throw robot_dart::Assertion (message);       \\\n        }                                               \\\n    } while (false)\n
"},{"location":"api/utils_8hpp/#define-robot_dart_exception_internal_assert","title":"define ROBOT_DART_EXCEPTION_INTERNAL_ASSERT","text":"
#define ROBOT_DART_EXCEPTION_INTERNAL_ASSERT (\ncondition\n) do {                                                \\\n        if (!(condition)) {                             \\\n            throw robot_dart::Assertion (#condition);    \\\n        }                                               \\\n    } while (false)\n
"},{"location":"api/utils_8hpp/#define-robot_dart_internal_assert","title":"define ROBOT_DART_INTERNAL_ASSERT","text":"
#define ROBOT_DART_INTERNAL_ASSERT (\ncondition\n) do {                                                                                                                      \\\n        if (!(condition)) {                                                                                                   \\\n            std::cerr << \"Assertion '\" << #condition << \"' failed in '\" << __FILE__ << \"' on line \" << __LINE__ << std::endl; \\\n            std::abort();                                                                                                     \\\n        }                                                                                                                     \\\n    } while (false)\n
"},{"location":"api/utils_8hpp/#define-robot_dart_show_warnings","title":"define ROBOT_DART_SHOW_WARNINGS","text":"
#define ROBOT_DART_SHOW_WARNINGS true\n
"},{"location":"api/utils_8hpp/#define-robot_dart_unused_variable","title":"define ROBOT_DART_UNUSED_VARIABLE","text":"
#define ROBOT_DART_UNUSED_VARIABLE (\nvar\n) (void)(var)\n
"},{"location":"api/utils_8hpp/#define-robot_dart_warning","title":"define ROBOT_DART_WARNING","text":"
#define ROBOT_DART_WARNING (\ncondition,\nmessage\n) if (ROBOT_DART_SHOW_WARNINGS && (condition)) {                               \\\n        std::cerr << \"[robot_dart WARNING]: \\\"\" << message << \"\\\"\" << std::endl; \\\n    }\n

The documentation for this class was generated from the following file robot_dart/utils.hpp

"},{"location":"api/utils_8hpp_source/","title":"File utils.hpp","text":"

File List > robot_dart > utils.hpp

Go to the documentation of this file

#ifndef ROBOT_DART_UTILS_HPP\n#define ROBOT_DART_UTILS_HPP\n#include <exception>\n#include <iostream>\n#include <robot_dart/utils_headers_external.hpp>\n#ifndef ROBOT_DART_SHOW_WARNINGS\n#define ROBOT_DART_SHOW_WARNINGS true\n#endif\n#ifndef M_PIf\n#define M_PIf static_cast<float>(M_PI)\n#endif\nnamespace robot_dart {\ninline Eigen::VectorXd make_vector(std::initializer_list<double> args)\n{\nreturn Eigen::VectorXd::Map(args.begin(), args.size());\n}\ninline Eigen::Isometry3d make_tf(const Eigen::Matrix3d& R, const Eigen::Vector3d& t)\n{\nEigen::Isometry3d tf = Eigen::Isometry3d::Identity();\ntf.linear().matrix() = R;\ntf.translation() = t;\nreturn tf;\n}\ninline Eigen::Isometry3d make_tf(const Eigen::Matrix3d& R)\n{\nEigen::Isometry3d tf = Eigen::Isometry3d::Identity();\ntf.linear().matrix() = R;\nreturn tf;\n}\ninline Eigen::Isometry3d make_tf(const Eigen::Vector3d& t)\n{\nEigen::Isometry3d tf = Eigen::Isometry3d::Identity();\ntf.translation() = t;\nreturn tf;\n}\ninline Eigen::Isometry3d make_tf(std::initializer_list<double> args)\n{\nEigen::Isometry3d tf = Eigen::Isometry3d::Identity();\ntf.translation() = make_vector(args);\nreturn tf;\n}\nclass Assertion : public std::exception {\npublic:\nAssertion(const std::string& msg = \"\") : _msg(_make_message(msg)) {}\nconst char* what() const throw()\n{\nreturn _msg.c_str();\n}\nprivate:\nstd::string _msg;\nstd::string _make_message(const std::string& msg) const\n{\nstd::string message = \"robot_dart assertion failed\";\nif (msg != \"\")\nmessage += \": '\" + msg + \"'\";\nreturn message;\n}\n};\n} // namespace robot_dart\n#define ROBOT_DART_UNUSED_VARIABLE(var) (void)(var)\n#define ROBOT_DART_WARNING(condition, message)                                   \\\n    if (ROBOT_DART_SHOW_WARNINGS && (condition)) {                               \\\n        std::cerr << \"[robot_dart WARNING]: \\\"\" << message << \"\\\"\" << std::endl; \\\n    }\n#define ROBOT_DART_ASSERT(condition, message, returnValue)                                                           \\\n    do {                                                                                                             \\\n        if (!(condition)) {                                                                                          \\\n            std::cerr << __LINE__ << \" \" << __FILE__ << \" -> robot_dart assertion failed: \" << message << std::endl; \\\n            return returnValue;                                                                                      \\\n        }                                                                                                            \\\n    } while (false)\n#define ROBOT_DART_EXCEPTION_ASSERT(condition, message) \\\n    do {                                                \\\n        if (!(condition)) {                             \\\n            throw robot_dart::Assertion(message);       \\\n        }                                               \\\n    } while (false)\n#define ROBOT_DART_INTERNAL_ASSERT(condition)                                                                                 \\\n    do {                                                                                                                      \\\n        if (!(condition)) {                                                                                                   \\\n            std::cerr << \"Assertion '\" << #condition << \"' failed in '\" << __FILE__ << \"' on line \" << __LINE__ << std::endl; \\\n            std::abort();                                                                                                     \\\n        }                                                                                                                     \\\n    } while (false)\n#define ROBOT_DART_EXCEPTION_INTERNAL_ASSERT(condition) \\\n    do {                                                \\\n        if (!(condition)) {                             \\\n            throw robot_dart::Assertion(#condition);    \\\n        }                                               \\\n    } while (false)\n#endif\n
"},{"location":"api/utils__headers__dart__collision_8hpp/","title":"File utils_headers_dart_collision.hpp","text":"

FileList > robot_dart > utils_headers_dart_collision.hpp

Go to the source code of this file

The documentation for this class was generated from the following file robot_dart/utils_headers_dart_collision.hpp

"},{"location":"api/utils__headers__dart__collision_8hpp_source/","title":"File utils_headers_dart_collision.hpp","text":"

File List > robot_dart > utils_headers_dart_collision.hpp

Go to the documentation of this file

#ifndef ROBOT_DART_UTILS_HEADERS_DART_COLLISION_HPP\n#define ROBOT_DART_UTILS_HEADERS_DART_COLLISION_HPP\n#pragma GCC system_header\n#include <dart/config.hpp>\n#include <dart/collision/CollisionFilter.hpp>\n#include <dart/collision/CollisionObject.hpp>\n#include <dart/collision/dart/DARTCollisionDetector.hpp>\n#include <dart/collision/fcl/FCLCollisionDetector.hpp>\n#include <dart/constraint/ConstraintSolver.hpp>\n#if (HAVE_BULLET == 1)\n#include <dart/collision/bullet/BulletCollisionDetector.hpp>\n#endif\n#if (HAVE_ODE == 1)\n#include <dart/collision/ode/OdeCollisionDetector.hpp>\n#endif\n#endif\n
"},{"location":"api/utils__headers__dart__dynamics_8hpp/","title":"File utils_headers_dart_dynamics.hpp","text":"

FileList > robot_dart > utils_headers_dart_dynamics.hpp

Go to the source code of this file

The documentation for this class was generated from the following file robot_dart/utils_headers_dart_dynamics.hpp

"},{"location":"api/utils__headers__dart__dynamics_8hpp_source/","title":"File utils_headers_dart_dynamics.hpp","text":"

File List > robot_dart > utils_headers_dart_dynamics.hpp

Go to the documentation of this file

#ifndef ROBOT_DART_UTILS_HEADERS_DART_DYNAMICS_HPP\n#define ROBOT_DART_UTILS_HEADERS_DART_DYNAMICS_HPP\n#pragma GCC system_header\n#include <dart/dynamics/BallJoint.hpp>\n#include <dart/dynamics/BodyNode.hpp>\n#include <dart/dynamics/BoxShape.hpp>\n#include <dart/dynamics/DegreeOfFreedom.hpp>\n#include <dart/dynamics/EllipsoidShape.hpp>\n#include <dart/dynamics/EulerJoint.hpp>\n#include <dart/dynamics/FreeJoint.hpp>\n#include <dart/dynamics/MeshShape.hpp>\n#include <dart/dynamics/RevoluteJoint.hpp>\n#include <dart/dynamics/ShapeNode.hpp>\n#include <dart/dynamics/SoftBodyNode.hpp>\n#include <dart/dynamics/SoftMeshShape.hpp>\n#include <dart/dynamics/WeldJoint.hpp>\n#endif\n
"},{"location":"api/utils__headers__dart__io_8hpp/","title":"File utils_headers_dart_io.hpp","text":"

FileList > robot_dart > utils_headers_dart_io.hpp

Go to the source code of this file

"},{"location":"api/utils__headers__dart__io_8hpp/#namespaces","title":"Namespaces","text":"Type Name namespace dart

The documentation for this class was generated from the following file robot_dart/utils_headers_dart_io.hpp

"},{"location":"api/utils__headers__dart__io_8hpp_source/","title":"File utils_headers_dart_io.hpp","text":"

File List > robot_dart > utils_headers_dart_io.hpp

Go to the documentation of this file

#ifndef ROBOT_DART_UTILS_HEADERS_DART_IO_HPP\n#define ROBOT_DART_UTILS_HEADERS_DART_IO_HPP\n#pragma GCC system_header\n#include <dart/config.hpp>\n#if DART_VERSION_AT_LEAST(7, 0, 0)\n#include <dart/io/SkelParser.hpp>\n#include <dart/io/sdf/SdfParser.hpp>\n#include <dart/io/urdf/urdf.hpp>\n#else\n#include <dart/utils/SkelParser.hpp>\n#include <dart/utils/sdf/SdfParser.hpp>\n#include <dart/utils/urdf/urdf.hpp>\n// namespace alias for compatibility\nnamespace dart {\nnamespace io = utils;\n}\n#endif\n#endif\n
"},{"location":"api/utils__headers__external_8hpp/","title":"File utils_headers_external.hpp","text":"

FileList > robot_dart > utils_headers_external.hpp

Go to the source code of this file

The documentation for this class was generated from the following file robot_dart/utils_headers_external.hpp

"},{"location":"api/utils__headers__external_8hpp_source/","title":"File utils_headers_external.hpp","text":"

File List > robot_dart > utils_headers_external.hpp

Go to the documentation of this file

#ifndef ROBOT_DART_UTILS_HEADERS_EXTERNAL_HPP\n#define ROBOT_DART_UTILS_HEADERS_EXTERNAL_HPP\n#pragma GCC system_header\n#include <Eigen/Core>\n#include <Eigen/Geometry>\n#include <dart/config.hpp>\n#include <dart/dynamics/MeshShape.hpp>\n#include <dart/dynamics/Skeleton.hpp>\n#include <dart/simulation/World.hpp>\n#endif\n
"},{"location":"api/utils__headers__external__gui_8hpp/","title":"File utils_headers_external_gui.hpp","text":"

FileList > robot_dart > utils_headers_external_gui.hpp

Go to the source code of this file

The documentation for this class was generated from the following file robot_dart/utils_headers_external_gui.hpp

"},{"location":"api/utils__headers__external__gui_8hpp_source/","title":"File utils_headers_external_gui.hpp","text":"

File List > robot_dart > utils_headers_external_gui.hpp

Go to the documentation of this file

#ifndef ROBOT_DART_UTILS_HEADERS_EXTERNAL_GUI_HPP\n#define ROBOT_DART_UTILS_HEADERS_EXTERNAL_GUI_HPP\n#pragma GCC system_header\n#include <robot_dart/utils_headers_external.hpp>\n#include <Magnum/DartIntegration/World.h>\n#endif\n
"},{"location":"api/namespaces/","title":"Namespace List","text":"

Here is a list of all namespaces with brief descriptions:

"},{"location":"api/classes/","title":"Class Index","text":""},{"location":"api/classes/#a","title":"a","text":""},{"location":"api/classes/#b","title":"b","text":""},{"location":"api/classes/#c","title":"c","text":""},{"location":"api/classes/#d","title":"d","text":""},{"location":"api/classes/#f","title":"f","text":""},{"location":"api/classes/#g","title":"g","text":""},{"location":"api/classes/#h","title":"h","text":""},{"location":"api/classes/#i","title":"i","text":""},{"location":"api/classes/#l","title":"l","text":""},{"location":"api/classes/#m","title":"m","text":""},{"location":"api/classes/#o","title":"o","text":""},{"location":"api/classes/#p","title":"p","text":""},{"location":"api/classes/#r","title":"r","text":""},{"location":"api/classes/#s","title":"s","text":""},{"location":"api/classes/#t","title":"t","text":""},{"location":"api/classes/#u","title":"u","text":""},{"location":"api/classes/#v","title":"v","text":""},{"location":"api/classes/#w","title":"w","text":""},{"location":"api/hierarchy/","title":"Class Hierarchy","text":"

This inheritance list is sorted roughly, but not completely, alphabetically:

"},{"location":"api/modules/","title":"Modules","text":"

No modules found.

"},{"location":"api/pages/","title":"Related Pages","text":"

Here is a list of all related documentation pages:

"},{"location":"api/class_members/","title":"Class Members","text":""},{"location":"api/class_members/#a","title":"a","text":""},{"location":"api/class_members/#b","title":"b","text":""},{"location":"api/class_members/#c","title":"c","text":""},{"location":"api/class_members/#d","title":"d","text":""},{"location":"api/class_members/#e","title":"e","text":""},{"location":"api/class_members/#f","title":"f","text":""},{"location":"api/class_members/#g","title":"g","text":""},{"location":"api/class_members/#h","title":"h","text":""},{"location":"api/class_members/#i","title":"i","text":""},{"location":"api/class_members/#j","title":"j","text":""},{"location":"api/class_members/#k","title":"k","text":""},{"location":"api/class_members/#l","title":"l","text":""},{"location":"api/class_members/#m","title":"m","text":""},{"location":"api/class_members/#n","title":"n","text":""},{"location":"api/class_members/#o","title":"o","text":""},{"location":"api/class_members/#p","title":"p","text":""},{"location":"api/class_members/#r","title":"r","text":""},{"location":"api/class_members/#s","title":"s","text":""},{"location":"api/class_members/#t","title":"t","text":""},{"location":"api/class_members/#u","title":"u","text":""},{"location":"api/class_members/#v","title":"v","text":""},{"location":"api/class_members/#w","title":"w","text":""},{"location":"api/class_members/#_1","title":"~","text":""},{"location":"api/class_members/#_","title":"_","text":""},{"location":"api/class_member_functions/","title":"Class Member Functions","text":""},{"location":"api/class_member_functions/#a","title":"a","text":""},{"location":"api/class_member_functions/#b","title":"b","text":""},{"location":"api/class_member_functions/#c","title":"c","text":""},{"location":"api/class_member_functions/#d","title":"d","text":""},{"location":"api/class_member_functions/#e","title":"e","text":""},{"location":"api/class_member_functions/#f","title":"f","text":""},{"location":"api/class_member_functions/#g","title":"g","text":""},{"location":"api/class_member_functions/#h","title":"h","text":""},{"location":"api/class_member_functions/#i","title":"i","text":""},{"location":"api/class_member_functions/#j","title":"j","text":""},{"location":"api/class_member_functions/#k","title":"k","text":""},{"location":"api/class_member_functions/#l","title":"l","text":""},{"location":"api/class_member_functions/#m","title":"m","text":""},{"location":"api/class_member_functions/#n","title":"n","text":""},{"location":"api/class_member_functions/#o","title":"o","text":""},{"location":"api/class_member_functions/#p","title":"p","text":""},{"location":"api/class_member_functions/#r","title":"r","text":""},{"location":"api/class_member_functions/#s","title":"s","text":""},{"location":"api/class_member_functions/#t","title":"t","text":""},{"location":"api/class_member_functions/#u","title":"u","text":""},{"location":"api/class_member_functions/#v","title":"v","text":""},{"location":"api/class_member_functions/#w","title":"w","text":""},{"location":"api/class_member_functions/#_1","title":"~","text":""},{"location":"api/class_member_functions/#_","title":"_","text":""},{"location":"api/class_member_variables/","title":"Class Member Variables","text":""},{"location":"api/class_member_variables/#a","title":"a","text":""},{"location":"api/class_member_variables/#b","title":"b","text":""},{"location":"api/class_member_variables/#c","title":"c","text":""},{"location":"api/class_member_variables/#d","title":"d","text":""},{"location":"api/class_member_variables/#f","title":"f","text":""},{"location":"api/class_member_variables/#g","title":"g","text":""},{"location":"api/class_member_variables/#h","title":"h","text":""},{"location":"api/class_member_variables/#i","title":"i","text":""},{"location":"api/class_member_variables/#m","title":"m","text":""},{"location":"api/class_member_variables/#r","title":"r","text":""},{"location":"api/class_member_variables/#s","title":"s","text":""},{"location":"api/class_member_variables/#t","title":"t","text":""},{"location":"api/class_member_variables/#w","title":"w","text":""},{"location":"api/class_member_variables/#_","title":"_","text":""},{"location":"api/class_member_typedefs/","title":"Class Member Typedefs","text":""},{"location":"api/class_member_typedefs/#c","title":"c","text":""},{"location":"api/class_member_typedefs/#d","title":"d","text":""},{"location":"api/class_member_typedefs/#f","title":"f","text":""},{"location":"api/class_member_typedefs/#n","title":"n","text":""},{"location":"api/class_member_typedefs/#p","title":"p","text":""},{"location":"api/class_member_typedefs/#r","title":"r","text":""},{"location":"api/class_member_typedefs/#t","title":"t","text":""},{"location":"api/class_member_enums/","title":"Class Member Enums","text":""},{"location":"api/class_member_enums/#f","title":"f","text":""},{"location":"api/namespace_members/","title":"Namespace Members","text":""},{"location":"api/namespace_members/#a","title":"a","text":""},{"location":"api/namespace_members/#b","title":"b","text":""},{"location":"api/namespace_members/#c","title":"c","text":""},{"location":"api/namespace_members/#d","title":"d","text":""},{"location":"api/namespace_members/#m","title":"m","text":""},{"location":"api/namespace_members/#o","title":"o","text":""},{"location":"api/namespace_members/#p","title":"p","text":""},{"location":"api/namespace_members/#r","title":"r","text":""},{"location":"api/namespace_members/#s","title":"s","text":""},{"location":"api/namespace_members/#_1","title":"@","text":""},{"location":"api/namespace_member_functions/","title":"Namespace Member Functions","text":""},{"location":"api/namespace_member_functions/#a","title":"a","text":""},{"location":"api/namespace_member_functions/#c","title":"c","text":""},{"location":"api/namespace_member_functions/#d","title":"d","text":""},{"location":"api/namespace_member_functions/#m","title":"m","text":""},{"location":"api/namespace_member_functions/#p","title":"p","text":""},{"location":"api/namespace_member_functions/#r","title":"r","text":""},{"location":"api/namespace_member_functions/#s","title":"s","text":""},{"location":"api/namespace_member_variables/","title":"Namespace Member Variables","text":""},{"location":"api/namespace_member_variables/#b","title":"b","text":""},{"location":"api/namespace_member_typedefs/","title":"Namespace Member Typedefs","text":""},{"location":"api/namespace_member_typedefs/#c","title":"c","text":""},{"location":"api/namespace_member_typedefs/#o","title":"o","text":""},{"location":"api/namespace_member_typedefs/#s","title":"s","text":""},{"location":"api/namespace_member_enums/","title":"Namespace Member Enums","text":""},{"location":"api/namespace_member_enums/#_1","title":"@","text":""},{"location":"api/functions/","title":"Functions","text":""},{"location":"api/functions/#r","title":"r","text":""},{"location":"api/functions/#s","title":"s","text":""},{"location":"api/macros/","title":"Macros","text":""},{"location":"api/macros/#g","title":"g","text":""},{"location":"api/macros/#m","title":"m","text":""},{"location":"api/macros/#r","title":"r","text":""},{"location":"api/macros/#s","title":"s","text":""},{"location":"api/variables/","title":"Variables","text":""},{"location":"api/variables/#s","title":"s","text":""},{"location":"api/links/","title":"Links","text":""}]} \ No newline at end of file diff --git a/docs/sitemap.xml b/docs/sitemap.xml index f98fd24d..e82a1346 100644 --- a/docs/sitemap.xml +++ b/docs/sitemap.xml @@ -2,1477 +2,1477 @@ None - 2024-02-01 + 2024-02-02 daily None - 2024-02-01 + 2024-02-02 daily None - 2024-02-01 + 2024-02-02 daily None - 2024-02-01 + 2024-02-02 daily None - 2024-02-01 + 2024-02-02 daily None - 2024-02-01 + 2024-02-02 daily None - 2024-02-01 + 2024-02-02 daily None - 2024-02-01 + 2024-02-02 daily None - 2024-02-01 + 2024-02-02 daily None - 2024-02-01 + 2024-02-02 daily None - 2024-02-01 + 2024-02-02 daily None - 2024-02-01 + 2024-02-02 daily None - 2024-02-01 + 2024-02-02 daily None - 2024-02-01 + 2024-02-02 daily None - 2024-02-01 + 2024-02-02 daily None - 2024-02-01 + 2024-02-02 daily None - 2024-02-01 + 2024-02-02 daily None - 2024-02-01 + 2024-02-02 daily None - 2024-02-01 + 2024-02-02 daily None - 2024-02-01 + 2024-02-02 daily None - 2024-02-01 + 2024-02-02 daily None - 2024-02-01 + 2024-02-02 daily None - 2024-02-01 + 2024-02-02 daily None - 2024-02-01 + 2024-02-02 daily None - 2024-02-01 + 2024-02-02 daily None - 2024-02-01 + 2024-02-02 daily None - 2024-02-01 + 2024-02-02 daily None - 2024-02-01 + 2024-02-02 daily None - 2024-02-01 + 2024-02-02 daily None - 2024-02-01 + 2024-02-02 daily None - 2024-02-01 + 2024-02-02 daily None - 2024-02-01 + 2024-02-02 daily None - 2024-02-01 + 2024-02-02 daily None - 2024-02-01 + 2024-02-02 daily None - 2024-02-01 + 2024-02-02 daily None - 2024-02-01 + 2024-02-02 daily None - 2024-02-01 + 2024-02-02 daily None - 2024-02-01 + 2024-02-02 daily None - 2024-02-01 + 2024-02-02 daily None - 2024-02-01 + 2024-02-02 daily None - 2024-02-01 + 2024-02-02 daily None - 2024-02-01 + 2024-02-02 daily None - 2024-02-01 + 2024-02-02 daily None - 2024-02-01 + 2024-02-02 daily None - 2024-02-01 + 2024-02-02 daily None - 2024-02-01 + 2024-02-02 daily None - 2024-02-01 + 2024-02-02 daily None - 2024-02-01 + 2024-02-02 daily None - 2024-02-01 + 2024-02-02 daily None - 2024-02-01 + 2024-02-02 daily None - 2024-02-01 + 2024-02-02 daily None - 2024-02-01 + 2024-02-02 daily None - 2024-02-01 + 2024-02-02 daily None - 2024-02-01 + 2024-02-02 daily None - 2024-02-01 + 2024-02-02 daily None - 2024-02-01 + 2024-02-02 daily None - 2024-02-01 + 2024-02-02 daily None - 2024-02-01 + 2024-02-02 daily None - 2024-02-01 + 2024-02-02 daily None - 2024-02-01 + 2024-02-02 daily None - 2024-02-01 + 2024-02-02 daily None - 2024-02-01 + 2024-02-02 daily None - 2024-02-01 + 2024-02-02 daily None - 2024-02-01 + 2024-02-02 daily None - 2024-02-01 + 2024-02-02 daily None - 2024-02-01 + 2024-02-02 daily None - 2024-02-01 + 2024-02-02 daily None - 2024-02-01 + 2024-02-02 daily None - 2024-02-01 + 2024-02-02 daily None - 2024-02-01 + 2024-02-02 daily None - 2024-02-01 + 2024-02-02 daily None - 2024-02-01 + 2024-02-02 daily None - 2024-02-01 + 2024-02-02 daily None - 2024-02-01 + 2024-02-02 daily None - 2024-02-01 + 2024-02-02 daily None - 2024-02-01 + 2024-02-02 daily None - 2024-02-01 + 2024-02-02 daily None - 2024-02-01 + 2024-02-02 daily None - 2024-02-01 + 2024-02-02 daily None - 2024-02-01 + 2024-02-02 daily None - 2024-02-01 + 2024-02-02 daily None - 2024-02-01 + 2024-02-02 daily None - 2024-02-01 + 2024-02-02 daily None - 2024-02-01 + 2024-02-02 daily None - 2024-02-01 + 2024-02-02 daily None - 2024-02-01 + 2024-02-02 daily None - 2024-02-01 + 2024-02-02 daily None - 2024-02-01 + 2024-02-02 daily None - 2024-02-01 + 2024-02-02 daily None - 2024-02-01 + 2024-02-02 daily None - 2024-02-01 + 2024-02-02 daily None - 2024-02-01 + 2024-02-02 daily None - 2024-02-01 + 2024-02-02 daily None - 2024-02-01 + 2024-02-02 daily None - 2024-02-01 + 2024-02-02 daily None - 2024-02-01 + 2024-02-02 daily None - 2024-02-01 + 2024-02-02 daily None - 2024-02-01 + 2024-02-02 daily None - 2024-02-01 + 2024-02-02 daily None - 2024-02-01 + 2024-02-02 daily None - 2024-02-01 + 2024-02-02 daily None - 2024-02-01 + 2024-02-02 daily None - 2024-02-01 + 2024-02-02 daily None - 2024-02-01 + 2024-02-02 daily None - 2024-02-01 + 2024-02-02 daily None - 2024-02-01 + 2024-02-02 daily None - 2024-02-01 + 2024-02-02 daily None - 2024-02-01 + 2024-02-02 daily None - 2024-02-01 + 2024-02-02 daily None - 2024-02-01 + 2024-02-02 daily None - 2024-02-01 + 2024-02-02 daily None - 2024-02-01 + 2024-02-02 daily None - 2024-02-01 + 2024-02-02 daily None - 2024-02-01 + 2024-02-02 daily None - 2024-02-01 + 2024-02-02 daily None - 2024-02-01 + 2024-02-02 daily None - 2024-02-01 + 2024-02-02 daily None - 2024-02-01 + 2024-02-02 daily None - 2024-02-01 + 2024-02-02 daily None - 2024-02-01 + 2024-02-02 daily None - 2024-02-01 + 2024-02-02 daily None - 2024-02-01 + 2024-02-02 daily None - 2024-02-01 + 2024-02-02 daily None - 2024-02-01 + 2024-02-02 daily None - 2024-02-01 + 2024-02-02 daily None - 2024-02-01 + 2024-02-02 daily None - 2024-02-01 + 2024-02-02 daily None - 2024-02-01 + 2024-02-02 daily None - 2024-02-01 + 2024-02-02 daily None - 2024-02-01 + 2024-02-02 daily None - 2024-02-01 + 2024-02-02 daily None - 2024-02-01 + 2024-02-02 daily None - 2024-02-01 + 2024-02-02 daily None - 2024-02-01 + 2024-02-02 daily None - 2024-02-01 + 2024-02-02 daily None - 2024-02-01 + 2024-02-02 daily None - 2024-02-01 + 2024-02-02 daily None - 2024-02-01 + 2024-02-02 daily None - 2024-02-01 + 2024-02-02 daily None - 2024-02-01 + 2024-02-02 daily None - 2024-02-01 + 2024-02-02 daily None - 2024-02-01 + 2024-02-02 daily None - 2024-02-01 + 2024-02-02 daily None - 2024-02-01 + 2024-02-02 daily None - 2024-02-01 + 2024-02-02 daily None - 2024-02-01 + 2024-02-02 daily None - 2024-02-01 + 2024-02-02 daily None - 2024-02-01 + 2024-02-02 daily None - 2024-02-01 + 2024-02-02 daily None - 2024-02-01 + 2024-02-02 daily None - 2024-02-01 + 2024-02-02 daily None - 2024-02-01 + 2024-02-02 daily None - 2024-02-01 + 2024-02-02 daily None - 2024-02-01 + 2024-02-02 daily None - 2024-02-01 + 2024-02-02 daily None - 2024-02-01 + 2024-02-02 daily None - 2024-02-01 + 2024-02-02 daily None - 2024-02-01 + 2024-02-02 daily None - 2024-02-01 + 2024-02-02 daily None - 2024-02-01 + 2024-02-02 daily None - 2024-02-01 + 2024-02-02 daily None - 2024-02-01 + 2024-02-02 daily None - 2024-02-01 + 2024-02-02 daily None - 2024-02-01 + 2024-02-02 daily None - 2024-02-01 + 2024-02-02 daily None - 2024-02-01 + 2024-02-02 daily None - 2024-02-01 + 2024-02-02 daily None - 2024-02-01 + 2024-02-02 daily None - 2024-02-01 + 2024-02-02 daily None - 2024-02-01 + 2024-02-02 daily None - 2024-02-01 + 2024-02-02 daily None - 2024-02-01 + 2024-02-02 daily None - 2024-02-01 + 2024-02-02 daily None - 2024-02-01 + 2024-02-02 daily None - 2024-02-01 + 2024-02-02 daily None - 2024-02-01 + 2024-02-02 daily None - 2024-02-01 + 2024-02-02 daily None - 2024-02-01 + 2024-02-02 daily None - 2024-02-01 + 2024-02-02 daily None - 2024-02-01 + 2024-02-02 daily None - 2024-02-01 + 2024-02-02 daily None - 2024-02-01 + 2024-02-02 daily None - 2024-02-01 + 2024-02-02 daily None - 2024-02-01 + 2024-02-02 daily None - 2024-02-01 + 2024-02-02 daily None - 2024-02-01 + 2024-02-02 daily None - 2024-02-01 + 2024-02-02 daily None - 2024-02-01 + 2024-02-02 daily None - 2024-02-01 + 2024-02-02 daily None - 2024-02-01 + 2024-02-02 daily None - 2024-02-01 + 2024-02-02 daily None - 2024-02-01 + 2024-02-02 daily None - 2024-02-01 + 2024-02-02 daily None - 2024-02-01 + 2024-02-02 daily None - 2024-02-01 + 2024-02-02 daily None - 2024-02-01 + 2024-02-02 daily None - 2024-02-01 + 2024-02-02 daily None - 2024-02-01 + 2024-02-02 daily None - 2024-02-01 + 2024-02-02 daily None - 2024-02-01 + 2024-02-02 daily None - 2024-02-01 + 2024-02-02 daily None - 2024-02-01 + 2024-02-02 daily None - 2024-02-01 + 2024-02-02 daily None - 2024-02-01 + 2024-02-02 daily None - 2024-02-01 + 2024-02-02 daily None - 2024-02-01 + 2024-02-02 daily None - 2024-02-01 + 2024-02-02 daily None - 2024-02-01 + 2024-02-02 daily None - 2024-02-01 + 2024-02-02 daily None - 2024-02-01 + 2024-02-02 daily None - 2024-02-01 + 2024-02-02 daily None - 2024-02-01 + 2024-02-02 daily None - 2024-02-01 + 2024-02-02 daily None - 2024-02-01 + 2024-02-02 daily None - 2024-02-01 + 2024-02-02 daily None - 2024-02-01 + 2024-02-02 daily None - 2024-02-01 + 2024-02-02 daily None - 2024-02-01 + 2024-02-02 daily None - 2024-02-01 + 2024-02-02 daily None - 2024-02-01 + 2024-02-02 daily None - 2024-02-01 + 2024-02-02 daily None - 2024-02-01 + 2024-02-02 daily None - 2024-02-01 + 2024-02-02 daily None - 2024-02-01 + 2024-02-02 daily None - 2024-02-01 + 2024-02-02 daily None - 2024-02-01 + 2024-02-02 daily None - 2024-02-01 + 2024-02-02 daily None - 2024-02-01 + 2024-02-02 daily None - 2024-02-01 + 2024-02-02 daily None - 2024-02-01 + 2024-02-02 daily None - 2024-02-01 + 2024-02-02 daily None - 2024-02-01 + 2024-02-02 daily None - 2024-02-01 + 2024-02-02 daily None - 2024-02-01 + 2024-02-02 daily None - 2024-02-01 + 2024-02-02 daily None - 2024-02-01 + 2024-02-02 daily None - 2024-02-01 + 2024-02-02 daily None - 2024-02-01 + 2024-02-02 daily None - 2024-02-01 + 2024-02-02 daily None - 2024-02-01 + 2024-02-02 daily None - 2024-02-01 + 2024-02-02 daily None - 2024-02-01 + 2024-02-02 daily None - 2024-02-01 + 2024-02-02 daily None - 2024-02-01 + 2024-02-02 daily None - 2024-02-01 + 2024-02-02 daily None - 2024-02-01 + 2024-02-02 daily None - 2024-02-01 + 2024-02-02 daily None - 2024-02-01 + 2024-02-02 daily None - 2024-02-01 + 2024-02-02 daily None - 2024-02-01 + 2024-02-02 daily None - 2024-02-01 + 2024-02-02 daily None - 2024-02-01 + 2024-02-02 daily None - 2024-02-01 + 2024-02-02 daily None - 2024-02-01 + 2024-02-02 daily None - 2024-02-01 + 2024-02-02 daily None - 2024-02-01 + 2024-02-02 daily None - 2024-02-01 + 2024-02-02 daily None - 2024-02-01 + 2024-02-02 daily None - 2024-02-01 + 2024-02-02 daily None - 2024-02-01 + 2024-02-02 daily None - 2024-02-01 + 2024-02-02 daily None - 2024-02-01 + 2024-02-02 daily None - 2024-02-01 + 2024-02-02 daily None - 2024-02-01 + 2024-02-02 daily None - 2024-02-01 + 2024-02-02 daily None - 2024-02-01 + 2024-02-02 daily None - 2024-02-01 + 2024-02-02 daily None - 2024-02-01 + 2024-02-02 daily None - 2024-02-01 + 2024-02-02 daily None - 2024-02-01 + 2024-02-02 daily None - 2024-02-01 + 2024-02-02 daily None - 2024-02-01 + 2024-02-02 daily None - 2024-02-01 + 2024-02-02 daily None - 2024-02-01 + 2024-02-02 daily None - 2024-02-01 + 2024-02-02 daily None - 2024-02-01 + 2024-02-02 daily None - 2024-02-01 + 2024-02-02 daily None - 2024-02-01 + 2024-02-02 daily None - 2024-02-01 + 2024-02-02 daily None - 2024-02-01 + 2024-02-02 daily None - 2024-02-01 + 2024-02-02 daily None - 2024-02-01 + 2024-02-02 daily None - 2024-02-01 + 2024-02-02 daily None - 2024-02-01 + 2024-02-02 daily None - 2024-02-01 + 2024-02-02 daily None - 2024-02-01 + 2024-02-02 daily None - 2024-02-01 + 2024-02-02 daily None - 2024-02-01 + 2024-02-02 daily None - 2024-02-01 + 2024-02-02 daily None - 2024-02-01 + 2024-02-02 daily None - 2024-02-01 + 2024-02-02 daily None - 2024-02-01 + 2024-02-02 daily None - 2024-02-01 + 2024-02-02 daily None - 2024-02-01 + 2024-02-02 daily None - 2024-02-01 + 2024-02-02 daily \ No newline at end of file diff --git a/docs/sitemap.xml.gz b/docs/sitemap.xml.gz index b2a56acddbfea5587fa522718e6b992c7d89871f..8078ef728b7ef41e852f20937c9a8cdc9a14d935 100644 GIT binary patch delta 235 zcmVb&Jby^n#Vr3E+E|at6z<|G-HqenDTL$kn8jwS_vIlAe zm1#28DLjpLAJ?>OVp{ciR%P+?EWe$VPvV){!P?Mo_O&Th#2eb%V9x^|xJ zlGU%){jn)A>^T|o?y=F`zQ_MG&-Wis7Q1cu=2h*Pw!>=uXUldS`6Knr_1lcF@{=aZ z`SosBp32KuHGLs}YTd0o`BxV2+Df--h<)FjWT^ct`01>>S7znj%|G;8u_om8uD5lk n{;2Kj_$klXe)wU5g$&<7P(S`Zdam5I@fYhR1_P~%2@DJX+$^U_ diff --git a/src/docs/docs/index.md b/src/docs/docs/index.md index d96c7132..5a90b280 100644 --- a/src/docs/docs/index.md +++ b/src/docs/docs/index.md @@ -10,7 +10,7 @@ # RobotDART -RobotDART is a **C++11 robot simulator** (with optional Python bindings) built on top of the [DART] physics engine. The RobotDART simulator is **intended to be used by *Robotics and Machine Learning researchers*** who want to write controllers or test learning algorithms **without the delays and overhead** that usually comes with other simulators (e.g., [Gazebo], [Coppelia-sim]). +RobotDART is a **C++ robot simulator** (with optional Python bindings) built on top of the [DART] physics engine. The RobotDART simulator is **intended to be used by *Robotics and Machine Learning researchers*** who want to write controllers or test learning algorithms **without the delays and overhead** that usually comes with other simulators (e.g., [Gazebo], [Coppelia-sim]). For this reason, **the simulator runs headless by default**, and there is the possibility of *rendering the scene (e.g., through a camera sensor) without opening a graphics window*. All RobotDART's code is **thread-safe** (including *graphics and camera sensors*), and thus enables its users to **use their code in parallel jobs in multicore computers**.