From 51605885539be8770f3aeabb2f0fa9afa909a69c Mon Sep 17 00:00:00 2001 From: dtotsila Date: Wed, 7 Aug 2024 15:08:23 +0200 Subject: [PATCH 1/3] add magnum python bindings installation #210 --- src/docs/docs/install.md | 10 ++++++++++ 1 file changed, 10 insertions(+) diff --git a/src/docs/docs/install.md b/src/docs/docs/install.md index d9eac27e..4abfbd3f 100644 --- a/src/docs/docs/install.md +++ b/src/docs/docs/install.md @@ -93,6 +93,16 @@ mkdir build && cd build cmake -DCMAKE_BUILD_TYPE=Release -DWITH_DART=ON -DWITH_EIGEN=ON .. make -j sudo make install + +# Installation of Magnum Python Bindings (some examples use them but this is optional) +cd /path/to/tmp/folder +git clone https://github.com/mosra/magnum-bindings.git +cd magnum-bindings +mkdir build && cd build +cmake .. -DMAGNUM_WITH_PYTHON=ON +make -j +cd src/python +sudo python3 setup.py install ``` **For OSX you can also install Magnum via brew:** `brew install --HEAD mosra/magnum/corrade && brew install --HEAD mosra/magnum/magnum && brew install --HEAD mosra/magnum/magnum-plugins && brew install --HEAD mosra/magnum/magnum-integration --with-dartsim` From 673d56cb0d2a40f4800e4fe013d8f207b16e8e81 Mon Sep 17 00:00:00 2001 From: dtotsila Date: Wed, 7 Aug 2024 15:22:12 +0200 Subject: [PATCH 2/3] modify ubuntu install script for python bindings #210 needs testing --- scripts/install_ubuntu.sh | 14 +++++++++++++- 1 file changed, 13 insertions(+), 1 deletion(-) diff --git a/scripts/install_ubuntu.sh b/scripts/install_ubuntu.sh index 4714f752..fa247e5b 100755 --- a/scripts/install_ubuntu.sh +++ b/scripts/install_ubuntu.sh @@ -76,10 +76,22 @@ cmake -DCMAKE_BUILD_TYPE=Release -DCMAKE_INSTALL_PREFIX=/opt/magnum -DMAGNUM_WIT make -j sudo make install +cd ../.. +if [ ! -d "magnum-bindings" ] +then +git clone https://github.com/mosra/magnum-bindings.git +cd magnum-bindings +mkdir build && cd build +cmake .. -DMAGNUM_WITH_PYTHON=ON +make -j +cd src/python +sudo python3 setup.py install + + export PATH=/opt/magnum/bin:$PATH export LD_LIBRARY_PATH=/opt/magnum/lib:$LD_LIBRARY_PATH -cd ../../.. +cd ../../../../.. if [ $CLEAN -ne 0 ]; then rm -rf temp_robot_dart fi From 1691291d6b8c1e36da6aa5623b8fb79b1fef17ff Mon Sep 17 00:00:00 2001 From: Konstantinos Chatzilygeroudis Date: Mon, 26 Aug 2024 12:44:27 +0300 Subject: [PATCH 3/3] Add magnum bindings in OSX script as well --- docs/install/index.html | 10 ++++++++++ docs/search/search_index.json | 2 +- scripts/install_osx.sh | 11 +++++++++++ 3 files changed, 22 insertions(+), 1 deletion(-) diff --git a/docs/install/index.html b/docs/install/index.html index 956dd3b4..3da7b969 100644 --- a/docs/install/index.html +++ b/docs/install/index.html @@ -1458,6 +1458,16 @@

Installing Magnumcmake -DCMAKE_BUILD_TYPE=Release -DWITH_DART=ON -DWITH_EIGEN=ON .. make -j sudo make install + +# Installation of Magnum Python Bindings (some examples use them but this is optional) +cd /path/to/tmp/folder +git clone https://github.com/mosra/magnum-bindings.git +cd magnum-bindings +mkdir build && cd build +cmake .. -DMAGNUM_WITH_PYTHON=ON +make -j +cd src/python +sudo python3 setup.py install

For OSX you can also install Magnum via brew: brew install --HEAD mosra/magnum/corrade && brew install --HEAD mosra/magnum/magnum && brew install --HEAD mosra/magnum/magnum-plugins && brew install --HEAD mosra/magnum/magnum-integration --with-dartsim

Compilation and running the examples

diff --git a/docs/search/search_index.json b/docs/search/search_index.json index 58f83896..286937a7 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++ 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:

  • a physics engine (DART)
  • an optional graphics engine (Magnum)
  • a few sensor classes (IMU, force/torque sensors, cameras, etc.)
  • a curated URDF library
  • ... and a few useful features to make the life of roboticists/researchers easier

"},{"location":"#main-features","title":"Main Features","text":"
  • Modern C++ code that makes it easy to develop environments and applications
  • Fast and reliable simulation of robotic mechanisms and their interactions (through the DART physics engine)
  • A structured Robot class that enables a unified creation and access to all important values: in RobotDART you can load any robot description file (URDF, SDF, SKEL, and MuJoCo files) with the same command, and all robot measurements can be queried without using any DART code
  • A generic RobotControl class that enables fast prototyping of any type of controller
  • A generic Sensor class that allows the creation of any kind of sensor
  • A growing list of already implemented sensors, that includes 6-axis ForceTorque, IMU, RGB, and RGB-D sensors
  • A simulation class (RobotDARTSimu) that handles multiple robots and sensors, and allows for step-by-step simulation
  • A growing list of supported robots along with edited and optimized models to be used with RobotDART (see the robots page for details and examples):
    • PAL Talos humanoid
    • Franka Emika Panda
    • KUKA LBR Iiwa (14kg version)
    • IIT iCub humanoid (without hands)
    • Unitree A1 quadruped robot
    • Dynamixel-based 6-legged robot
    • A simple arm for educational purposes
    • and you can use any URDF
  • A custom graphical interface built on top of Magnum that allows generic customization
  • Support for windowless OpenGL context creation (even in parallel threads!) to allow for camera sensor usage even in parallel jobs running on clusters
  • Support for video recording in simulation time (i.e., not affected by delays of simulator and/or graphics) for visualization or debugging purposes
  • Full-featured Python bindings for fast prototyping
  • RobotDART runs on any Linux distribution and Mac OS
"},{"location":"#what-robotdart-is-not","title":"What RobotDART is not","text":"
  • RobotDART is primarily intended to be non-interactive (run a simulation, record/view the result),
  • Interaction is limited to changing the view and your own code. No GUI for adding objects or interactively build an environment,
  • RobotDART is not optimized for wheeled robots,
  • RobotDART is not optimized for simulating complex (e.g., mountain-like) terrains.
"},{"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.

  • We first include the appropriate files:
C++Python
#include <robot_dart/robot_dart_simu.hpp>\n\n#ifdef GRAPHIC\n#include <robot_dart/gui/magnum/graphics.hpp>\n#endif\n
import RobotDART as rd\n
  • We then load our hexapod robot:
C++Python
auto robot = std::make_shared<robot_dart::Robot>(\"pexod.urdf\");\n
robot = rd.Robot(\"pexod.urdf\");\n
  • We need to place it above the floor to avoid collision (we can use RobotDART's helpers ;)):
C++Python
robot->set_base_pose(robot_dart::make_tf({0., 0., 0.2}));\n
# pose is a 6D vector (first 3D orientation in angle-axis and last 3D translation)\nrobot.set_base_pose([0., 0., 0., 0., 0., 0.2])\n
  • We can now create the simulation object and add the robot and the floor:
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
  • If needed or wanted, we can add a graphics component to visualize the scene:
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
  • Once everything is configured, we can run our simulation for a few seconds:
C++Python
simu.run(10.);\n
simu.run(10.)\n
  • Here's how it looks:

"},{"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:

  • Install Magnum. See the installation page for details.
  • Create and set a graphics object in the simulation object. Here's an example:
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 (1) of what the main or any other camera \"sees\", you need to call the function record_video(path) of the graphics class:

  1. Make sure that you have ffmpeg installed on your system.
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\n    0.01f, // near plane\n    60.0f, // field of view\n    600, // width\n    400 // height\n);\n
camera.camera().set_camera_params(5., #far plane\n                                  0.01, #near plane\n                                  60.0, # field of view\n                                  600, # width\n                                  400) #height\n

You can find a complete example at cameras.cpp and cameras.py.

"},{"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\n// We can change the configuration for shadows\nconfiguration.shadowed = true;\nconfiguration.transparent_shadows = true;\nconfiguration.shadow_map_size = 1024;\n\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\n// Some extra configuration for the main camera\nconfiguration.draw_main_camera = true;\nconfiguration.draw_debug = true;\nconfiguration.draw_text = true;\n\n// We can also change the background color [default=black]\nconfiguration.bg_color = Eigen::Vector4d{1.0, 1.0, 1.0, 1.0};\n\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\n# We can change the configuration for shadows\nconfiguration.shadowed = True\nconfiguration.transparent_shadows = True\nconfiguration.shadow_map_size = 1024\n\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\n#  Some extra configuration for the main camera\nconfiguration.draw_main_camera = True\nconfiguration.draw_debug = True\nconfiguration.draw_text = True\n\n# We can also change the background color [default = black]\nconfiguration.bg_color = [1., 1., 1., 1.]\n\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\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\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\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\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);\n// add the controller to the robot, with a default weight of 1.0\nrobot->add_controller(controller1);\n
controller1 = rd.SimpleControl(ctrl)\n# add the controller to the robot, with a default weight of 1.0\nrobot.add_controller(controller1)\n

Robot control

C++Python
class MyController : public robot_dart::control::RobotControl {\npublic:\n    MyController() : robot_dart::control::RobotControl() {}\n\n    MyController(const Eigen::VectorXd& ctrl, bool full_control) : robot_dart::control::RobotControl(ctrl, full_control) {}\n    MyController(const Eigen::VectorXd& ctrl, const std::vector<std::string>& dof_names) : robot_dart::control::RobotControl(ctrl, dof_names) {}\n\n    void configure() override\n    {\n        _active = true;\n    }\n\n    Eigen::VectorXd calculate(double) override\n    {\n        auto robot = _robot.lock();\n        Eigen::VectorXd cmd = 100. * (_ctrl - robot->positions(_controllable_dofs));\n        return cmd;\n    }\n    std::shared_ptr<robot_dart::control::RobotControl> clone() const override\n    {\n        return std::make_shared<MyController>(*this);\n    }\n};\n
class MyController(rd.RobotControl):\n    def __init__(self, ctrl, full_control):\n        rd.RobotControl.__init__(self, ctrl, full_control)\n\n    def __init__(self, ctrl, controllable_dofs):\n        rd.RobotControl.__init__(self, ctrl, controllable_dofs)\n\n    def configure(self):\n        self._active = True\n\n    def calculate(self, t):\n        target = np.array([self._ctrl])\n        cmd = 100*(target-self.robot().positions(self._controllable_dofs))\n        return cmd[0]\n\n    # TO-DO: This is NOT working at the moment!\n    def clone(self):\n        return 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()) {\n    std::cout << \"Self collision is not enabled\" << std::endl;\n    // set self collisions to true and adjacent collisions to false\n    robot->set_self_collision(true, false);\n}\n
if(not robot.self_colliding()):\n    print(\"Self collision is not enabled\")\n    # set self collisions to true and adjacent collisions to false\n    robot.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\n// Get Joint Velocities\nauto joint_vels = robot->velocities();\n\n// Get Joint Accelerations\nauto joint_accs = robot->accelerations();\n\n// Get link_name(str) Transformation matrix with respect to the world frame.\nauto eef_tf = robot->body_pose(link_name);\n\n// Get translation vector from transformation matrix\nauto eef_pos = eef_tf.translation();\n\n// Get rotation matrix from tranformation matrix\nauto eef_rot = eef_tf.rotation();\n\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\n// Get link_name 6d velocity vector [angular, cartesian]\nauto eef_vel = robot->body_velocity(link_name);\n\n// Get link_name 6d acceleration vector [angular, cartesian]\nauto eef_acc = robot->body_acceleration(link_name);\n\n// Jacobian targeting the origin of link_name(str)\nauto jacobian = robot->jacobian(link_name);\n\n// Jacobian time derivative\nauto jacobian_deriv = robot->jacobian_deriv(link_name);\n\n// Center of Mass Jacobian\nauto com_jacobian = robot->com_jacobian();\n\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\n# Get Joint Velocities\njoint_vels = robot.velocities()\n\n# Get Joint Accelerations\njoint_accs = robot.accelerations()\n\n# Get link_name(str) Transformation matrix with respect to the world frame.\neef_tf = robot.body_pose(link_name)\n\n# Get translation vector from transformation matrix\neef_pos = eef_tf.translation()\n\n# Get rotation matrix from tranformation matrix\neef_rot = eef_tf.rotation()\n\n# Get link_name 6d pose vector [logmap(eef_tf.linear()), eef_tf.translation()]\neef_pose_vec = robot.body_pose_vec(link_name)\n\n# Get link_name 6d velocity vector [angular, cartesian]\neef_vel = robot.body_velocity(link_name)\n\n# Get link_name 6d acceleration vector [angular, cartesian]\neef_acc = robot.body_acceleration(link_name)\n\n# Jacobian targeting the origin of link_name(str)\njacobian = robot.jacobian(link_name)\n\n# Jacobian time derivative\njacobian_deriv = robot.jacobian_deriv(link_name)\n\n# Center of Mass Jacobian\ncom_jacobian = robot.com_jacobian()\n\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\n// Get link's mass\nauto eef_mass = robot->body_mass(link_name);\n\n// Mass Matrix of robot\nauto mass_matrix = robot->mass_matrix();\n\n// Inverse of Mass Matrix\nauto inv_mass_matrix = robot->inv_mass_matrix();\n\n// Augmented Mass matrix\nauto aug_mass_matrix = robot->aug_mass_matrix();\n\n// Inverse of Augmented Mass matrix\nauto inv_aug_mass_matrix = robot->inv_aug_mass_matrix();\n\n// Coriolis Force vector\nauto coriolis = robot->coriolis_forces();\n\n// Gravity Force vector\nauto gravity = robot->gravity_forces();\n\n// Combined vector of Coriolis Force and Gravity Force\nauto coriolis_gravity = robot->coriolis_gravity_forces();\n\n// Constraint Force Vector\nauto constraint_forces = robot->constraint_forces();\n
# Get Joint Forces\njoint_forces = robot.forces()\n\n# Get link's mass\neef_mass = robot.body_mass(link_name)\n\n# Mass Matrix of robot\nmass_matrix = robot.mass_matrix()\n\n# Inverse of Mass Matrix\ninv_mass_matrix = robot.inv_mass_matrix()\n\n# Augmented Mass matrix\naug_mass_matrix = robot.aug_mass_matrix()\n\n# Inverse of Augmented Mass matrix\ninv_aug_mass_matrix = robot.inv_aug_mass_matrix()\n\n# Coriolis Force vector\ncoriolis = robot.coriolis_forces()\n\n# Gravity Force vector\ngravity = robot.gravity_forces()\n\n# Combined vector of Coriolis Force and Gravity Force\ncoriolis_gravity = robot.coriolis_gravity_forces()\n\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\n// Modify Velocity Limits\n\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\n// Modify Force Limits\n\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\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\n# Modify Velocity Limits\nvel_upper_lims = np.array([1.5, 1.5, 1.5, 1.5, 1.5, 1.5, 1.5])\n\nrobot.set_velocity_upper_limits(vel_upper_lims, dof_names)\nrobot.set_velocity_lower_limits(-1*vel_upper_lims, dof_names)\n\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\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\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\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\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\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())\n    tq_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():\n    simu.add_sensor(rd.sensor.Torque(robot, joint, 1000))\n    tq_sensors[ct] = simu.sensors()[-1]\n    ct += 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)\n    torques_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:\n    torques_measure[ct] = tq_sens.torques()\n    ct += 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())\n    f_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():\n    simu.add_sensor(rd.sensor.ForceTorque(\n        robot, joint, 1000, \"parent_to_child\"))\n    f_tq_sensors[ct] = simu.sensors()[-1]\n    print(f_tq_sensors)\n    ct += 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) {\n    ft_torques_measure.block<1, 3>(ct, 0) = f_tq_sens->torque();\n    ft_forces_measure.block<1, 3>(ct, 0) = f_tq_sens->force();\n    ft_wrench_measure.block<1, 6>(ct, 0) = f_tq_sens->wrench();\n    ct++;\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:\n    ft_torques_measure[ct, :] = f_tq_sens.torque()\n    ft_forces_measure[ct, :] = f_tq_sens.force()\n    ft_wrench_measure[ct, :] = f_tq_sens.wrench()\n    ct += 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))),\n    imu_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():\n    simu.add_sensor(rd.sensor.IMU(\n        rd.sensor.IMUConfig(robot.body_node(body_node), 1000)))\n    imu_sensors[ct] = simu.sensors()[-1]\n    ct += 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) {\n    imu_angular_positions_measure.block<1, 3>(ct, 0) = imu_sens->angular_position_vec();\n    imu_angular_velocities_measure.block<1, 3>(ct, 0) = imu_sens->angular_velocity();\n    imu_linear_acceleration_measure.block<1, 3>(ct, 0) = imu_sens->linear_acceleration();\n    ct++;\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:\n    imu_angular_positions_measure[ct,:] = imu_sens.angular_position_vec()\n    imu_angular_velocities_measure[ct, :] = imu_sens.angular_velocity()\n    imu_linear_acceleration_measure[ct,:] = imu_sens.linear_acceleration()\n    ct += 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:

  • Minimize the overhead of loading robots (it happens only once!) or cloning robots (it never happens)
  • Make sure that your robots are \"clean\" once released from each thread
  • Focus on the important stuff rather than handling robots and threads

Let's see a more practical example:

  • First we need to include the proper header:
C++
#include <robot_dart/robot_pool.hpp>\n
  • Then we create a creator function and the pool object:
C++
namespace pool {\n    // This function should load one robot: here we load Talos\n    inline std::shared_ptr<robot_dart::Robot> robot_creator()\n    {\n        return std::make_shared<robot_dart::robots::Talos>();\n    }\n\n    // To create the object we need to pass the robot_creator function and the number of maximum parallel threads\n    robot_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.

  • Next, we create a few threads that utilize the robots (in your code you might be using OpenMP or TBB):
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)\n    threads[i] = std::thread(eval_robot, i); // eval_robot is the function that uses the robot\n
  • An example evaluation function:
C++
inline void eval_robot(int i)\n{\n    // We get one available robot\n    auto robot = pool::robot_pool.get_robot();\n    std::cout << \"Robot \" << i << \" got [\" << robot->skeleton() << \"]\" << std::endl;\n\n    /// --- some robot_dart code ---\n    simulate_robot(robot);\n    // --- do something with the result\n\n    std::cout << \"End of simulation \" << i << std::endl;\n\n    // CRITICAL : free your robot !\n    pool::robot_pool.free_robot(robot);\n\n    std::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>();\n\nstd::vector<std::thread> workers;\n\n// Set maximum number of parallel GL contexts (this is GPU-dependent)\nrobot_dart::gui::magnum::GlobalData::instance()->set_max_contexts(4);\n\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++) {\n    workers.push_back(std::thread([&] {\n        mutex.lock();\n        size_t index = id++;\n        mutex.unlock();\n\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\n        get_gl_context_with_sleep(gl_context, 20); // this call will sleep 20ms between each failed query\n\n        // Do the simulation\n        auto robot = global_robot->clone();\n\n        robot_dart::RobotDARTSimu simu(0.001);\n\n        Eigen::VectorXd ctrl = robot_dart::make_vector({0., M_PI / 3., 0., -M_PI / 4., 0., 0., 0.});\n\n        auto controller = std::make_shared<robot_dart::control::PDControl>(ctrl);\n        robot->add_controller(controller);\n        controller->set_pd(300., 50.);\n\n        // Magnum graphics\n        robot_dart::gui::magnum::GraphicsConfiguration configuration = robot_dart::gui::magnum::WindowlessGraphics::default_configuration();\n\n        configuration.width = 1024;\n        configuration.height = 768;\n        auto graphics = std::make_shared<robot_dart::gui::magnum::WindowlessGraphics>(configuration);\n        simu.set_graphics(graphics);\n        // Position the camera differently for each thread to visualize the difference\n        graphics->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\n\n        simu.add_robot(robot);\n        simu.run(6);\n\n        // Save the image for verification\n        robot_dart::gui::save_png_image(\"camera_\" + std::to_string(index) + \".png\",\n            graphics->image());\n\n        // Release the GL context for another thread to use\n        release_gl_context(gl_context);\n    }));\n}\n\n// Wait for all the workers\nfor (size_t i = 0; i < workers.size(); i++) {\n    workers[i].join();\n}\n
robot = rd.Robot(\"arm.urdf\", \"arm\", False)\nrobot.fix_to_world()\n\ndef test():\n    pid = os.getpid()\n    ii = pid%15\n\n    # create the controller\n    pdcontrol = rd.PDControl([0.0, 1.0, -1.5, 1.0], False)\n\n    # clone the robot\n    grobot = robot.clone()\n\n    # add the controller to the robot\n    grobot.add_controller(pdcontrol, 1.)\n    pdcontrol.set_pd(200., 20.)\n\n    # create the simulation object\n    simu = rd.RobotDARTSimu(0.001)\n\n    # set the graphics\n    graphics = rd.gui.WindowlessGraphics()\n    simu.set_graphics(graphics)\n\n    graphics.look_at([0.4 * ii, 3.5 - ii * 0.1, 2.], [0., 0., 0.25], [0., 0., 1.])\n\n    # add the robot and the floor\n    simu.add_robot(grobot)\n    simu.add_checkerboard_floor()\n\n    # run\n    simu.run(20.)\n\n    # save last frame for visualization purposes\n    img = graphics.image()\n    rd.gui.save_png_image('camera-' + str(ii) + '.png', img)\n\n# helper function to run in parallel\ndef runInParallel(N):\n  proc = []\n  for 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\n    p = Process(target=rd.gui.run_with_gl_context, args=(test, 20))\n    p.start()\n    proc.append(p)\n  for p in proc:\n    p.join()\n\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:

"},{"location":"faq/#prerequisites","title":"Prerequisites:","text":"
  • Ensure RobotDart and Magnum are installed.
  • If RobotDart and Magnum are not installed in standard locations, you can either:
  • Set the CMAKE_PREFIX_PATH environment variable:
    export CMAKE_PREFIX_PATH=/opt/robot_dart:/opt/magnum\n
  • Or, specify the paths directly when running cmake:
    cmake -DRobotDART_DIR=/opt/robot_dart -DMagnum_DIR=/opt/magnum ..\n
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)\n\nadd_executable(robot_dart_example example.cpp)\n\ntarget_link_libraries(robot_dart_example\n   RobotDART::Simu\n)\n\nif(RobotDART_Magnum_FOUND)\n  add_executable(robot_dart_example_graphics example.cpp)\n  target_link_libraries(robot_dart_example_graphics\n    RobotDART::Simu\n    RobotDART::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":"
  • Ubuntu (it should work on versions >= 14.04) or OSX
  • Eigen3
  • DART, http://dartsim.github.io/
"},{"location":"install/#optional","title":"Optional","text":"
  • Boost (for unit tests)
  • Magnum (for graphics), https://github.com/mosra/magnum
  • ffmpeg (for video recording) - please install using your favorite package manager
"},{"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

For OSX you can also install Magnum via brew: brew install --HEAD mosra/magnum/corrade && brew install --HEAD mosra/magnum/magnum && brew install --HEAD mosra/magnum/magnum-plugins && brew install --HEAD mosra/magnum/magnum-integration --with-dartsim

"},{"location":"install/#compilation-and-running-the-examples","title":"Compilation and running the examples","text":"

The compilation of the library is straight-forward:

  • retrieve the code, for instance with git clone https://github.com/resibots/robot_dart.git
  • cd /path/to/repo/root
  • ./waf configure
  • ./waf

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:

  • ./waf install

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:

  • ./waf configure --prefix=/path/to/install/dir --shared
  • ./waf install

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:

  • retrieve the code, for instance with git clone https://github.com/resibots/robot_dart.git
  • cd /path/to/repo/root
  • ./waf configure --python (--python enables the python bindings)
  • ./waf
  • Install the library (including the python bindings) as before (no change is needed)
  • Depending on your installation directory you might need to update your PYTHONPATH, e.g. export PYTHONPATH=$PYTHONPATH:/usr/local/lib/python3.10/site-packages/

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

  • cd /path/to/repo/root
  • python src/python/example.py or python src/python/example_parallel.py
"},{"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":"pubs/","title":"Publications using RobotDART","text":""},{"location":"pubs/#scientific-publications-indicative-list-ordered-by-date","title":"Scientific Publications (indicative list, ordered by date)","text":""},{"location":"pubs/#scientific-publications-indicative-list-ordered-by-date_1","title":"Scientific Publications (indicative list, ordered by date)","text":"
  1. Anne, T. and Mouret, J.B., 2024. Parametric-Task MAP-Elites. Proceedings of the Genetic and Evolutionary Computation Conference (GECCO). (pdf)

  2. Ivaldi, S. and Ghini, E., 2023, June. Teleoperating a robot for removing asbestos tiles on roofs: insights from a pilot study. In 2023 IEEE International Conference on Advanced Robotics and Its Social Impacts (ARSO) (pp. 128-133). IEEE. (pdf)

  3. Khadivar, F., Chatzilygeroudis, K. and Billard, A., 2023. Self-correcting quadratic programming-based robot control. IEEE Transactions on Systems, Man, and Cybernetics: Systems. (pdf)

  4. Souza, A.O., Grenier, J., Charpillet, F., Maurice, P. and Ivaldi, S., 2023, June. Towards data-driven predictive control of active upper-body exoskeletons for load carrying. In 2023 IEEE International Conference on Advanced Robotics and Its Social Impacts (ARSO) (pp. 59-64). IEEE. (pdf)

  5. Chatzilygeroudis, K.I., Tsakonas, C.G. and Vrahatis, M.N., 2023, July. Evolving Dynamic Locomotion Policies in Minutes. In 2023 14th International Conference on Information, Intelligence, Systems & Applications (IISA) (pp. 1-8). IEEE. (pdf)

  6. Tsakonas, C.G. and Chatzilygeroudis, K.I., 2023, July. Effective Skill Learning via Autonomous Goal Representation Learning. In 2023 14th International Conference on Information, Intelligence, Systems & Applications (IISA) (pp. 1-8). IEEE. (pdf)

  7. Totsila, D., Chatzilygeroudis, K., Hadjivelichkov, D., Modugno, V., Hatzilygeroudis, I. and Kanoulas, D., 2023. End-to-End Stable Imitation Learning via Autonomous Neural Dynamic Policies. Life-Long Learning with Human Help (L3H2) Workshop, ICRA. (pdf)

  8. Allard, M., Smith, S.C., Chatzilygeroudis, K., Lim, B. and Cully, A., 2023. Online damage recovery for physical robots with hierarchical quality-diversity. ACM Transactions on Evolutionary Learning, 3(2), pp.1-23. (pdf)

  9. Anne, T., Dalin, E., Bergonzani, I., Ivaldi, S. and Mouret, J.B., 2022. First do not fall: learning to exploit a wall with a damaged humanoid robot. IEEE Robotics and Automation Letters, 7(4), pp.9028-9035. (pdf)

  10. Mayr, M., Ahmad, F., Chatzilygeroudis, K., Nardi, L. and Krueger, V., 2022, December. Skill-based multi-objective reinforcement learning of industrial robot tasks with planning and knowledge integration. In 2022 IEEE International Conference on Robotics and Biomimetics (ROBIO) (pp. 1995-2002). IEEE. (pdf)

  11. Grillotti, L. and Cully, A., 2022. Unsupervised behavior discovery with quality-diversity optimization. IEEE Transactions on Evolutionary Computation, 26(6), pp.1539-1552. (pdf)

  12. Lim, B., Grillotti, L., Bernasconi, L. and Cully, A., 2022, May. Dynamics-aware quality-diversity for efficient learning of skill repertoires. In 2022 International Conference on Robotics and Automation (ICRA) (pp. 5360-5366). IEEE. (pdf)

  13. Tsinganos, K., Chatzilygeroudis, K., Hadjivelichkov, D., Komninos, T., Dermatas, E. and Kanoulas, D., 2022. Behavior policy learning: Learning multi-stage tasks via solution sketches and model-based controllers. Frontiers in Robotics and AI, 9, p.974537. (pdf)

  14. d'Elia, E., Mouret, J.B., Kober, J. and Ivaldi, S., 2022, October. Automatic tuning and selection of whole-body controllers. In 2022 IEEE/RSJ International Conference on Intelligent Robots and Systems (IROS) (pp. 12935-12941). IEEE. (pdf)

  15. Mayr, M., Hvarfner, C., Chatzilygeroudis, K., Nardi, L. and Krueger, V., 2022, August. Learning skill-based industrial robot tasks with user priors. In 2022 IEEE 18th International Conference on Automation Science and Engineering (CASE) (pp. 1485-1492). IEEE. (pdf)

  16. Allard, M., Smith, S.C., Chatzilygeroudis, K. and Cully, A., 2022, July. Hierarchical quality-diversity for online damage recovery. In Proceedings of the Genetic and Evolutionary Computation Conference (pp. 58-67). (pdf)

  17. Mayr, M., Ahmad, F., Chatzilygeroudis, K., Nardi, L. and Krueger, V., 2022. Combining planning, reasoning and reinforcement learning to solve industrial robot tasks. 2nd Workshop on Trends and Advances in Machine Learning and Automated Reasoning for Intelligent Robots and Systems, IROS. (pdf)

  18. Cully, A., 2021, June. Multi-emitter map-elites: improving quality, diversity and data efficiency with heterogeneous sets of emitters. In Proceedings of the Genetic and Evolutionary Computation Conference (pp. 84-92). (pdf)

  19. Mayr, M., Chatzilygeroudis, K., Ahmad, F., Nardi, L. and Krueger, V., 2021, September. Learning of parameters in behavior trees for movement skills. In 2021 IEEE/RSJ International Conference on Intelligent Robots and Systems (IROS) (pp. 7572-7579). IEEE. (pdf)

  20. Penco, L., Hoffman, E.M., Modugno, V., Gomes, W., Mouret, J.B. and Ivaldi, S., 2020. Learning robust task priorities and gains for control of redundant robots. IEEE Robotics and Automation Letters, 5(2), pp.2626-2633. (pdf)

  21. Flageat, M. and Cully, A., 2020, July. Fast and stable MAP-Elites in noisy domains using deep grids. In Artificial Life Conference Proceedings 32 (pp. 273-282). One Rogers Street, Cambridge, MA 02142-1209, USA journals-info@ mit. edu: MIT Press. (pdf)

  22. Paul, S., Chatzilygeroudis, K., Ciosek, K., Mouret, J.B., Osborne, M.A. and Whiteson, S., 2020. Robust reinforcement learning with Bayesian optimisation and quadrature. Journal of Machine Learning Research, 21(151), pp.1-31. (pdf)

  23. Chatzilygeroudis, K., Vassiliades, V. and Mouret, J.B., 2018. Reset-free trial-and-error learning for robot damage recovery. Robotics and Autonomous Systems, 100, pp.236-250. (pdf)

  24. Pautrat, R., Chatzilygeroudis, K. and Mouret, J.B., 2018, May. Bayesian optimization with automatic prior selection for data-efficient direct policy search. In 2018 IEEE International Conference on Robotics and Automation (ICRA) (pp. 7571-7578). IEEE. (pdf)

  25. Chatzilygeroudis, K. and Mouret, J.B., 2018, May. Using parameterized black-box priors to scale up model-based policy search for robotics. In 2018 IEEE international conference on robotics and automation (ICRA) (pp. 5121-5128). IEEE. (pdf)

  26. Paul, S., Chatzilygeroudis, K., Ciosek, K., Mouret, J.B., Osborne, M. and Whiteson, S., 2018, April. Alternating optimisation and quadrature for robust control. In Proceedings of the AAAI Conference on Artificial Intelligence (Vol. 32, No. 1). (pdf)

  27. Kaushik, R., Chatzilygeroudis, K. and Mouret, J.B., 2018, October. Multi-objective model-based policy search for data-efficient learning with sparse rewards. In Conference on Robot Learning (pp. 839-855). PMLR. (pdf)

  28. Vassiliades, V., Chatzilygeroudis, K. and Mouret, J.B., 2017. Using centroidal voronoi tessellations to scale up the multidimensional archive of phenotypic elites algorithm. IEEE Transactions on Evolutionary Computation, 22(4), pp.623-630. (pdf)

  29. Mouret, J.B. and Chatzilygeroudis, K., 2017, July. 20 years of reality gap: a few thoughts about simulators in evolutionary robotics. In Proceedings of the genetic and evolutionary computation conference companion (pp. 1121-1124). (pdf)

  30. Papaspyros, V., Chatzilygeroudis, K., Vassiliades, V. and Mouret, J.B., 2016. Safety-aware robot damage recovery using constrained bayesian optimization and simulated priors. BayesOpt '16: Proceedings of the International Workshop \"Bayesian Optimization: Black-box Optimization and Beyond\", NeurIPS. (pdf)

  31. Chatzilygeroudis, K., Cully, A. and Mouret, J.B., 2016. Towards semi-episodic learning for robot damage recovery. AILTA '16: Proceedings of the International Workshop \"AI for Long-term Autonomy\", ICRA. (pdf)

"},{"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/#video-recording-to-file","title":"Video recording to file","text":"

ffmpeg is needed for enabling the video recording capabilities. You can install this at any time using your favorite package manager (e.g. apt for Ubuntu or brew for Mac OSX).

"},{"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:

  • git clone https://github.com/resibots/robot_dart.git
  • cd robot_dart
  • ./scripts/install_ubuntu.sh

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 CMAKE_PREFIX_PATH=/opt/robot_dart:/opt/magnum\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":"

To quickly install RobotDART on Mac OSX, we just need to run ./scripts/install_osx.sh from the root of the repo. In more detail:

  • git clone https://github.com/resibots/robot_dart.git
  • cd robot_dart
  • ./scripts/install_osx.sh

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 CMAKE_PREFIX_PATH=/opt/robot_dart:/opt/magnum\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
  1. You can run python --version to see your version. We only keep the major.minor (ignoring the patch version)\u00a0\u21a9\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()):

  • First check in the current directory
  • If not found, check in current_directory/utheque
  • If not found, check in $ROBOT_DART_PATH/utheque
  • If not found, check in the robot dart installation path/robots (e.g., /usr/share/utheque or $HOME/share/utheque)
  • Otherwise, report failure

utheque is a separate header-only library that gets installed together with RobotDART (or even alone), that can be used in libraries that do not want to interfere with RobotDART and use the curated URDF files.

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

Talos is a humanoid robot made by PAL Robotics.

  • Datasheet: [pdf]
  • 32 degrees of freedom (6 for each leg, 7 for each arm, 2 for the waist, 2 for the neck, 1 for each gripper)
  • 175 cm / 95 kg
  • IMU in the torso
  • Torque sensors in all joints except head, wrist and gripper (22 torque sensors total)
  • 1 force/torque sensor in each ankle
  • 1 force/torque sensor in each wrist

We have two URDF files:

  • utheque/talos/talos.urdf :
    • accurate (simplified but made of polygons) collision meshes
    • mimic joints for the gripper
    • Not compatible the DART collision detector (you need to use FCL collision detector - shipped with DART)
    • URDF: [talos.urdf]
    • Example: [talos.cpp] [talos.py]

Load Talos

C++
auto robot = std::make_shared<robot_dart::robots::Talos>();\n
Python
robot = rd.Talos()\n
  • utheque/talos/talos_fast.urdf:
    • no collision except for the feet, which are approximated by boxes
    • grippers are fixed (no movement is allowed)
    • compatible with the DART collision detector
    • URDF: [talos_fast.urdf]
    • Example: [talos_fast.cpp]

talos_fast.urdf is faster because it makes it possible to use the DART collision detector (and has much collision shapes). You should prefer it except if you want to use the grippers (e.g., for manipulation) or are working on self-collisions.

  • utheque/talos/talos_fast_collision.urdf:
    • all bodies are approximated by boxes
    • grippers are fixed (no movement is allowed)
    • compatible with the DART collision detector
    • URDF: [talos_fast_collision.urdf]
    • Example: [talos_fast_collision.cpp] [talos_fast_collision.py]

talos_fast_collision.urdf is faster than talos.urdf but slower than talos_fast.urdf. You should use it when you need more detail collisions but faster simulation times.

Load Talos Fast

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.

  • Datasheet: [pdf]
  • 7 degrees of freedom
  • Can be controlled in torque
  • 18 kg
  • workspace: 855 mm (horizontal), 1190 mm (vertical)
  • URDF: [franka.urdf]
  • Example: [franka.cpp] [franka.py] The URDF includes the gripper.

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.

  • Datasheet: [pdf]
  • We implement the 14 kg version
  • 29.5 kg
  • 7 degrees of freedom
  • URDF: [iiwa.urdf]
  • Example: [iiwa.cpp] [iiwa.py]

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.

  • Datasheet (rev 2.3) [pdf]
  • 6 force/torque sensors (upper arms, upper legs, ankles)
  • IMU in the head
  • We do to simulate the skin
  • We do not simulate the hands
  • Our model is close to the Inria's iCub, but it has not been checked in detail.
  • URDF: [icub.urdf]
  • Example [icub.cpp] [icub.py]

Please note that the mesh files (.glb) require assimp 5.x (and not assimp4.x usually shipped with ROS). If you cannot load the URDF, please check your assimp version.

Load iCub

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

  • IMU in the torso
  • We do not simulate the foot pressure sensors (yet)
  • One can easily add a depth camera on the head
  • URDF: [a1.urdf]
  • Example [a1.cpp] [a1.py]

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

  • 6 legs, 3 degrees of freedom for each leg (18 degrees of freedom)
  • simple URDF (no meshes)
  • URDF: [pexod.urdf]
  • Example: [hexapod.cpp] [hexapod.py]

Load 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":"
  • A simple arm for educational or debugging purposes
  • 5 degrees of freedom
  • simple URDF (no meshes)
  • URDF: [arm.urdf]
  • Example: [arm.cpp] [arm.py]

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');\n    auto 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\")]\n    your_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:

  • namespace Magnum
    • namespace GL
    • namespace Platform
    • namespace SceneGraph
    • namespace Shaders
      • namespace Implementation
  • namespace TinyProcessLib
  • namespace dart
    • namespace collision
    • namespace dynamics
  • namespace robot_dart
    • class Assertion
    • class Robot
    • class RobotDARTSimu
    • class RobotPool
    • class Scheduler
    • namespace collision_filter
      • class BitmaskContactFilter
        • struct Masks
    • namespace control
      • class PDControl
      • class PolicyControl
      • class RobotControl
      • class SimpleControl
    • namespace detail
    • namespace gui
      • class Base
      • struct DepthImage
      • struct GrayscaleImage
      • struct Image
      • namespace magnum
        • class BaseApplication
        • class BaseGraphics
        • 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
        • namespace gs
          • class Camera
          • class CubeMap
          • class CubeMapColor
          • class Light
          • class Material
          • class PhongMultiLight
          • class ShadowMap
          • class ShadowMapColor
        • namespace sensor
          • class Camera
    • namespace robots
      • 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
    • namespace sensor
      • class ForceTorque
      • class IMU
      • struct IMUConfig
      • class Sensor
      • class Torque
    • namespace simu
      • struct GUIData
      • struct TextData
  • namespace gs
  • struct RobotData
  • namespace std
"},{"location":"api/files/","title":"File List","text":"

Here is a list of all files with brief descriptions:

  • dir robot_dart
    • file gui_data.hpp
    • file robot.cpp
    • file robot.hpp
    • dir control
      • 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
    • dir gui
      • file base.hpp
      • file helper.cpp
      • file helper.hpp
      • dir magnum
        • 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
        • dir gs
          • 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
        • dir sensor
          • file camera.cpp
          • file camera.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
      • file stb_image_write.h
    • dir robots
      • 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
    • dir sensor
      • 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
    • 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/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 (\n    const Utility::Resource & rs,\n    GL::Version version,\n    GL::Shader::Type type\n) \n

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

"},{"location":"api/namespaceTinyProcessLib/","title":"Namespace TinyProcessLib","text":"

Namespace List > TinyProcessLib

The documentation for this class was generated from the following file robot_dart/gui/magnum/gs/camera.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 (\n    const Eigen::Matrix3d & R,\n    const Eigen::Vector3d & t\n) \n
"},{"location":"api/namespacerobot__dart/#function-make_tf_1","title":"function make_tf","text":"
inline Eigen::Isometry3d robot_dart::make_tf (\n    const Eigen::Matrix3d & R\n) \n
"},{"location":"api/namespacerobot__dart/#function-make_tf_2","title":"function make_tf","text":"
inline Eigen::Isometry3d robot_dart::make_tf (\n    const Eigen::Vector3d & t\n) \n
"},{"location":"api/namespacerobot__dart/#function-make_tf_3","title":"function make_tf","text":"
inline Eigen::Isometry3d robot_dart::make_tf (\n    std::initializer_list< double > args\n) \n
"},{"location":"api/namespacerobot__dart/#function-make_vector","title":"function make_vector","text":"
inline Eigen::VectorXd robot_dart::make_vector (\n    std::initializer_list< double > args\n) \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 (\n    const std::string & msg=\"\"\n) \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 (\n    const std::string & model_file,\n    const std::vector< std::pair< std::string, std::string > > & packages,\n    const std::string & robot_name=\"robot\",\n    bool is_urdf_string=false,\n    bool cast_shadows=true\n) \n
"},{"location":"api/classrobot__dart_1_1Robot/#function-robot-23","title":"function Robot [\u2154]","text":"
robot_dart::Robot::Robot (\n    const std::string & model_file,\n    const std::string & robot_name=\"robot\",\n    bool is_urdf_string=false,\n    bool cast_shadows=true\n) \n
"},{"location":"api/classrobot__dart_1_1Robot/#function-robot-33","title":"function Robot [3/3]","text":"
robot_dart::Robot::Robot (\n    dart::dynamics::SkeletonPtr skeleton,\n    const std::string & robot_name=\"robot\",\n    bool cast_shadows=true\n) \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 (\n    const 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 (\n    const 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 (\n    const 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 (\n    const 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 (\n    const 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 (\n    const std::string & body_name,\n    double mass\n) \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 (\n    size_t body_index,\n    double mass\n) \n
"},{"location":"api/classrobot__dart_1_1Robot/#function-add_controller","title":"function add_controller","text":"
void robot_dart::Robot::add_controller (\n    const std::shared_ptr< control::RobotControl > & controller,\n    double weight=1.0\n) \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 (\n    const std::string & body_name,\n    const Eigen::Vector3d & force,\n    const Eigen::Vector3d & offset=Eigen::Vector3d::Zero(),\n    bool force_local=false,\n    bool offset_local=true\n) \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 (\n    size_t body_index,\n    const Eigen::Vector3d & force,\n    const Eigen::Vector3d & offset=Eigen::Vector3d::Zero(),\n    bool force_local=false,\n    bool offset_local=true\n) \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 (\n    const std::string & body_name,\n    const Eigen::Vector3d & torque,\n    bool local=false\n) \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 (\n    size_t body_index,\n    const Eigen::Vector3d & torque,\n    bool local=false\n) \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 (\n    const 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 (\n    const 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 (\n    size_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 (\n    const 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 (\n    const 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 (\n    size_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 (\n    size_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 (\n    const std::string & body_name\n) \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 (\n    size_t body_index\n) \n
"},{"location":"api/classrobot__dart_1_1Robot/#function-body_pose-12","title":"function body_pose [\u00bd]","text":"
Eigen::Isometry3d robot_dart::Robot::body_pose (\n    const 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 (\n    size_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 (\n    const 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 (\n    size_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 (\n    const 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 (\n    size_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 () \n
"},{"location":"api/classrobot__dart_1_1Robot/#function-clear_external_forces","title":"function clear_external_forces","text":"
void robot_dart::Robot::clear_external_forces () \n
"},{"location":"api/classrobot__dart_1_1Robot/#function-clear_internal_forces","title":"function clear_internal_forces","text":"
void robot_dart::Robot::clear_internal_forces () \n
"},{"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 (\n    const std::string & ghost_name=\"ghost\",\n    const 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 (\n    const 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 (\n    const 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 (\n    const 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 (\n    const 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 (\n    size_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 (\n    const 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 (\n    const 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 (\n    const 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 (\n    const 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 (\n    const std::string & dof_name\n) \n
"},{"location":"api/classrobot__dart_1_1Robot/#function-dof-22","title":"function dof [2/2]","text":"
dart::dynamics::DegreeOfFreedom * robot_dart::Robot::dof (\n    size_t dof_index\n) \n
"},{"location":"api/classrobot__dart_1_1Robot/#function-dof_index","title":"function dof_index","text":"
size_t robot_dart::Robot::dof_index (\n    const 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 (\n    size_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 (\n    bool filter_mimics=false,\n    bool filter_locked=false,\n    bool 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 (\n    const 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 (\n    size_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 () \n
"},{"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 (\n    const 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 () \n
"},{"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 (\n    size_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 (\n    const 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 (\n    const 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 (\n    const Eigen::Vector6d & pose=Eigen::Vector6d::Zero()\n) \n
"},{"location":"api/classrobot__dart_1_1Robot/#function-friction_coeff-12","title":"function friction_coeff [\u00bd]","text":"
double robot_dart::Robot::friction_coeff (\n    const std::string & body_name\n) \n
"},{"location":"api/classrobot__dart_1_1Robot/#function-friction_coeff-22","title":"function friction_coeff [2/2]","text":"
double robot_dart::Robot::friction_coeff (\n    size_t body_index\n) \n
"},{"location":"api/classrobot__dart_1_1Robot/#function-friction_dir-12","title":"function friction_dir [\u00bd]","text":"
Eigen::Vector3d robot_dart::Robot::friction_dir (\n    const std::string & body_name\n) \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 (\n    size_t body_index\n) \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 (\n    const 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 (\n    const 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 (\n    const 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 (\n    const std::string & body_name,\n    const 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 (\n    const std::string & body_name,\n    const 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 (\n    const std::string & joint_name\n) \n
"},{"location":"api/classrobot__dart_1_1Robot/#function-joint-22","title":"function joint [2/2]","text":"
dart::dynamics::Joint * robot_dart::Robot::joint (\n    size_t joint_index\n) \n
"},{"location":"api/classrobot__dart_1_1Robot/#function-joint_index","title":"function joint_index","text":"
size_t robot_dart::Robot::joint_index (\n    const 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 (\n    size_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 (\n    const 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 (\n    const 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 (\n    const 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 (\n    const 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 (\n    const 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 () \n
"},{"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 () \n
"},{"location":"api/classrobot__dart_1_1Robot/#function-remove_controller-12","title":"function remove_controller [\u00bd]","text":"
void robot_dart::Robot::remove_controller (\n    const std::shared_ptr< control::RobotControl > & controller\n) \n
"},{"location":"api/classrobot__dart_1_1Robot/#function-remove_controller-22","title":"function remove_controller [2/2]","text":"
void robot_dart::Robot::remove_controller (\n    size_t index\n) \n
"},{"location":"api/classrobot__dart_1_1Robot/#function-reset","title":"function reset","text":"
virtual void robot_dart::Robot::reset () \n
"},{"location":"api/classrobot__dart_1_1Robot/#function-reset_commands","title":"function reset_commands","text":"
void robot_dart::Robot::reset_commands () \n
"},{"location":"api/classrobot__dart_1_1Robot/#function-restitution_coeff-12","title":"function restitution_coeff [\u00bd]","text":"
double robot_dart::Robot::restitution_coeff (\n    const std::string & body_name\n) \n
"},{"location":"api/classrobot__dart_1_1Robot/#function-restitution_coeff-22","title":"function restitution_coeff [2/2]","text":"
double robot_dart::Robot::restitution_coeff (\n    size_t body_index\n) \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 (\n    const std::string & body_name\n) \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 (\n    size_t body_index\n) \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 (\n    const Eigen::VectorXd & accelerations,\n    const std::vector< std::string > & dof_names={}\n) \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 (\n    const Eigen::VectorXd & accelerations,\n    const std::vector< std::string > & dof_names={}\n) \n
"},{"location":"api/classrobot__dart_1_1Robot/#function-set_accelerations","title":"function set_accelerations","text":"
void robot_dart::Robot::set_accelerations (\n    const Eigen::VectorXd & accelerations,\n    const std::vector< std::string > & dof_names={}\n) \n
"},{"location":"api/classrobot__dart_1_1Robot/#function-set_actuator_type","title":"function set_actuator_type","text":"
void robot_dart::Robot::set_actuator_type (\n    const std::string & type,\n    const std::string & joint_name,\n    bool override_mimic=false,\n    bool override_base=false\n) \n
"},{"location":"api/classrobot__dart_1_1Robot/#function-set_actuator_types","title":"function set_actuator_types","text":"
void robot_dart::Robot::set_actuator_types (\n    const std::string & type,\n    const std::vector< std::string > & joint_names={},\n    bool override_mimic=false,\n    bool override_base=false\n) \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 (\n    const Eigen::Isometry3d & tf\n) \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 (\n    const Eigen::Vector6d & pose\n) \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 (\n    const std::string & body_name,\n    double mass\n) \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 (\n    size_t body_index,\n    double mass\n) \n
"},{"location":"api/classrobot__dart_1_1Robot/#function-set_body_name","title":"function set_body_name","text":"
void robot_dart::Robot::set_body_name (\n    size_t body_index,\n    const std::string & body_name\n) \n
"},{"location":"api/classrobot__dart_1_1Robot/#function-set_cast_shadows","title":"function set_cast_shadows","text":"
void robot_dart::Robot::set_cast_shadows (\n    bool cast_shadows=true\n) \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 (\n    const std::string & color_mode\n) \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 (\n    const std::string & color_mode,\n    const std::string & body_name\n) \n
"},{"location":"api/classrobot__dart_1_1Robot/#function-set_commands","title":"function set_commands","text":"
void robot_dart::Robot::set_commands (\n    const Eigen::VectorXd & commands,\n    const std::vector< std::string > & dof_names={}\n) \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 (\n    const std::vector< double > & cfrictions,\n    const std::vector< std::string > & dof_names={}\n) \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 (\n    double cfriction,\n    const std::vector< std::string > & dof_names={}\n) \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 (\n    const std::vector< double > & damps,\n    const std::vector< std::string > & dof_names={}\n) \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 (\n    double damp,\n    const std::vector< std::string > & dof_names={}\n) \n
"},{"location":"api/classrobot__dart_1_1Robot/#function-set_draw_axis","title":"function set_draw_axis","text":"
void robot_dart::Robot::set_draw_axis (\n    const std::string & body_name,\n    double size=0.25\n) \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 (\n    const std::string & body_name,\n    const Eigen::Vector3d & force,\n    const Eigen::Vector3d & offset=Eigen::Vector3d::Zero(),\n    bool force_local=false,\n    bool offset_local=true\n) \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 (\n    size_t body_index,\n    const Eigen::Vector3d & force,\n    const Eigen::Vector3d & offset=Eigen::Vector3d::Zero(),\n    bool force_local=false,\n    bool offset_local=true\n) \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 (\n    const std::string & body_name,\n    const Eigen::Vector3d & torque,\n    bool local=false\n) \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 (\n    size_t body_index,\n    const Eigen::Vector3d & torque,\n    bool local=false\n) \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 (\n    const Eigen::VectorXd & forces,\n    const std::vector< std::string > & dof_names={}\n) \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 (\n    const Eigen::VectorXd & forces,\n    const std::vector< std::string > & dof_names={}\n) \n
"},{"location":"api/classrobot__dart_1_1Robot/#function-set_forces","title":"function set_forces","text":"
void robot_dart::Robot::set_forces (\n    const Eigen::VectorXd & forces,\n    const std::vector< std::string > & dof_names={}\n) \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 (\n    const std::string & body_name,\n    double value\n) \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 (\n    size_t body_index,\n    double value\n) \n
"},{"location":"api/classrobot__dart_1_1Robot/#function-set_friction_coeffs","title":"function set_friction_coeffs","text":"
void robot_dart::Robot::set_friction_coeffs (\n    double value\n) \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 (\n    const std::string & body_name,\n    const Eigen::Vector3d & direction\n) \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 (\n    size_t body_index,\n    const Eigen::Vector3d & direction\n) \n
"},{"location":"api/classrobot__dart_1_1Robot/#function-set_ghost","title":"function set_ghost","text":"
void robot_dart::Robot::set_ghost (\n    bool ghost=true\n) \n
"},{"location":"api/classrobot__dart_1_1Robot/#function-set_joint_name","title":"function set_joint_name","text":"
void robot_dart::Robot::set_joint_name (\n    size_t joint_index,\n    const std::string & joint_name\n) \n
"},{"location":"api/classrobot__dart_1_1Robot/#function-set_mimic","title":"function set_mimic","text":"
void robot_dart::Robot::set_mimic (\n    const std::string & joint_name,\n    const std::string & mimic_joint_name,\n    double multiplier=1.,\n    double offset=0.\n) \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 (\n    const std::vector< bool > & enforced,\n    const std::vector< std::string > & dof_names={}\n) \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 (\n    bool enforced,\n    const std::vector< std::string > & dof_names={}\n) \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 (\n    const Eigen::VectorXd & positions,\n    const std::vector< std::string > & dof_names={}\n) \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 (\n    const Eigen::VectorXd & positions,\n    const std::vector< std::string > & dof_names={}\n) \n
"},{"location":"api/classrobot__dart_1_1Robot/#function-set_positions","title":"function set_positions","text":"
void robot_dart::Robot::set_positions (\n    const Eigen::VectorXd & positions,\n    const std::vector< std::string > & dof_names={}\n) \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 (\n    const std::string & body_name,\n    double value\n) \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 (\n    size_t body_index,\n    double value\n) \n
"},{"location":"api/classrobot__dart_1_1Robot/#function-set_restitution_coeffs","title":"function set_restitution_coeffs","text":"
void robot_dart::Robot::set_restitution_coeffs (\n    double value\n) \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 (\n    const std::string & body_name,\n    double value\n) \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 (\n    size_t body_index,\n    double value\n) \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 (\n    double value\n) \n
"},{"location":"api/classrobot__dart_1_1Robot/#function-set_self_collision","title":"function set_self_collision","text":"
void robot_dart::Robot::set_self_collision (\n    bool enable_self_collisions=true,\n    bool enable_adjacent_collisions=false\n) \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 (\n    const std::vector< double > & stiffnesses,\n    const std::vector< std::string > & dof_names={}\n) \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 (\n    double stiffness,\n    const std::vector< std::string > & dof_names={}\n) \n
"},{"location":"api/classrobot__dart_1_1Robot/#function-set_velocities","title":"function set_velocities","text":"
void robot_dart::Robot::set_velocities (\n    const Eigen::VectorXd & velocities,\n    const std::vector< std::string > & dof_names={}\n) \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 (\n    const Eigen::VectorXd & velocities,\n    const std::vector< std::string > & dof_names={}\n) \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 (\n    const Eigen::VectorXd & velocities,\n    const std::vector< std::string > & dof_names={}\n) \n
"},{"location":"api/classrobot__dart_1_1Robot/#function-skeleton","title":"function skeleton","text":"
dart::dynamics::SkeletonPtr robot_dart::Robot::skeleton () \n
"},{"location":"api/classrobot__dart_1_1Robot/#function-spring_stiffnesses","title":"function spring_stiffnesses","text":"
std::vector< double > robot_dart::Robot::spring_stiffnesses (\n    const 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 (\n    double t\n) \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 () \n
"},{"location":"api/classrobot__dart_1_1Robot/#function-vec_dof","title":"function vec_dof","text":"
Eigen::VectorXd robot_dart::Robot::vec_dof (\n    const Eigen::VectorXd & vec,\n    const 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 (\n    const 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 (\n    const 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 (\n    const 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 () \n
"},{"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 (\n    const Eigen::Vector3d & dims,\n    const Eigen::Isometry3d & tf,\n    const std::string & type=\"free\",\n    double mass=1.0,\n    const Eigen::Vector4d & color=dart::Color::Red(1.0),\n    const std::string & box_name=\"box\"\n) \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 (\n    const Eigen::Vector3d & dims,\n    const Eigen::Vector6d & pose=Eigen::Vector6d::Zero(),\n    const std::string & type=\"free\",\n    double mass=1.0,\n    const Eigen::Vector4d & color=dart::Color::Red(1.0),\n    const std::string & box_name=\"box\"\n) \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 (\n    const Eigen::Vector3d & dims,\n    const Eigen::Isometry3d & tf,\n    const std::string & type=\"free\",\n    double mass=1.0,\n    const Eigen::Vector4d & color=dart::Color::Red(1.0),\n    const std::string & ellipsoid_name=\"ellipsoid\"\n) \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 (\n    const Eigen::Vector3d & dims,\n    const Eigen::Vector6d & pose=Eigen::Vector6d::Zero(),\n    const std::string & type=\"free\",\n    double mass=1.0,\n    const Eigen::Vector4d & color=dart::Color::Red(1.0),\n    const std::string & ellipsoid_name=\"ellipsoid\"\n) \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 (\n    size_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 (\n    const std::string & filename\n) const\n
"},{"location":"api/classrobot__dart_1_1Robot/#function-_jacobian","title":"function _jacobian","text":"
Eigen::MatrixXd robot_dart::Robot::_jacobian (\n    const Eigen::MatrixXd & full_jacobian,\n    const 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 (\n    const std::string & filename,\n    const std::vector< std::pair< std::string, std::string > > & packages=std::vector< std::pair< std::string, std::string > >(),\n    bool is_urdf_string=false\n) \n
"},{"location":"api/classrobot__dart_1_1Robot/#function-_mass_matrix","title":"function _mass_matrix","text":"
Eigen::MatrixXd robot_dart::Robot::_mass_matrix (\n    const Eigen::MatrixXd & full_mass_matrix,\n    const 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 (\n    RobotDARTSimu *\n) \n
"},{"location":"api/classrobot__dart_1_1Robot/#function-_post_removal","title":"function _post_removal","text":"
inline virtual void robot_dart::Robot::_post_removal (\n    RobotDARTSimu *\n) \n
"},{"location":"api/classrobot__dart_1_1Robot/#function-_set_actuator_type","title":"function _set_actuator_type","text":"
void robot_dart::Robot::_set_actuator_type (\n    size_t joint_index,\n    dart::dynamics::Joint::ActuatorType type,\n    bool override_mimic=false,\n    bool override_base=false\n) \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 (\n    const std::vector< dart::dynamics::Joint::ActuatorType > & types,\n    bool override_mimic=false,\n    bool override_base=false\n) \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 (\n    dart::dynamics::Joint::ActuatorType type,\n    bool override_mimic=false,\n    bool override_base=false\n) \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 (\n    dart::dynamics::MeshShape::ColorMode color_mode,\n    dart::dynamics::SkeletonPtr skel\n) \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 (\n    dart::dynamics::MeshShape::ColorMode color_mode,\n    dart::dynamics::ShapeNode * sn\n) \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=2<< 2, 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 (\n    double timestep=0.015\n) \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 (\n    double floor_width=10.0,\n    double floor_height=0.1,\n    double size=1.,\n    const Eigen::Isometry3d & tf=Eigen::Isometry3d::Identity(),\n    const std::string & floor_name=\"checkerboard_floor\",\n    const Eigen::Vector4d & first_color=dart::Color::White(1.),\n    const Eigen::Vector4d & second_color=dart::Color::Gray(1.)\n) \n
"},{"location":"api/classrobot__dart_1_1RobotDARTSimu/#function-add_floor","title":"function add_floor","text":"
std::shared_ptr< Robot > robot_dart::RobotDARTSimu::add_floor (\n    double floor_width=10.0,\n    double floor_height=0.1,\n    const Eigen::Isometry3d & tf=Eigen::Isometry3d::Identity(),\n    const std::string & floor_name=\"floor\"\n) \n
"},{"location":"api/classrobot__dart_1_1RobotDARTSimu/#function-add_robot","title":"function add_robot","text":"
void robot_dart::RobotDARTSimu::add_robot (\n    const robot_t & robot\n) \n
"},{"location":"api/classrobot__dart_1_1RobotDARTSimu/#function-add_sensor-12","title":"function add_sensor [\u00bd]","text":"
template<typename T, typename... Args>\ninline std::shared_ptr< T > robot_dart::RobotDARTSimu::add_sensor (\n    Args &&... args\n) \n
"},{"location":"api/classrobot__dart_1_1RobotDARTSimu/#function-add_sensor-22","title":"function add_sensor [2/2]","text":"
void robot_dart::RobotDARTSimu::add_sensor (\n    const std::shared_ptr< sensor::Sensor > & sensor\n) \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 (\n    const std::string & text,\n    const Eigen::Affine2d & tf=Eigen::Affine2d::Identity(),\n    Eigen::Vector4d color=Eigen::Vector4d(1, 1, 1, 1),\n    std::uint8_t alignment=2<< 2,\n    bool draw_bg=false,\n    Eigen::Vector4d bg_color=Eigen::Vector4d(0, 0, 0, 0.75),\n    double font_size=28\n) \n
"},{"location":"api/classrobot__dart_1_1RobotDARTSimu/#function-add_visual_robot","title":"function add_visual_robot","text":"
void robot_dart::RobotDARTSimu::add_visual_robot (\n    const robot_t & robot\n) \n
"},{"location":"api/classrobot__dart_1_1RobotDARTSimu/#function-clear_robots","title":"function clear_robots","text":"
void robot_dart::RobotDARTSimu::clear_robots () \n
"},{"location":"api/classrobot__dart_1_1RobotDARTSimu/#function-clear_sensors","title":"function clear_sensors","text":"
void robot_dart::RobotDARTSimu::clear_sensors () \n
"},{"location":"api/classrobot__dart_1_1RobotDARTSimu/#function-collision_category-12","title":"function collision_category [\u00bd]","text":"
uint32_t robot_dart::RobotDARTSimu::collision_category (\n    size_t robot_index,\n    const std::string & body_name\n) \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 (\n    size_t robot_index,\n    size_t body_index\n) \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 (\n    size_t robot_index,\n    const std::string & body_name\n) \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 (\n    size_t robot_index,\n    size_t body_index\n) \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 (\n    size_t robot_index,\n    const std::string & body_name\n) \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 (\n    size_t robot_index,\n    size_t body_index\n) \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 (\n    bool enable=true,\n    double font_size=-1\n) \n
"},{"location":"api/classrobot__dart_1_1RobotDARTSimu/#function-enable_text_panel","title":"function enable_text_panel","text":"
void robot_dart::RobotDARTSimu::enable_text_panel (\n    bool enable=true,\n    double font_size=-1\n) \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 () \n
"},{"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 () \n
"},{"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 (\n    size_t robot_index\n) \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 (\n    size_t robot_index,\n    const std::string & body_name\n) \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 (\n    size_t robot_index,\n    size_t body_index\n) \n
"},{"location":"api/classrobot__dart_1_1RobotDARTSimu/#function-remove_robot-12","title":"function remove_robot [\u00bd]","text":"
void robot_dart::RobotDARTSimu::remove_robot (\n    const robot_t & robot\n) \n
"},{"location":"api/classrobot__dart_1_1RobotDARTSimu/#function-remove_robot-22","title":"function remove_robot [2/2]","text":"
void robot_dart::RobotDARTSimu::remove_robot (\n    size_t index\n) \n
"},{"location":"api/classrobot__dart_1_1RobotDARTSimu/#function-remove_sensor-12","title":"function remove_sensor [\u00bd]","text":"
void robot_dart::RobotDARTSimu::remove_sensor (\n    const std::shared_ptr< sensor::Sensor > & sensor\n) \n
"},{"location":"api/classrobot__dart_1_1RobotDARTSimu/#function-remove_sensor-22","title":"function remove_sensor [2/2]","text":"
void robot_dart::RobotDARTSimu::remove_sensor (\n    size_t index\n) \n
"},{"location":"api/classrobot__dart_1_1RobotDARTSimu/#function-remove_sensors","title":"function remove_sensors","text":"
void robot_dart::RobotDARTSimu::remove_sensors (\n    const std::string & type\n) \n
"},{"location":"api/classrobot__dart_1_1RobotDARTSimu/#function-robot","title":"function robot","text":"
robot_t robot_dart::RobotDARTSimu::robot (\n    size_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 (\n    const 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 (\n    double max_duration=5.0,\n    bool reset_commands=false,\n    bool force_position_bounds=true\n) \n
"},{"location":"api/classrobot__dart_1_1RobotDARTSimu/#function-schedule","title":"function schedule","text":"
inline bool robot_dart::RobotDARTSimu::schedule (\n    int freq\n) \n
"},{"location":"api/classrobot__dart_1_1RobotDARTSimu/#function-scheduler-12","title":"function scheduler [\u00bd]","text":"
inline Scheduler & robot_dart::RobotDARTSimu::scheduler () \n
"},{"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 (\n    size_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 (\n    const std::string & collision_detector\n) \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 (\n    size_t robot_index,\n    uint32_t category_mask,\n    uint32_t collision_mask\n) \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 (\n    size_t robot_index,\n    const std::string & body_name,\n    uint32_t category_mask,\n    uint32_t collision_mask\n) \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 (\n    size_t robot_index,\n    size_t body_index,\n    uint32_t category_mask,\n    uint32_t collision_mask\n) \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 (\n    int frequency\n) \n
"},{"location":"api/classrobot__dart_1_1RobotDARTSimu/#function-set_graphics","title":"function set_graphics","text":"
void robot_dart::RobotDARTSimu::set_graphics (\n    const std::shared_ptr< gui::Base > & graphics\n) \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 (\n    int frequency\n) \n
"},{"location":"api/classrobot__dart_1_1RobotDARTSimu/#function-set_gravity","title":"function set_gravity","text":"
void robot_dart::RobotDARTSimu::set_gravity (\n    const Eigen::Vector3d & gravity\n) \n
"},{"location":"api/classrobot__dart_1_1RobotDARTSimu/#function-set_text_panel","title":"function set_text_panel","text":"
void robot_dart::RobotDARTSimu::set_text_panel (\n    const std::string & str\n) \n
"},{"location":"api/classrobot__dart_1_1RobotDARTSimu/#function-set_timestep","title":"function set_timestep","text":"
void robot_dart::RobotDARTSimu::set_timestep (\n    double timestep,\n    bool update_control_freq=true\n) \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 (\n    bool reset_commands=false,\n    bool force_position_bounds=true\n) \n
"},{"location":"api/classrobot__dart_1_1RobotDARTSimu/#function-step_world","title":"function step_world","text":"
bool robot_dart::RobotDARTSimu::step_world (\n    bool reset_commands=false,\n    bool force_position_bounds=true\n) \n
"},{"location":"api/classrobot__dart_1_1RobotDARTSimu/#function-stop_sim","title":"function stop_sim","text":"
void robot_dart::RobotDARTSimu::stop_sim (\n    bool disable=true\n) \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 () \n
"},{"location":"api/classrobot__dart_1_1RobotDARTSimu/#function-robotdartsimu_1","title":"function ~RobotDARTSimu","text":"
robot_dart::RobotDARTSimu::~RobotDARTSimu () \n
"},{"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 (\n    std::shared_ptr< simu::TextData > & text,\n    bool enable,\n    double font_size\n) \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 (\n    const robot_creator_t & robot_creator,\n    size_t pool_size=32,\n    bool verbose=true\n) \n
"},{"location":"api/classrobot__dart_1_1RobotPool/#function-robotpool-22","title":"function RobotPool [2/2]","text":"
robot_dart::RobotPool::RobotPool (\n    const 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 (\n    const std::shared_ptr< Robot > & robot\n) \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 (\n    const std::string & name=\"robot\"\n) \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= (\n    const RobotPool &\n) = delete\n
"},{"location":"api/classrobot__dart_1_1RobotPool/#function-robotpool","title":"function ~RobotPool","text":"
inline virtual robot_dart::RobotPool::~RobotPool () \n
"},{"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 (\n    const std::shared_ptr< Robot > & robot\n) \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 (\n    double dt,\n    bool sync=false\n) \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() (\n    int frequency\n) \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 (\n    double dt,\n    bool sync=false,\n    double current_time=0.,\n    double real_time=0.\n) \n
"},{"location":"api/classrobot__dart_1_1Scheduler/#function-schedule","title":"function schedule","text":"
bool robot_dart::Scheduler::schedule (\n    int frequency\n) \n
"},{"location":"api/classrobot__dart_1_1Scheduler/#function-set_sync","title":"function set_sync","text":"
inline void robot_dart::Scheduler::set_sync (\n    bool enable\n) \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 () \n

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::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::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 (\n    DartShapeConstPtr shape,\n    uint32_t col_mask,\n    uint32_t cat_mask\n) \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 (\n    dart::dynamics::SkeletonPtr skel,\n    uint32_t col_mask,\n    uint32_t cat_mask\n) \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 () \n
"},{"location":"api/classrobot__dart_1_1collision__filter_1_1BitmaskContactFilter/#function-ignorescollision","title":"function ignoresCollision","text":"
inline bool robot_dart::collision_filter::BitmaskContactFilter::ignoresCollision (\n    DartCollisionConstPtr object1,\n    DartCollisionConstPtr 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 (\n    DartShapeConstPtr 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 (\n    DartShapeConstPtr shape\n) \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 (\n    dart::dynamics::SkeletonPtr skel\n) \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 () \n
"},{"location":"api/classrobot__dart_1_1control_1_1PDControl/#function-pdcontrol-23","title":"function PDControl [\u2154]","text":"
robot_dart::control::PDControl::PDControl (\n    const Eigen::VectorXd & ctrl,\n    bool full_control=false,\n    bool use_angular_errors=true\n) \n
"},{"location":"api/classrobot__dart_1_1control_1_1PDControl/#function-pdcontrol-33","title":"function PDControl [3/3]","text":"
robot_dart::control::PDControl::PDControl (\n    const Eigen::VectorXd & ctrl,\n    const std::vector< std::string > & controllable_dofs,\n    bool use_angular_errors=true\n) \n
"},{"location":"api/classrobot__dart_1_1control_1_1PDControl/#function-calculate","title":"function calculate","text":"
virtual Eigen::VectorXd robot_dart::control::PDControl::calculate (\n    double\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 (\n    double p,\n    double d\n) \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 (\n    const Eigen::VectorXd & p,\n    const Eigen::VectorXd & d\n) \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 (\n    bool enable=true\n) \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 (\n    double target,\n    double current\n) \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>

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 () \n
"},{"location":"api/classrobot__dart_1_1control_1_1PolicyControl/#function-policycontrol-25","title":"function PolicyControl [\u2156]","text":"
inline robot_dart::control::PolicyControl::PolicyControl (\n    double dt,\n    const Eigen::VectorXd & ctrl,\n    bool full_control=false\n) \n
"},{"location":"api/classrobot__dart_1_1control_1_1PolicyControl/#function-policycontrol-35","title":"function PolicyControl [\u2157]","text":"
inline robot_dart::control::PolicyControl::PolicyControl (\n    const Eigen::VectorXd & ctrl,\n    bool full_control=false\n) \n
"},{"location":"api/classrobot__dart_1_1control_1_1PolicyControl/#function-policycontrol-45","title":"function PolicyControl [\u2158]","text":"
inline robot_dart::control::PolicyControl::PolicyControl (\n    double dt,\n    const Eigen::VectorXd & ctrl,\n    const std::vector< std::string > & controllable_dofs\n) \n
"},{"location":"api/classrobot__dart_1_1control_1_1PolicyControl/#function-policycontrol-55","title":"function PolicyControl [5/5]","text":"
inline robot_dart::control::PolicyControl::PolicyControl (\n    const Eigen::VectorXd & ctrl,\n    const std::vector< std::string > & controllable_dofs\n) \n
"},{"location":"api/classrobot__dart_1_1control_1_1PolicyControl/#function-calculate","title":"function calculate","text":"
inline virtual Eigen::VectorXd robot_dart::control::PolicyControl::calculate (\n    double 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 (\n    const Eigen::VectorXd & h_params\n) \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 () \n
"},{"location":"api/classrobot__dart_1_1control_1_1RobotControl/#function-robotcontrol-23","title":"function RobotControl [\u2154]","text":"
robot_dart::control::RobotControl::RobotControl (\n    const Eigen::VectorXd & ctrl,\n    bool full_control=false\n) \n
"},{"location":"api/classrobot__dart_1_1control_1_1RobotControl/#function-robotcontrol-33","title":"function RobotControl [3/3]","text":"
robot_dart::control::RobotControl::RobotControl (\n    const Eigen::VectorXd & ctrl,\n    const std::vector< std::string > & controllable_dofs\n) \n
"},{"location":"api/classrobot__dart_1_1control_1_1RobotControl/#function-activate","title":"function activate","text":"
void robot_dart::control::RobotControl::activate (\n    bool enable=true\n) \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 (\n    double 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 () \n
"},{"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 (\n    const Eigen::VectorXd & ctrl\n) \n
"},{"location":"api/classrobot__dart_1_1control_1_1RobotControl/#function-set_robot","title":"function set_robot","text":"
void robot_dart::control::RobotControl::set_robot (\n    const std::shared_ptr< Robot > & robot\n) \n
"},{"location":"api/classrobot__dart_1_1control_1_1RobotControl/#function-set_weight","title":"function set_weight","text":"
void robot_dart::control::RobotControl::set_weight (\n    double weight\n) \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 () \n
"},{"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 () \n
"},{"location":"api/classrobot__dart_1_1control_1_1SimpleControl/#function-simplecontrol-23","title":"function SimpleControl [\u2154]","text":"
robot_dart::control::SimpleControl::SimpleControl (\n    const Eigen::VectorXd & ctrl,\n    bool full_control=false\n) \n
"},{"location":"api/classrobot__dart_1_1control_1_1SimpleControl/#function-simplecontrol-33","title":"function SimpleControl [3/3]","text":"
robot_dart::control::SimpleControl::SimpleControl (\n    const Eigen::VectorXd & ctrl,\n    const std::vector< std::string > & controllable_dofs\n) \n
"},{"location":"api/classrobot__dart_1_1control_1_1SimpleControl/#function-calculate","title":"function calculate","text":"
virtual Eigen::VectorXd robot_dart::control::SimpleControl::calculate (\n    double\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 (\n    const Eigen::VectorXd & data,\n    dart::dynamics::SkeletonPtr skeleton,\n    const std::vector< std::string > & dof_names,\n    const std::unordered_map< std::string, size_t > & dof_map\n) \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 (\n    dart::dynamics::SkeletonPtr skeleton,\n    const std::vector< std::string > & dof_names,\n    const std::unordered_map< std::string, size_t > & dof_map\n) \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 (\n    const Eigen::VectorXd & data,\n    dart::dynamics::SkeletonPtr skeleton,\n    const std::vector< std::string > & dof_names,\n    const std::unordered_map< std::string, size_t > & dof_map\n) \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 (\n    const Image & rgb\n) \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 (\n    const DepthImage & depth_image,\n    const Eigen::Matrix3d & intrinsic_matrix,\n    const Eigen::Matrix4d & tf,\n    double far_plane\n) \n
"},{"location":"api/namespacerobot__dart_1_1gui/#function-save_png_image","title":"function save_png_image","text":"
void robot_dart::gui::save_png_image (\n    const std::string & filename,\n    const Image & rgb\n) \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 (\n    const std::string & filename,\n    const GrayscaleImage & gray\n) \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 () \n
"},{"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 () \n
"},{"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 () \n
"},{"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 () \n
"},{"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 () \n
"},{"location":"api/classrobot__dart_1_1gui_1_1Base/#function-refresh","title":"function refresh","text":"
inline virtual void robot_dart::gui::Base::refresh () \n
"},{"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 (\n    bool\n) \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 (\n    int\n) \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 (\n    double\n) \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 (\n    RobotDARTSimu * simu\n) \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 () \n
"},{"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 =  Magnum::SceneGraph::Camera3D;\n
"},{"location":"api/namespacerobot__dart_1_1gui_1_1magnum/#typedef-object3d","title":"typedef Object3D","text":"
using robot_dart::gui::magnum::Object3D =  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 =  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>\ninline BaseApplication * robot_dart::gui::magnum::make_application (\n    RobotDARTSimu * simu,\n    const GraphicsConfiguration & configuration=GraphicsConfiguration ()\n) \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 (\n    const GraphicsConfiguration & configuration=GraphicsConfiguration ()\n) \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 (\n    const gs::Light & light\n) \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 (\n    gs::Camera & camera,\n    dart::dynamics::BodyNode * body\n) \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 () \n
"},{"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 () \n
"},{"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 () \n
"},{"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 () \n
"},{"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 () \n
"},{"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 () \n
"},{"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 (\n    bool enable=true,\n    bool drawTransparentShadows=false\n) \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 () \n
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1BaseApplication/#function-init","title":"function init","text":"
void robot_dart::gui::magnum::BaseApplication::init (\n    RobotDARTSimu * simu,\n    const GraphicsConfiguration & configuration\n) \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 (\n    size_t i\n) \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 () \n
"},{"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 (\n    const Eigen::Vector3d & camera_pos,\n    const Eigen::Vector3d & look_at,\n    const Eigen::Vector3d & up\n) \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 () \n
"},{"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 (\n    const std::string & video_fname,\n    int fps\n) \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 () \n
"},{"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 () \n
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1BaseApplication/#function-scene","title":"function scene","text":"
inline Scene3D & robot_dart::gui::magnum::BaseApplication::scene () \n
"},{"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 () \n
"},{"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 (\n    const gs::Camera & camera\n) \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 () \n
"},{"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 () \n
"},{"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 () \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_1BaseGraphics/","title":"Class robot_dart::gui::magnum::BaseGraphics","text":"

template <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 (\n    const GraphicsConfiguration & configuration=GraphicsConfiguration ()\n) \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 (\n    const magnum::gs::Light & light\n) \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 () \n
"},{"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 () \n
"},{"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 (\n    bool enable=true,\n    bool transparent=true\n) \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 (\n    size_t i\n) \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 () \n
"},{"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 (\n    const Eigen::Vector3d & camera_pos,\n    const Eigen::Vector3d & look_at=Eigen::Vector3d(0, 0, 0),\n    const Eigen::Vector3d & up=Eigen::Vector3d(0, 0, 1)\n) \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 () \n
"},{"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 () \n
"},{"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 (\n    const std::string & video_fname,\n    int fps=-1\n) \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 (\n    bool 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 (\n    int 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 (\n    RobotDARTSimu * 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 () \n
"},{"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 (\n    RobotDARTSimu * simu,\n    dart::dynamics::ShapeNode * shape,\n    const std::vector< std::reference_wrapper< Magnum::GL::Mesh > > & meshes,\n    gs::CubeMapColor & shader,\n    gs::CubeMapColor & texture_shader,\n    Object3D * parent,\n    Magnum::SceneGraph::DrawableGroup3D * group\n) \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 (\n    const std::vector< gs::Material > & materials\n) \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 (\n    const std::vector< std::reference_wrapper< Magnum::GL::Mesh > > & meshes\n) \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 (\n    const std::vector< Magnum::Vector3 > & scalings\n) \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 (\n    RobotDARTSimu * simu,\n    dart::dynamics::ShapeNode * shape,\n    const std::vector< std::reference_wrapper< Magnum::GL::Mesh > > & meshes,\n    gs::CubeMap & shader,\n    gs::CubeMap & texture_shader,\n    Object3D * parent,\n    Magnum::SceneGraph::DrawableGroup3D * group\n) \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 (\n    const std::vector< gs::Material > & materials\n) \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 (\n    const std::vector< std::reference_wrapper< Magnum::GL::Mesh > > & meshes\n) \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 (\n    const std::vector< Magnum::Vector3 > & scalings\n) \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 (\n    RobotDARTSimu * simu,\n    dart::dynamics::ShapeNode * shape,\n    const std::vector< std::reference_wrapper< Magnum::GL::Mesh > > & meshes,\n    const std::vector< gs::Material > & materials,\n    gs::PhongMultiLight & color,\n    gs::PhongMultiLight & texture,\n    Object3D * parent,\n    Magnum::SceneGraph::DrawableGroup3D * group\n) \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 (\n    std::reference_wrapper< gs::PhongMultiLight > shader\n) \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 (\n    const std::vector< gs::Material > & materials\n) \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 (\n    const std::vector< std::reference_wrapper< Magnum::GL::Mesh > > & meshes\n) \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 (\n    const std::vector< Magnum::Vector3 > & scalings\n) \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 (\n    const std::vector< bool > & softBody\n) \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 (\n    std::reference_wrapper< gs::PhongMultiLight > shader\n) \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 (\n    bool transparent=true\n) \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 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 (\n    int argc,\n    char ** argv,\n    RobotDARTSimu * simu,\n    const GraphicsConfiguration & configuration=GraphicsConfiguration ()\n) \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 () \n
"},{"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":"
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 (\n    ExitEvent & 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 (\n    KeyEvent & 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 (\n    KeyEvent & 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 (\n    MouseMoveEvent & 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 (\n    MouseScrollEvent & 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 (\n    ViewportEvent & 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 (\n    const 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 (\n    Magnum::Platform::WindowlessGLContext * context\n) \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 () \n
"},{"location":"api/structrobot__dart_1_1gui_1_1magnum_1_1GlobalData/#function-operator","title":"function operator=","text":"
void robot_dart::gui::magnum::GlobalData::operator= (\n    const 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 (\n    size_t N\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 () \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_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 (\n    const GraphicsConfiguration & configuration=default_configuration()\n) \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 (\n    RobotDARTSimu * 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 () \n
"},{"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 () \n

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 (\n    RobotDARTSimu * simu,\n    dart::dynamics::ShapeNode * shape,\n    const std::vector< std::reference_wrapper< Magnum::GL::Mesh > > & meshes,\n    gs::ShadowMapColor & shader,\n    gs::ShadowMapColor & texture_shader,\n    Object3D * parent,\n    Magnum::SceneGraph::DrawableGroup3D * group\n) \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 (\n    const std::vector< gs::Material > & materials\n) \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 (\n    const std::vector< std::reference_wrapper< Magnum::GL::Mesh > > & meshes\n) \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 (\n    const std::vector< Magnum::Vector3 > & scalings\n) \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 (\n    RobotDARTSimu * simu,\n    dart::dynamics::ShapeNode * shape,\n    const std::vector< std::reference_wrapper< Magnum::GL::Mesh > > & meshes,\n    gs::ShadowMap & shader,\n    gs::ShadowMap & texture_shader,\n    Object3D * parent,\n    Magnum::SceneGraph::DrawableGroup3D * group\n) \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 (\n    const std::vector< gs::Material > & materials\n) \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 (\n    const std::vector< std::reference_wrapper< Magnum::GL::Mesh > > & meshes\n) \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 (\n    const std::vector< Magnum::Vector3 > & scalings\n) \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 (\n    int argc,\n    char ** argv,\n    RobotDARTSimu * simu,\n    const GraphicsConfiguration & configuration=GraphicsConfiguration ()\n) \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 () \n
"},{"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 (\n    const GraphicsConfiguration & configuration=default_configuration()\n) \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 (\n    RobotDARTSimu * 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 () \n
"},{"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 () \n

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 (\n    const Magnum::Vector3 & direction,\n    const Material & material\n) \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 (\n    const Magnum::Vector3 & position,\n    const Material & material,\n    Magnum::Float intensity,\n    const Magnum::Vector3 & attenuationTerms\n) \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 (\n    const Magnum::Vector3 & position,\n    const Material & material,\n    const Magnum::Vector3 & spot_direction,\n    Magnum::Float spot_exponent,\n    Magnum::Float spot_cut_off,\n    Magnum::Float intensity,\n    const Magnum::Vector3 & attenuationTerms\n) \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 (\n    Magnum::Image2D * image,\n    Magnum::Float near_plane,\n    Magnum::Float far_plane\n) \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 (\n    Magnum::Image2D * image,\n    bool linearize,\n    Magnum::Float near_plane,\n    Magnum::Float far_plane\n) \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 (\n    Magnum::Image2D * image\n) \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 (\n    const fs::path & filename\n) \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 (\n    Object3D & object,\n    Magnum::Int width,\n    Magnum::Int height\n) \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 () \n
"},{"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 (\n    Magnum::SceneGraph::DrawableGroup3D & drawables,\n    Magnum::GL::AbstractFramebuffer & framebuffer,\n    Magnum::PixelFormat format,\n    RobotDARTSimu * simu,\n    const DebugDrawData & debug_data,\n    bool draw_debug=true\n) \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 (\n    Magnum::Float speed\n) \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 () \n
"},{"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 (\n    const Magnum::Vector3 & camera,\n    const Magnum::Vector3 & center,\n    const Magnum::Vector3 & up=Magnum::Vector3::zAxis()\n) \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 (\n    const Magnum::Vector2i & shift\n) \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 (\n    bool recording,\n    bool recording_depth=false\n) \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 (\n    const std::string & video_fname,\n    int fps\n) \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 () \n
"},{"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 () \n
"},{"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 () \n
"},{"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 (\n    Magnum::Float near_plane,\n    Magnum::Float far_plane,\n    Magnum::Float fov,\n    Magnum::Int width,\n    Magnum::Int height\n) \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 (\n    Magnum::Float far_plane\n) \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 (\n    Magnum::Float fov\n) \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 (\n    Magnum::Float near_plane\n) \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 (\n    const Magnum::Vector2 & speed\n) \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 (\n    const Magnum::Vector2i & size\n) \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 (\n    Magnum::Float speed\n) \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 (\n    std::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 () \n

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 {\n    DiffuseTexture = 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 (\n    Flags flags={}\n) \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 (\n    Magnum::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 (\n    Magnum::Float far_plane\n) \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 (\n    Magnum::Int index\n) \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 (\n    const Magnum::Vector3 & position\n) \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 (\n    Material & material\n) \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 (\n    Magnum::Matrix4 matrices\n) \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 (\n    const Magnum::Matrix4 & matrix\n) \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 {\n    DiffuseTexture = 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 (\n    Flags flags={}\n) \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 (\n    Magnum::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 (\n    Magnum::GL::CubeMapTextureArray & texture\n) \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 (\n    Magnum::Float far_plane\n) \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 (\n    Magnum::Int index\n) \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 (\n    const Magnum::Vector3 & position\n) \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 (\n    Material & material\n) \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 (\n    Magnum::Matrix4 matrices\n) \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 (\n    const Magnum::Matrix4 & matrix\n) \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 () \n
"},{"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 (\n    const Magnum::Vector4 & position,\n    const Material & material,\n    const Magnum::Vector3 & spot_direction,\n    Magnum::Float spot_exponent,\n    Magnum::Float spot_cut_off,\n    const Magnum::Vector4 & attenuation,\n    bool cast_shadows=true\n) \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 () \n
"},{"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 () \n
"},{"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 (\n    const Magnum::Vector4 & attenuation\n) \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 (\n    bool cast_shadows\n) \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 (\n    const Material & material\n) \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 (\n    const Magnum::Vector4 & position\n) \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 (\n    const Magnum::Matrix4 & shadowTransform\n) \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 (\n    Magnum::Float spot_cut_off\n) \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 (\n    const Magnum::Vector3 & spot_direction\n) \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 (\n    Magnum::Float spot_exponent\n) \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 (\n    const Magnum::Vector4 & transformed_position\n) \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 (\n    const Magnum::Vector3 & transformed_spot_direction\n) \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 () \n
"},{"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 () \n
"},{"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 () \n
"},{"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 () \n
"},{"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 () \n
"},{"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 (\n    const Magnum::Color4 & ambient,\n    const Magnum::Color4 & diffuse,\n    const Magnum::Color4 & specular,\n    Magnum::Float shininess\n) \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 (\n    Magnum::GL::Texture2D * ambient_texture,\n    Magnum::GL::Texture2D * diffuse_texture,\n    Magnum::GL::Texture2D * specular_texture,\n    Magnum::Float shininess\n) \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 () \n
"},{"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 () \n
"},{"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 () \n
"},{"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 () \n
"},{"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 (\n    const Magnum::Color4 & ambient\n) \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 (\n    Magnum::GL::Texture2D * ambient_texture\n) \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 (\n    const Magnum::Color4 & diffuse\n) \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 (\n    Magnum::GL::Texture2D * diffuse_texture\n) \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 (\n    Magnum::Float shininess\n) \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 (\n    const Magnum::Color4 & specular\n) \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 (\n    Magnum::GL::Texture2D * specular_texture\n) \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 () \n
"},{"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 () \n
"},{"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 () \n
"},{"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 {\n    AmbientTexture = 1 << 0,\n    DiffuseTexture = 1 << 1,\n    SpecularTexture = 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 (\n    Flags flags={},\n    Magnum::Int max_lights=10\n) \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 (\n    Magnum::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 (\n    Magnum::GL::CubeMapTextureArray & texture\n) \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 (\n    Magnum::GL::CubeMapTextureArray & texture\n) \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 (\n    Magnum::GL::Texture2DArray & texture\n) \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 (\n    Magnum::GL::Texture2DArray & texture\n) \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 (\n    const Magnum::Matrix4 & matrix\n) \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 (\n    Magnum::Float far_plane\n) \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 (\n    bool shadows\n) \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 (\n    Magnum::Int i,\n    const Light & light\n) \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 (\n    Material & material\n) \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 (\n    const Magnum::Matrix3x3 & matrix\n) \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 (\n    const Magnum::Matrix4 & matrix\n) \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 (\n    Magnum::Float specular_strength\n) \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 (\n    const Magnum::Matrix4 & matrix\n) \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 (\n    bool shadows\n) \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 {\n    DiffuseTexture = 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 (\n    Flags flags={}\n) \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 (\n    Magnum::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 (\n    Material & material\n) \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 (\n    const Magnum::Matrix4 & matrix\n) \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 (\n    const Magnum::Matrix4 & matrix\n) \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 {\n    DiffuseTexture = 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 (\n    Flags flags={}\n) \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 (\n    Magnum::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 (\n    Material & material\n) \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 (\n    const Magnum::Matrix4 & matrix\n) \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 (\n    const Magnum::Matrix4 & matrix\n) \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 (\n    BaseApplication * app,\n    size_t width,\n    size_t height,\n    size_t freq=30,\n    bool draw_debug=false\n) \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 (\n    dart::dynamics::BodyNode * body,\n    const 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 (\n    dart::dynamics::Joint *,\n    const 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 (\n    double\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 () \n
"},{"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 () \n
"},{"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 () \n
"},{"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 (\n    bool draw=true\n) \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 () \n
"},{"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 (\n    const Eigen::Vector3d & camera_pos,\n    const Eigen::Vector3d & look_at=Eigen::Vector3d(0, 0, 0),\n    const Eigen::Vector3d & up=Eigen::Vector3d(0, 0, 1)\n) \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 () \n
"},{"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 () \n
"},{"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 () \n
"},{"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 (\n    const std::string & video_fname\n) \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 () \n
"},{"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 (\n    size_t frequency=1000,\n    const std::string & urdf=\"unitree_a1/a1.urdf\",\n    const std::vector< std::pair< std::string, std::string > > & packages=('a1_description', 'unitree_a1/a1_description')\n) \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 (\n    const std::string & urdf=\"arm.urdf\"\n) \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 (\n    size_t frequency=1000,\n    const std::string & urdf=\"franka/franka.urdf\",\n    const std::vector< std::pair< std::string, std::string > > & packages=('franka_description', 'franka/franka_description')\n) \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 (\n    RobotDARTSimu *\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 (\n    RobotDARTSimu *\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 (\n    const std::string & urdf=\"pexod.urdf\"\n) \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 (\n    size_t frequency=1000,\n    const std::string & urdf=\"icub/icub.urdf\",\n    const std::vector< std::pair< std::string, std::string > > & packages=('icub_description', 'icub/icub_description')\n) \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 (\n    RobotDARTSimu *\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 (\n    RobotDARTSimu *\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 (\n    size_t frequency=1000,\n    const std::string & urdf=\"iiwa/iiwa.urdf\",\n    const std::vector< std::pair< std::string, std::string > > & packages=('iiwa_description', 'iiwa/iiwa_description')\n) \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 (\n    RobotDARTSimu *\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 (\n    RobotDARTSimu *\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 (\n    const std::string & urdf=\"pendulum.urdf\"\n) \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 __

  • #include <robot_dart/robots/talos.hpp>

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 (\n    size_t frequency=1000,\n    const std::string & urdf=\"talos/talos.urdf\",\n    const std::vector< std::pair< std::string, std::string > > & packages=('talos_description', 'talos/talos_description')\n) \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 (\n    RobotDARTSimu *\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 (\n    RobotDARTSimu *\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 (\n    size_t frequency=1000,\n    const std::string & urdf=\"talos/talos_fast_collision.urdf\",\n    const std::vector< std::pair< std::string, std::string > > & packages=('talos_description', 'talos/talos_description')\n) \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 () \n
"},{"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 (\n    RobotDARTSimu *\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 (\n    size_t frequency=1000,\n    const std::string & urdf=\"talos/talos_fast.urdf\",\n    const std::vector< std::pair< std::string, std::string > > & packages=('talos_description', 'talos/talos_description')\n) \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 __

  • #include <robot_dart/robots/tiago.hpp>

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 (\n    size_t frequency=1000,\n    const std::string & urdf=\"tiago/tiago_steel.urdf\",\n    const std::vector< std::pair< std::string, std::string > > & packages=('tiago_description', 'tiago/tiago_description')\n) \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 (\n    const std::string & type,\n    const std::string & joint_name,\n    bool override_mimic=false,\n    bool override_base=false,\n    bool override_caster=false\n) \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 (\n    const std::string & type,\n    const std::vector< std::string > & joint_names={},\n    bool override_mimic=false,\n    bool override_base=false,\n    bool override_caster=false\n) \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 (\n    RobotDARTSimu *\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 (\n    RobotDARTSimu *\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 (\n    size_t frequency=1000,\n    const std::string & urdf=\"ur3e/ur3e.urdf\",\n    const std::vector< std::pair< std::string, std::string > > & packages=('ur3e_description', 'ur3e/ur3e_description')\n) \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 (\n    RobotDARTSimu *\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 (\n    RobotDARTSimu *\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 (\n    size_t frequency=1000,\n    const std::string & urdf=\"ur3e/ur3e_with_schunk_hand.urdf\",\n    const std::vector< std::pair< std::string, std::string > > & packages=('ur3e_description', 'ur3e/ur3e_description')\n) \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 (\n    const std::string & urdf=\"vx300/vx300.urdf\",\n    const std::vector< std::pair< std::string, std::string > > & packages=('interbotix_xsarm_descriptions', 'vx300')\n) \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 (\n    dart::dynamics::Joint * joint,\n    size_t frequency=1000,\n    const std::string & direction=\"child_to_parent\"\n) \n
"},{"location":"api/classrobot__dart_1_1sensor_1_1ForceTorque/#function-forcetorque-22","title":"function ForceTorque [2/2]","text":"
inline robot_dart::sensor::ForceTorque::ForceTorque (\n    const std::shared_ptr< Robot > & robot,\n    const std::string & joint_name,\n    size_t frequency=1000,\n    const std::string & direction=\"child_to_parent\"\n) \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 (\n    dart::dynamics::BodyNode *,\n    const 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 (\n    double\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 (\n    const IMUConfig & config\n) \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 (\n    dart::dynamics::Joint *,\n    const 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 (\n    double\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 (\n    dart::dynamics::BodyNode * b,\n    size_t f\n) \n
"},{"location":"api/structrobot__dart_1_1sensor_1_1IMUConfig/#function-imuconfig-23","title":"function IMUConfig [\u2154]","text":"
inline robot_dart::sensor::IMUConfig::IMUConfig (\n    const Eigen::Vector3d & gyro_bias,\n    const Eigen::Vector3d & accel_bias,\n    dart::dynamics::BodyNode * b,\n    size_t f\n) \n
"},{"location":"api/structrobot__dart_1_1sensor_1_1IMUConfig/#function-imuconfig-33","title":"function IMUConfig [3/3]","text":"
inline robot_dart::sensor::IMUConfig::IMUConfig () \n

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 (\n    size_t freq=40\n) \n
"},{"location":"api/classrobot__dart_1_1sensor_1_1Sensor/#function-activate","title":"function activate","text":"
void robot_dart::sensor::Sensor::activate (\n    bool enable=true\n) \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 (\n    dart::dynamics::BodyNode * body,\n    const Eigen::Isometry3d & tf=Eigen::Isometry3d::Identity()\n) \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 (\n    const std::shared_ptr< Robot > & robot,\n    const std::string & body_name,\n    const Eigen::Isometry3d & tf=Eigen::Isometry3d::Identity()\n) \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 (\n    dart::dynamics::Joint * joint,\n    const Eigen::Isometry3d & tf=Eigen::Isometry3d::Identity()\n) \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 (\n    const std::shared_ptr< Robot > & robot,\n    const std::string & joint_name,\n    const Eigen::Isometry3d & tf=Eigen::Isometry3d::Identity()\n) \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 (\n    double\n) = 0\n
"},{"location":"api/classrobot__dart_1_1sensor_1_1Sensor/#function-detach","title":"function detach","text":"
void robot_dart::sensor::Sensor::detach () \n
"},{"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 (\n    double t\n) \n
"},{"location":"api/classrobot__dart_1_1sensor_1_1Sensor/#function-set_frequency","title":"function set_frequency","text":"
void robot_dart::sensor::Sensor::set_frequency (\n    size_t freq\n) \n
"},{"location":"api/classrobot__dart_1_1sensor_1_1Sensor/#function-set_pose","title":"function set_pose","text":"
void robot_dart::sensor::Sensor::set_pose (\n    const Eigen::Isometry3d & tf\n) \n
"},{"location":"api/classrobot__dart_1_1sensor_1_1Sensor/#function-set_simu","title":"function set_simu","text":"
void robot_dart::sensor::Sensor::set_simu (\n    RobotDARTSimu * simu\n) \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 () \n
"},{"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 (\n    dart::dynamics::Joint * joint,\n    size_t frequency=1000\n) \n
"},{"location":"api/classrobot__dart_1_1sensor_1_1Torque/#function-torque-22","title":"function Torque [2/2]","text":"
inline robot_dart::sensor::Torque::Torque (\n    const std::shared_ptr< Robot > & robot,\n    const std::string & joint_name,\n    size_t frequency=1000\n) \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 (\n    dart::dynamics::BodyNode *,\n    const 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 (\n    double\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=2<< 2, 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 (\n    const std::string & text,\n    const Eigen::Affine2d & tf=Eigen::Affine2d::Identity(),\n    Eigen::Vector4d color=Eigen::Vector4d(1, 1, 1, 1),\n    std::uint8_t alignment=2<< 2,\n    bool draw_bg=false,\n    Eigen::Vector4d bg_color=Eigen::Vector4d(0, 0, 0, 0.75),\n    double font_size=28\n) \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 (\n    dart::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 (\n    dart::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 (\n    const std::shared_ptr< Robot > & robot\n) \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 (\n    const std::shared_ptr< simu::TextData > & data\n) \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 (\n    size_t index\n) \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 (\n    const std::shared_ptr< Robot > & robot\n) \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::gs","text":"

Namespace List > gs

"},{"location":"api/namespacerobot__dart_1_1gui_1_1magnum_1_1gs_1_1_0d21/#public-types","title":"Public Types","text":"Type Name enum Magnum::Int gs"},{"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-gs","title":"enum gs","text":"
enum gs::gs;\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/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

  • #include \"robot_dart_simu.hpp\"
  • #include \"utils_headers_dart_dynamics.hpp\"
  • #include <unordered_map>
  • #include <vector>
"},{"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\n#include \"robot_dart_simu.hpp\"\n#include \"utils_headers_dart_dynamics.hpp\"\n\n#include <unordered_map>\n#include <vector>\n\nnamespace robot_dart {\n    namespace simu {\n        struct GUIData {\n        private:\n            struct RobotData {\n                bool casting_shadows;\n                bool is_ghost;\n            };\n\n            std::unordered_map<dart::dynamics::ShapeNode*, RobotData> robot_data;\n            std::unordered_map<Robot*, std::vector<std::pair<dart::dynamics::BodyNode*, double>>> robot_axes;\n            std::vector<std::shared_ptr<simu::TextData>> text_drawings;\n\n        public:\n            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 = 2 << 2, bool draw_bg = false, Eigen::Vector4d bg_color = Eigen::Vector4d(0, 0, 0, 0.75), double font_size = 28)\n            {\n                text_drawings.emplace_back(new TextData{text, tf, color, alignment, draw_bg, bg_color, font_size});\n\n                return text_drawings.back();\n            }\n\n            void remove_text(const std::shared_ptr<simu::TextData>& data)\n            {\n                for (size_t i = 0; i < text_drawings.size(); i++) {\n                    if (text_drawings[i] == data) {\n                        text_drawings.erase(text_drawings.begin() + i);\n                        return;\n                    }\n                }\n            }\n\n            void remove_text(size_t index)\n            {\n                if (index >= text_drawings.size())\n                    return;\n                text_drawings.erase(text_drawings.begin() + index);\n            }\n\n            void update_robot(const std::shared_ptr<Robot>& robot)\n            {\n                auto robot_ptr = &*robot;\n                auto skel = robot->skeleton();\n                bool cast = robot->cast_shadows();\n                bool ghost = robot->ghost();\n\n                for (size_t i = 0; i < skel->getNumBodyNodes(); ++i) {\n                    auto bd = skel->getBodyNode(i);\n#if DART_VERSION_AT_LEAST(6, 13, 0)\n                    bd->eachShapeNodeWith<dart::dynamics::VisualAspect>([this, cast, ghost](dart::dynamics::ShapeNode* shapeNode) {\n                        robot_data[shapeNode] = {cast, ghost};\n                    });\n#else\n                    auto& shapes = bd->getShapeNodesWith<dart::dynamics::VisualAspect>();\n                    for (size_t j = 0; j < shapes.size(); j++) {\n                        robot_data[shapes[j]] = {cast, ghost};\n                    }\n#endif\n                }\n\n                auto& axes = robot->drawing_axes();\n                if (axes.size() > 0)\n                    robot_axes[robot_ptr] = axes;\n            }\n\n            void remove_robot(const std::shared_ptr<Robot>& robot)\n            {\n                auto robot_ptr = &*robot;\n                auto skel = robot->skeleton();\n                for (size_t i = 0; i < skel->getNumShapeNodes(); ++i) {\n                    auto shape = skel->getShapeNode(i);\n                    auto shape_iter = robot_data.find(shape);\n                    if (shape_iter != robot_data.end())\n                        robot_data.erase(shape_iter);\n                }\n\n                auto iter = robot_axes.find(robot_ptr);\n                if (iter != robot_axes.end())\n                    robot_axes.erase(iter);\n            }\n\n            bool cast_shadows(dart::dynamics::ShapeNode* shape) const\n            {\n                auto shape_iter = robot_data.find(shape);\n                if (shape_iter != robot_data.end())\n                    return robot_data.at(shape).casting_shadows;\n                // if not in the array, cast shadow by default\n                return true;\n            }\n\n            bool ghost(dart::dynamics::ShapeNode* shape) const\n            {\n                auto shape_iter = robot_data.find(shape);\n                if (shape_iter != robot_data.end())\n                    return robot_data.at(shape).is_ghost;\n                // if not in the array, the robot is not ghost by default\n                return false;\n            }\n\n            std::vector<std::pair<dart::dynamics::BodyNode*, double>> drawing_axes() const\n            {\n                std::vector<std::pair<dart::dynamics::BodyNode*, double>> axes;\n                for (std::pair<Robot*, std::vector<std::pair<dart::dynamics::BodyNode*, double>>> elem : robot_axes) {\n                    axes.insert(axes.end(), elem.second.begin(), elem.second.end());\n                }\n\n                return axes;\n            }\n\n            const std::vector<std::shared_ptr<simu::TextData>>& drawing_texts() const { return text_drawings; }\n        };\n    } // namespace simu\n} // namespace robot_dart\n\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

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

  • #include <unordered_map>
  • #include <robot_dart/utils.hpp>
"},{"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\n#include <unordered_map>\n\n#include <robot_dart/utils.hpp>\n\nnamespace robot_dart {\n    class RobotDARTSimu;\n    namespace control {\n        class RobotControl;\n    }\n\n    class Robot : public std::enable_shared_from_this<Robot> {\n    public:\n        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);\n        Robot(const std::string& model_file, const std::string& robot_name = \"robot\", bool is_urdf_string = false, bool cast_shadows = true);\n        Robot(dart::dynamics::SkeletonPtr skeleton, const std::string& robot_name = \"robot\", bool cast_shadows = true);\n        virtual ~Robot() {}\n\n        std::shared_ptr<Robot> clone() const;\n        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;\n\n        dart::dynamics::SkeletonPtr skeleton();\n        dart::dynamics::BodyNode* body_node(const std::string& body_name);\n        dart::dynamics::BodyNode* body_node(size_t body_index);\n\n        dart::dynamics::Joint* joint(const std::string& joint_name);\n        dart::dynamics::Joint* joint(size_t joint_index);\n\n        dart::dynamics::DegreeOfFreedom* dof(const std::string& dof_name);\n        dart::dynamics::DegreeOfFreedom* dof(size_t dof_index);\n\n        const std::string& name() const;\n        // to use the same urdf somewhere else\n        const std::string& model_filename() const { return _model_filename; }\n        const std::vector<std::pair<std::string, std::string>>& model_packages() const { return _packages; }\n\n        void update(double t);\n\n        void reinit_controllers();\n\n        size_t num_controllers() const;\n        std::vector<std::shared_ptr<control::RobotControl>> controllers() const;\n        std::vector<std::shared_ptr<control::RobotControl>> active_controllers() const;\n\n        std::shared_ptr<control::RobotControl> controller(size_t index) const;\n\n        void add_controller(\n            const std::shared_ptr<control::RobotControl>& controller, double weight = 1.0);\n        void remove_controller(const std::shared_ptr<control::RobotControl>& controller);\n        void remove_controller(size_t index);\n        void clear_controllers();\n\n        void fix_to_world();\n        // pose: Orientation-Position\n        void free_from_world(const Eigen::Vector6d& pose = Eigen::Vector6d::Zero());\n\n        bool fixed() const;\n        bool free() const;\n\n        virtual void reset();\n\n        void clear_external_forces();\n        void clear_internal_forces();\n        void reset_commands();\n\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\n        void set_actuator_types(const std::string& type, const std::vector<std::string>& joint_names = {}, bool override_mimic = false, bool override_base = false);\n        void set_actuator_type(const std::string& type, const std::string& joint_name, bool override_mimic = false, bool override_base = false);\n        void set_mimic(const std::string& joint_name, const std::string& mimic_joint_name, double multiplier = 1., double offset = 0.);\n\n        std::string actuator_type(const std::string& joint_name) const;\n        std::vector<std::string> actuator_types(const std::vector<std::string>& joint_names = {}) const;\n\n        void set_position_enforced(const std::vector<bool>& enforced, const std::vector<std::string>& dof_names = {});\n        void set_position_enforced(bool enforced, const std::vector<std::string>& dof_names = {});\n\n        std::vector<bool> position_enforced(const std::vector<std::string>& dof_names = {}) const;\n\n        void force_position_bounds();\n\n        void set_damping_coeffs(const std::vector<double>& damps, const std::vector<std::string>& dof_names = {});\n        void set_damping_coeffs(double damp, const std::vector<std::string>& dof_names = {});\n\n        std::vector<double> damping_coeffs(const std::vector<std::string>& dof_names = {}) const;\n\n        void set_coulomb_coeffs(const std::vector<double>& cfrictions, const std::vector<std::string>& dof_names = {});\n        void set_coulomb_coeffs(double cfriction, const std::vector<std::string>& dof_names = {});\n\n        std::vector<double> coulomb_coeffs(const std::vector<std::string>& dof_names = {}) const;\n\n        void set_spring_stiffnesses(const std::vector<double>& stiffnesses, const std::vector<std::string>& dof_names = {});\n        void set_spring_stiffnesses(double stiffness, const std::vector<std::string>& dof_names = {});\n\n        std::vector<double> spring_stiffnesses(const std::vector<std::string>& dof_names = {}) const;\n\n        // the friction direction is in local frame\n        void set_friction_dir(const std::string& body_name, const Eigen::Vector3d& direction);\n        void set_friction_dir(size_t body_index, const Eigen::Vector3d& direction);\n        Eigen::Vector3d friction_dir(const std::string& body_name);\n        Eigen::Vector3d friction_dir(size_t body_index);\n\n        void set_friction_coeff(const std::string& body_name, double value);\n        void set_friction_coeff(size_t body_index, double value);\n        void set_friction_coeffs(double value);\n        double friction_coeff(const std::string& body_name);\n        double friction_coeff(size_t body_index);\n\n        void set_secondary_friction_coeff(const std::string& body_name, double value);\n        void set_secondary_friction_coeff(size_t body_index, double value);\n        void set_secondary_friction_coeffs(double value);\n        double secondary_friction_coeff(const std::string& body_name);\n        double secondary_friction_coeff(size_t body_index);\n\n        void set_restitution_coeff(const std::string& body_name, double value);\n        void set_restitution_coeff(size_t body_index, double value);\n        void set_restitution_coeffs(double value);\n        double restitution_coeff(const std::string& body_name);\n        double restitution_coeff(size_t body_index);\n\n        Eigen::Isometry3d base_pose() const;\n        Eigen::Vector6d base_pose_vec() const;\n        void set_base_pose(const Eigen::Isometry3d& tf);\n        void set_base_pose(const Eigen::Vector6d& pose);\n\n        size_t num_dofs() const;\n        size_t num_joints() const;\n        size_t num_bodies() const;\n\n        Eigen::Vector3d com() const;\n        Eigen::Vector6d com_velocity() const;\n        Eigen::Vector6d com_acceleration() const;\n\n        Eigen::VectorXd positions(const std::vector<std::string>& dof_names = {}) const;\n        void set_positions(const Eigen::VectorXd& positions, const std::vector<std::string>& dof_names = {});\n\n        Eigen::VectorXd position_lower_limits(const std::vector<std::string>& dof_names = {}) const;\n        void set_position_lower_limits(const Eigen::VectorXd& positions, const std::vector<std::string>& dof_names = {});\n        Eigen::VectorXd position_upper_limits(const std::vector<std::string>& dof_names = {}) const;\n        void set_position_upper_limits(const Eigen::VectorXd& positions, const std::vector<std::string>& dof_names = {});\n\n        Eigen::VectorXd velocities(const std::vector<std::string>& dof_names = {}) const;\n        void set_velocities(const Eigen::VectorXd& velocities, const std::vector<std::string>& dof_names = {});\n\n        Eigen::VectorXd velocity_lower_limits(const std::vector<std::string>& dof_names = {}) const;\n        void set_velocity_lower_limits(const Eigen::VectorXd& velocities, const std::vector<std::string>& dof_names = {});\n        Eigen::VectorXd velocity_upper_limits(const std::vector<std::string>& dof_names = {}) const;\n        void set_velocity_upper_limits(const Eigen::VectorXd& velocities, const std::vector<std::string>& dof_names = {});\n\n        Eigen::VectorXd accelerations(const std::vector<std::string>& dof_names = {}) const;\n        void set_accelerations(const Eigen::VectorXd& accelerations, const std::vector<std::string>& dof_names = {});\n\n        Eigen::VectorXd acceleration_lower_limits(const std::vector<std::string>& dof_names = {}) const;\n        void set_acceleration_lower_limits(const Eigen::VectorXd& accelerations, const std::vector<std::string>& dof_names = {});\n        Eigen::VectorXd acceleration_upper_limits(const std::vector<std::string>& dof_names = {}) const;\n        void set_acceleration_upper_limits(const Eigen::VectorXd& accelerations, const std::vector<std::string>& dof_names = {});\n\n        Eigen::VectorXd forces(const std::vector<std::string>& dof_names = {}) const;\n        void set_forces(const Eigen::VectorXd& forces, const std::vector<std::string>& dof_names = {});\n\n        Eigen::VectorXd force_lower_limits(const std::vector<std::string>& dof_names = {}) const;\n        void set_force_lower_limits(const Eigen::VectorXd& forces, const std::vector<std::string>& dof_names = {});\n        Eigen::VectorXd force_upper_limits(const std::vector<std::string>& dof_names = {}) const;\n        void set_force_upper_limits(const Eigen::VectorXd& forces, const std::vector<std::string>& dof_names = {});\n\n        Eigen::VectorXd commands(const std::vector<std::string>& dof_names = {}) const;\n        void set_commands(const Eigen::VectorXd& commands, const std::vector<std::string>& dof_names = {});\n\n        std::pair<Eigen::Vector6d, Eigen::Vector6d> force_torque(size_t joint_index) const;\n\n        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);\n        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);\n        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);\n        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);\n\n        void set_external_torque(const std::string& body_name, const Eigen::Vector3d& torque, bool local = false);\n        void set_external_torque(size_t body_index, const Eigen::Vector3d& torque, bool local = false);\n        void add_external_torque(const std::string& body_name, const Eigen::Vector3d& torque, bool local = false);\n        void add_external_torque(size_t body_index, const Eigen::Vector3d& torque, bool local = false);\n\n        Eigen::Vector6d external_forces(const std::string& body_name) const;\n        Eigen::Vector6d external_forces(size_t body_index) const;\n\n        Eigen::Isometry3d body_pose(const std::string& body_name) const;\n        Eigen::Isometry3d body_pose(size_t body_index) const;\n\n        Eigen::Vector6d body_pose_vec(const std::string& body_name) const;\n        Eigen::Vector6d body_pose_vec(size_t body_index) const;\n\n        Eigen::Vector6d body_velocity(const std::string& body_name) const;\n        Eigen::Vector6d body_velocity(size_t body_index) const;\n\n        Eigen::Vector6d body_acceleration(const std::string& body_name) const;\n        Eigen::Vector6d body_acceleration(size_t body_index) const;\n\n        std::vector<std::string> body_names() const;\n        std::string body_name(size_t body_index) const;\n        void set_body_name(size_t body_index, const std::string& body_name);\n        size_t body_index(const std::string& body_name) const;\n\n        double body_mass(const std::string& body_name) const;\n        double body_mass(size_t body_index) const;\n        void set_body_mass(const std::string& body_name, double mass);\n        void set_body_mass(size_t body_index, double mass);\n        void add_body_mass(const std::string& body_name, double mass);\n        void add_body_mass(size_t body_index, double mass);\n\n        Eigen::MatrixXd jacobian(const std::string& body_name, const std::vector<std::string>& dof_names = {}) const;\n        Eigen::MatrixXd jacobian_deriv(const std::string& body_name, const std::vector<std::string>& dof_names = {}) const;\n\n        Eigen::MatrixXd com_jacobian(const std::vector<std::string>& dof_names = {}) const;\n        Eigen::MatrixXd com_jacobian_deriv(const std::vector<std::string>& dof_names = {}) const;\n\n        Eigen::MatrixXd mass_matrix(const std::vector<std::string>& dof_names = {}) const;\n        Eigen::MatrixXd aug_mass_matrix(const std::vector<std::string>& dof_names = {}) const;\n        Eigen::MatrixXd inv_mass_matrix(const std::vector<std::string>& dof_names = {}) const;\n        Eigen::MatrixXd inv_aug_mass_matrix(const std::vector<std::string>& dof_names = {}) const;\n\n        Eigen::VectorXd coriolis_forces(const std::vector<std::string>& dof_names = {}) const;\n        Eigen::VectorXd gravity_forces(const std::vector<std::string>& dof_names = {}) const;\n        Eigen::VectorXd coriolis_gravity_forces(const std::vector<std::string>& dof_names = {}) const;\n        Eigen::VectorXd constraint_forces(const std::vector<std::string>& dof_names = {}) const;\n\n        // Get only the part of vector for DOFs in dof_names\n        Eigen::VectorXd vec_dof(const Eigen::VectorXd& vec, const std::vector<std::string>& dof_names) const;\n\n        void update_joint_dof_maps();\n        const std::unordered_map<std::string, size_t>& dof_map() const;\n        const std::unordered_map<std::string, size_t>& joint_map() const;\n\n        std::vector<std::string> dof_names(bool filter_mimics = false, bool filter_locked = false, bool filter_passive = false) const;\n        std::vector<std::string> mimic_dof_names() const;\n        std::vector<std::string> locked_dof_names() const;\n        std::vector<std::string> passive_dof_names() const;\n        std::string dof_name(size_t dof_index) const;\n        size_t dof_index(const std::string& dof_name) const;\n\n        std::vector<std::string> joint_names() const;\n        std::string joint_name(size_t joint_index) const;\n        void set_joint_name(size_t joint_index, const std::string& joint_name);\n        size_t joint_index(const std::string& joint_name) const;\n\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)\n        void set_color_mode(const std::string& color_mode);\n        void set_color_mode(const std::string& color_mode, const std::string& body_name);\n\n        void set_self_collision(bool enable_self_collisions = true, bool enable_adjacent_collisions = false);\n        bool self_colliding() const;\n        // This returns true if self colliding AND adjacent checks are on\n        bool adjacent_colliding() const;\n\n        // GUI options\n        void set_cast_shadows(bool cast_shadows = true);\n        bool cast_shadows() const;\n\n        void set_ghost(bool ghost = true);\n        bool ghost() const;\n\n        void set_draw_axis(const std::string& body_name, double size = 0.25);\n        void remove_all_drawing_axis();\n        const std::vector<std::pair<dart::dynamics::BodyNode*, double>>& drawing_axes() const;\n\n        // helper functions\n        static std::shared_ptr<Robot> create_box(const Eigen::Vector3d& dims,\n            const Eigen::Isometry3d& tf, const std::string& type = \"free\",\n            double mass = 1.0, const Eigen::Vector4d& color = dart::Color::Red(1.0),\n            const std::string& box_name = \"box\");\n        // pose: 6D log_map\n        static std::shared_ptr<Robot> create_box(const Eigen::Vector3d& dims,\n            const Eigen::Vector6d& pose = Eigen::Vector6d::Zero(), const std::string& type = \"free\",\n            double mass = 1.0, const Eigen::Vector4d& color = dart::Color::Red(1.0),\n            const std::string& box_name = \"box\");\n\n        static std::shared_ptr<Robot> create_ellipsoid(const Eigen::Vector3d& dims,\n            const Eigen::Isometry3d& tf, const std::string& type = \"free\",\n            double mass = 1.0, const Eigen::Vector4d& color = dart::Color::Red(1.0),\n            const std::string& ellipsoid_name = \"ellipsoid\");\n        // pose: 6D log_map\n        static std::shared_ptr<Robot> create_ellipsoid(const Eigen::Vector3d& dims,\n            const Eigen::Vector6d& pose = Eigen::Vector6d::Zero(), const std::string& type = \"free\",\n            double mass = 1.0, const Eigen::Vector4d& color = dart::Color::Red(1.0),\n            const std::string& ellipsoid_name = \"ellipsoid\");\n\n    protected:\n        std::string _get_path(const std::string& filename) const;\n        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);\n\n        void _set_color_mode(dart::dynamics::MeshShape::ColorMode color_mode, dart::dynamics::SkeletonPtr skel);\n        void _set_color_mode(dart::dynamics::MeshShape::ColorMode color_mode, dart::dynamics::ShapeNode* sn);\n        void _set_actuator_type(size_t joint_index, dart::dynamics::Joint::ActuatorType type, bool override_mimic = false, bool override_base = false);\n        void _set_actuator_types(const std::vector<dart::dynamics::Joint::ActuatorType>& types, bool override_mimic = false, bool override_base = false);\n        void _set_actuator_types(dart::dynamics::Joint::ActuatorType type, bool override_mimic = false, bool override_base = false);\n\n        dart::dynamics::Joint::ActuatorType _actuator_type(size_t joint_index) const;\n        std::vector<dart::dynamics::Joint::ActuatorType> _actuator_types() const;\n\n        Eigen::MatrixXd _jacobian(const Eigen::MatrixXd& full_jacobian, const std::vector<std::string>& dof_names) const;\n        Eigen::MatrixXd _mass_matrix(const Eigen::MatrixXd& full_mass_matrix, const std::vector<std::string>& dof_names) const;\n\n        virtual void _post_addition(RobotDARTSimu*) {}\n        virtual void _post_removal(RobotDARTSimu*) {}\n\n        friend class RobotDARTSimu;\n\n        std::string _robot_name;\n        std::string _model_filename;\n        std::vector<std::pair<std::string, std::string>> _packages;\n        dart::dynamics::SkeletonPtr _skeleton;\n        std::vector<std::shared_ptr<control::RobotControl>> _controllers;\n        std::unordered_map<std::string, size_t> _dof_map, _joint_map;\n        bool _cast_shadows;\n        bool _is_ghost;\n        std::vector<std::pair<dart::dynamics::BodyNode*, double>> _axis_shapes;\n    };\n} // namespace robot_dart\n\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

  • #include \"pd_control.hpp\"
  • #include \"robot_dart/robot.hpp\"
  • #include \"robot_dart/utils.hpp\"
  • #include \"robot_dart/utils_headers_dart_dynamics.hpp\"
"},{"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\"\n\nnamespace robot_dart {\n    namespace control {\n        PDControl::PDControl() : RobotControl() {}\n        PDControl::PDControl(const Eigen::VectorXd& ctrl, bool full_control, bool use_angular_errors) : RobotControl(ctrl, full_control), _use_angular_errors(use_angular_errors) {}\n        PDControl::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) {}\n\n        void PDControl::configure()\n        {\n            if (_ctrl.size() == _control_dof)\n                _active = true;\n\n            if (_Kp.size() == 0)\n                set_pd(10., 0.1);\n        }\n\n        Eigen::VectorXd PDControl::calculate(double)\n        {\n            ROBOT_DART_ASSERT(_control_dof == _ctrl.size(), \"PDControl: Controller parameters size is not the same as DOFs of the robot\", Eigen::VectorXd::Zero(_control_dof));\n            auto robot = _robot.lock();\n\n            Eigen::VectorXd dq = robot->velocities(_controllable_dofs);\n\n            Eigen::VectorXd error;\n            if (!_use_angular_errors) {\n                Eigen::VectorXd q = robot->positions(_controllable_dofs);\n                error = _ctrl - q;\n            }\n            else {\n                error = Eigen::VectorXd::Zero(_control_dof);\n\n                std::unordered_map<size_t, Eigen::VectorXd> joint_vals, joint_desired, errors;\n\n                for (int i = 0; i < _control_dof; ++i) {\n                    auto dof = robot->dof(_controllable_dofs[i]);\n                    size_t joint_index = dof->getJoint()->getJointIndexInSkeleton();\n                    if (joint_vals.find(joint_index) == joint_vals.end()) {\n                        joint_vals[joint_index] = dof->getJoint()->getPositions();\n                        joint_desired[joint_index] = dof->getJoint()->getPositions();\n                    }\n\n                    joint_desired[joint_index][dof->getIndexInJoint()] = _ctrl[i];\n                }\n\n                for (int i = 0; i < _control_dof; ++i) {\n                    auto dof = robot->dof(_controllable_dofs[i]);\n                    size_t joint_index = dof->getJoint()->getJointIndexInSkeleton();\n                    size_t dof_index_in_joint = dof->getIndexInJoint();\n\n                    Eigen::VectorXd val;\n                    if (errors.find(joint_index) == errors.end()) {\n                        val = Eigen::VectorXd(dof->getJoint()->getNumDofs());\n\n                        std::string joint_type = robot->dof(_controllable_dofs[i])->getJoint()->getType();\n                        if (joint_type == dart::dynamics::RevoluteJoint::getStaticType()) {\n                            val[dof_index_in_joint] = _angle_dist(_ctrl[i], joint_vals[joint_index][dof_index_in_joint]);\n                        }\n                        else if (joint_type == dart::dynamics::BallJoint::getStaticType()) {\n                            Eigen::Matrix3d R_desired = dart::math::expMapRot(joint_desired[joint_index]);\n                            Eigen::Matrix3d R_current = dart::math::expMapRot(joint_vals[joint_index]);\n                            val = dart::math::logMap(R_desired * R_current.transpose());\n                        }\n                        else if (joint_type == dart::dynamics::EulerJoint::getStaticType()) {\n                            // TO-DO: Check if this is 100% correct\n                            for (size_t d = 0; d < dof->getJoint()->getNumDofs(); d++)\n                                val[d] = _angle_dist(joint_desired[joint_index][d], joint_vals[joint_index][d]);\n                        }\n                        else if (joint_type == dart::dynamics::FreeJoint::getStaticType()) {\n                            auto free_joint = static_cast<dart::dynamics::FreeJoint*>(dof->getJoint());\n\n                            Eigen::Isometry3d tf_desired = free_joint->convertToTransform(joint_desired[joint_index]);\n                            Eigen::Isometry3d tf_current = free_joint->convertToTransform(joint_vals[joint_index]);\n\n                            val.tail(3) = tf_desired.translation() - tf_current.translation();\n                            val.head(3) = dart::math::logMap(tf_desired.linear().matrix() * tf_current.linear().matrix().transpose());\n                        }\n                        else {\n                            val[dof_index_in_joint] = _ctrl[i] - joint_vals[joint_index][dof_index_in_joint];\n                        }\n\n                        errors[joint_index] = val;\n                    }\n                    else\n                        val = errors[joint_index];\n                    error(i) = val[dof_index_in_joint];\n                }\n            }\n\n            Eigen::VectorXd commands = _Kp.array() * error.array() - _Kd.array() * dq.array();\n\n            return commands;\n        }\n\n        void 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        }\n\n        void PDControl::set_pd(const Eigen::VectorXd& Kp, const Eigen::VectorXd& Kd)\n        {\n            ROBOT_DART_ASSERT(Kp.size() == _control_dof, \"PDControl: The Kp size is not the same as the DOFs!\", );\n            ROBOT_DART_ASSERT(Kd.size() == _control_dof, \"PDControl: The Kd size is not the same as the DOFs!\", );\n            _Kp = Kp;\n            _Kd = Kd;\n        }\n\n        std::pair<Eigen::VectorXd, Eigen::VectorXd> PDControl::pd() const\n        {\n            return std::make_pair(_Kp, _Kd);\n        }\n\n        bool PDControl::using_angular_errors() const { return _use_angular_errors; }\n\n        void PDControl::set_use_angular_errors(bool enable) { _use_angular_errors = enable; }\n\n        std::shared_ptr<RobotControl> PDControl::clone() const\n        {\n            return std::make_shared<PDControl>(*this);\n        }\n\n        double PDControl::_angle_dist(double target, double current)\n        {\n            double theta = target - current;\n            while (theta < -M_PI)\n                theta += 2 * M_PI;\n            while (theta > M_PI)\n                theta -= 2 * M_PI;\n            return 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

  • #include <utility>
  • #include <robot_dart/control/robot_control.hpp>
  • #include <robot_dart/robot.hpp>
"},{"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\n#include <utility>\n\n#include <robot_dart/control/robot_control.hpp>\n#include <robot_dart/robot.hpp>\n\nnamespace robot_dart {\n    namespace control {\n\n        class PDControl : public RobotControl {\n        public:\n            PDControl();\n            PDControl(const Eigen::VectorXd& ctrl, bool full_control = false, bool use_angular_errors = true);\n            PDControl(const Eigen::VectorXd& ctrl, const std::vector<std::string>& controllable_dofs, bool use_angular_errors = true);\n\n            void configure() override;\n            Eigen::VectorXd calculate(double) override;\n\n            void set_pd(double p, double d);\n            void set_pd(const Eigen::VectorXd& p, const Eigen::VectorXd& d);\n\n            std::pair<Eigen::VectorXd, Eigen::VectorXd> pd() const;\n\n            bool using_angular_errors() const;\n            void set_use_angular_errors(bool enable = true);\n\n            std::shared_ptr<RobotControl> clone() const override;\n\n        protected:\n            Eigen::VectorXd _Kp;\n            Eigen::VectorXd _Kd;\n            bool _use_angular_errors;\n\n            static 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

  • #include <robot_dart/control/robot_control.hpp>
  • #include <robot_dart/robot.hpp>
"},{"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\n#include <robot_dart/control/robot_control.hpp>\n#include <robot_dart/robot.hpp>\n\nnamespace robot_dart {\n    namespace control {\n\n        template <typename Policy>\n        class PolicyControl : public RobotControl {\n        public:\n            PolicyControl() : RobotControl() {}\n            PolicyControl(double dt, const Eigen::VectorXd& ctrl, bool full_control = false) : RobotControl(ctrl, full_control), _dt(dt), _first(true), _full_dt(false) {}\n            PolicyControl(const Eigen::VectorXd& ctrl, bool full_control = false) : RobotControl(ctrl, full_control), _dt(0.), _first(true), _full_dt(true) {}\n            PolicyControl(double dt, const Eigen::VectorXd& ctrl, const std::vector<std::string>& controllable_dofs) : RobotControl(ctrl, controllable_dofs), _dt(dt), _first(true), _full_dt(false) {}\n            PolicyControl(const Eigen::VectorXd& ctrl, const std::vector<std::string>& controllable_dofs) : RobotControl(ctrl, controllable_dofs), _dt(0.), _first(true), _full_dt(true) {}\n\n            void configure() override\n            {\n                _policy.set_params(_ctrl);\n                if (_policy.output_size() == _control_dof)\n                    _active = true;\n                else\n                    ROBOT_DART_WARNING(_policy.output_size() != _control_dof, \"Control DoF != Policy output size. Policy is not active.\");\n                auto robot = _robot.lock();\n                if (_full_dt)\n                    _dt = robot->skeleton()->getTimeStep();\n                _first = true;\n                _i = 0;\n                _threshold = -robot->skeleton()->getTimeStep() * 0.5;\n            }\n\n            void set_h_params(const Eigen::VectorXd& h_params)\n            {\n                _policy.set_h_params(h_params);\n            }\n\n            Eigen::VectorXd h_params() const\n            {\n                return _policy.h_params();\n            }\n\n            Eigen::VectorXd calculate(double t) override\n            {\n                ROBOT_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));\n                if (_first || _full_dt || (t - _prev_time - _dt) >= _threshold) {\n                    _prev_commands = _policy.query(_robot.lock(), t);\n\n                    _first = false;\n                    _prev_time = t;\n                    _i++;\n                }\n\n                return _prev_commands;\n            }\n\n            std::shared_ptr<RobotControl> clone() const override\n            {\n                return std::make_shared<PolicyControl>(*this);\n            }\n\n        protected:\n            int _i;\n            Policy _policy;\n            double _dt, _prev_time, _threshold;\n            Eigen::VectorXd _prev_commands;\n            bool _first, _full_dt;\n        };\n    } // namespace control\n} // namespace robot_dart\n\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

  • #include \"robot_control.hpp\"
  • #include \"robot_dart/robot.hpp\"
  • #include \"robot_dart/utils.hpp\"
  • #include \"robot_dart/utils_headers_dart_dynamics.hpp\"
"},{"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\"\n\nnamespace robot_dart {\n    namespace control {\n        RobotControl::RobotControl() : _weight(1.), _active(false), _check_free(true) {}\n        RobotControl::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) {}\n        RobotControl::RobotControl(const Eigen::VectorXd& ctrl, bool full_control) : _ctrl(ctrl), _weight(1.), _active(false), _check_free(!full_control) {}\n\n        void RobotControl::set_parameters(const Eigen::VectorXd& ctrl)\n        {\n            _ctrl = ctrl;\n            _active = false;\n            init();\n        }\n\n        const Eigen::VectorXd& RobotControl::parameters() const\n        {\n            return _ctrl;\n        }\n\n        void RobotControl::init()\n        {\n            ROBOT_DART_ASSERT(_robot.use_count() > 0, \"RobotControl: parent robot should be initialized; use set_robot()\", );\n            auto robot = _robot.lock();\n            _dof = robot->skeleton()->getNumDofs();\n\n            if (_check_free && robot->free()) {\n                auto names = robot->dof_names(true, true, true);\n                _controllable_dofs = std::vector<std::string>(names.begin() + 6, names.end());\n            }\n            else if (_controllable_dofs.empty()) {\n                // we cannot control mimic, locked and passive joints\n                _controllable_dofs = robot->dof_names(true, true, true);\n            }\n\n            _control_dof = _controllable_dofs.size();\n\n            configure();\n        }\n\n        void RobotControl::set_robot(const std::shared_ptr<Robot>& robot)\n        {\n            _robot = robot;\n        }\n\n        std::shared_ptr<Robot> RobotControl::robot() const\n        {\n            return _robot.lock();\n        }\n\n        void RobotControl::activate(bool enable)\n        {\n            _active = false;\n            if (enable) {\n                init();\n            }\n        }\n\n        bool RobotControl::active() const\n        {\n            return _active;\n        }\n\n        const std::vector<std::string>& RobotControl::controllable_dofs() const { return _controllable_dofs; }\n\n        double RobotControl::weight() const\n        {\n            return _weight;\n        }\n\n        void 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

  • #include <robot_dart/utils.hpp>
  • #include <memory>
  • #include <vector>
"},{"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\n#include <robot_dart/utils.hpp>\n\n#include <memory>\n#include <vector>\n\nnamespace robot_dart {\n    class Robot;\n\n    namespace control {\n\n        class RobotControl {\n        public:\n            RobotControl();\n            RobotControl(const Eigen::VectorXd& ctrl, bool full_control = false);\n            RobotControl(const Eigen::VectorXd& ctrl, const std::vector<std::string>& controllable_dofs);\n            virtual ~RobotControl() {}\n\n            void set_parameters(const Eigen::VectorXd& ctrl);\n            const Eigen::VectorXd& parameters() const;\n\n            void init();\n\n            void set_robot(const std::shared_ptr<Robot>& robot);\n            std::shared_ptr<Robot> robot() const;\n\n            void activate(bool enable = true);\n            bool active() const;\n\n            const std::vector<std::string>& controllable_dofs() const;\n\n            double weight() const;\n            void set_weight(double weight);\n\n            virtual void configure() = 0;\n            // TO-DO: Maybe make this const?\n            virtual Eigen::VectorXd calculate(double t) = 0;\n            virtual std::shared_ptr<RobotControl> clone() const = 0;\n\n        protected:\n            std::weak_ptr<Robot> _robot;\n            Eigen::VectorXd _ctrl;\n            double _weight;\n            bool _active, _check_free = false;\n            int _dof, _control_dof;\n            std::vector<std::string> _controllable_dofs;\n        };\n    } // namespace control\n} // namespace robot_dart\n\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

  • #include \"simple_control.hpp\"
  • #include \"robot_dart/robot.hpp\"
  • #include \"robot_dart/utils.hpp\"
"},{"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\"\n\nnamespace robot_dart {\n    namespace control {\n        SimpleControl::SimpleControl() : RobotControl() {}\n        SimpleControl::SimpleControl(const Eigen::VectorXd& ctrl, bool full_control) : RobotControl(ctrl, full_control) {}\n        SimpleControl::SimpleControl(const Eigen::VectorXd& ctrl, const std::vector<std::string>& controllable_dofs) : RobotControl(ctrl, controllable_dofs) {}\n\n        void SimpleControl::configure()\n        {\n            if (_ctrl.size() == _control_dof)\n                _active = true;\n        }\n\n        Eigen::VectorXd SimpleControl::calculate(double)\n        {\n            ROBOT_DART_ASSERT(_control_dof == _ctrl.size(), \"SimpleControl: Controller parameters size is not the same as DOFs of the robot\", Eigen::VectorXd::Zero(_control_dof));\n            return _ctrl;\n        }\n\n        std::shared_ptr<RobotControl> SimpleControl::clone() const\n        {\n            return 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

  • #include <robot_dart/control/robot_control.hpp>
"},{"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\n#include <robot_dart/control/robot_control.hpp>\n\nnamespace robot_dart {\n    namespace control {\n\n        class SimpleControl : public RobotControl {\n        public:\n            SimpleControl();\n            SimpleControl(const Eigen::VectorXd& ctrl, bool full_control = false);\n            SimpleControl(const Eigen::VectorXd& ctrl, const std::vector<std::string>& controllable_dofs);\n\n            void configure() override;\n            Eigen::VectorXd calculate(double) override;\n            std::shared_ptr<RobotControl> clone() const override;\n        };\n    } // namespace control\n} // namespace robot_dart\n\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

  • #include <robot_dart/gui/helper.hpp>
"},{"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\n#include <robot_dart/gui/helper.hpp>\n\nnamespace robot_dart {\n    class RobotDARTSimu;\n\n    namespace gui {\n        class Base {\n        public:\n            Base() {}\n\n            virtual ~Base() {}\n\n            virtual void set_simu(RobotDARTSimu* simu) { _simu = simu; }\n            const RobotDARTSimu* simu() const { return _simu; }\n\n            virtual bool done() const { return false; }\n\n            virtual void refresh() {}\n\n            virtual void set_render_period(double) {}\n\n            virtual void set_enable(bool) {}\n            virtual void set_fps(int) {}\n\n            virtual Image image() { return Image(); }\n            virtual GrayscaleImage depth_image() { return GrayscaleImage(); }\n            virtual GrayscaleImage raw_depth_image() { return GrayscaleImage(); }\n            virtual DepthImage depth_array() { return DepthImage(); }\n\n            virtual size_t width() const { return 0; }\n            virtual size_t height() const { return 0; }\n\n        protected:\n            RobotDARTSimu* _simu = nullptr;\n        };\n    } // namespace gui\n} // namespace robot_dart\n\n#endif\n
"},{"location":"api/helper_8cpp/","title":"File helper.cpp","text":"

FileList > gui > helper.cpp

Go to the source code of this file

  • #include \"helper.hpp\"
  • #include \"stb_image_write.h\"
"},{"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\n#define STB_IMAGE_WRITE_IMPLEMENTATION\n#include \"stb_image_write.h\"\n\nnamespace robot_dart {\n    namespace gui {\n        void save_png_image(const std::string& filename, const Image& rgb)\n        {\n            auto ends_with = [](const std::string& value, const std::string& ending) {\n                if (ending.size() > value.size())\n                    return false;\n                return std::equal(ending.rbegin(), ending.rend(), value.rbegin());\n            };\n\n            std::string png = \".png\";\n            if (ends_with(filename, png))\n                png = \"\";\n\n            stbi_write_png((filename + png).c_str(), rgb.width, rgb.height, rgb.channels, rgb.data.data(), rgb.width * rgb.channels);\n        }\n\n        void save_png_image(const std::string& filename, const GrayscaleImage& gray)\n        {\n            auto ends_with = [](const std::string& value, const std::string& ending) {\n                if (ending.size() > value.size())\n                    return false;\n                return std::equal(ending.rbegin(), ending.rend(), value.rbegin());\n            };\n\n            std::string png = \".png\";\n            if (ends_with(filename, png))\n                png = \"\";\n\n            stbi_write_png((filename + png).c_str(), gray.width, gray.height, 1, gray.data.data(), gray.width);\n        }\n\n        GrayscaleImage convert_rgb_to_grayscale(const Image& rgb)\n        {\n            assert(rgb.channels == 3);\n            size_t width = rgb.width;\n            size_t height = rgb.height;\n\n            GrayscaleImage gray;\n            gray.width = width;\n            gray.height = height;\n            gray.data.resize(width * height);\n\n            for (size_t h = 0; h < height; h++) {\n                for (size_t w = 0; w < width; w++) {\n                    int id = w + h * width;\n                    int id_rgb = w * rgb.channels + h * (width * rgb.channels);\n                    uint8_t color = 0.3 * rgb.data[id_rgb + 0] + 0.59 * rgb.data[id_rgb + 1] + 0.11 * rgb.data[id_rgb + 2];\n                    gray.data[id] = color;\n                }\n            }\n\n            return gray;\n        }\n\n        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)\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/.\n            auto point_3d = [](const Eigen::Matrix3d& K, size_t u, size_t v, double depth) {\n                double fx = K(0, 0);\n                double fy = K(1, 1);\n                double cx = K(0, 2);\n                double cy = K(1, 2);\n                double gamma = K(0, 1);\n\n                Eigen::Vector3d p;\n                p << 0., 0., -depth;\n\n                p(1) = (cy - v) * depth / fy;\n                p(0) = -((cx - u) * depth - gamma * p(1)) / fx;\n\n                return p;\n            };\n\n            std::vector<Eigen::Vector3d> point_cloud;\n\n            size_t height = depth_image.height;\n            size_t width = depth_image.width;\n            for (size_t h = 0; h < height; h++) {\n                for (size_t w = 0; w < width; w++) {\n                    int id = w + h * width;\n                    if (depth_image.data[id] >= 0.99 * far_plane) // close to far plane\n                        continue;\n                    Eigen::Vector4d pp;\n                    pp.head(3) = point_3d(intrinsic_matrix, w, h, depth_image.data[id]);\n                    pp.tail(1) << 1.;\n                    pp = tf.inverse() * pp;\n\n                    point_cloud.push_back(pp.head(3));\n                }\n            }\n\n            return 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

  • #include <string>
  • #include <vector>
  • #include <robot_dart/utils.hpp>
"},{"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\n#include <string>\n#include <vector>\n\n#include <robot_dart/utils.hpp>\n\nnamespace robot_dart {\n    namespace gui {\n        struct Image {\n            size_t width = 0, height = 0;\n            size_t channels = 3;\n            std::vector<uint8_t> data;\n        };\n\n        struct GrayscaleImage {\n            size_t width = 0, height = 0;\n            std::vector<uint8_t> data;\n        };\n\n        struct DepthImage {\n            size_t width = 0, height = 0;\n            std::vector<double> data;\n        };\n\n        void save_png_image(const std::string& filename, const Image& rgb);\n        void save_png_image(const std::string& filename, const GrayscaleImage& gray);\n\n        GrayscaleImage convert_rgb_to_grayscale(const Image& rgb);\n\n        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 = 1000.);\n    } // namespace gui\n} // namespace robot_dart\n\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

  • #include \"base_application.hpp\"
  • #include <robot_dart/gui/magnum/gs/helper.hpp>
  • #include <robot_dart/robot_dart_simu.hpp>
  • #include <robot_dart/utils.hpp>
  • #include <robot_dart/utils_headers_dart_dynamics.hpp>
  • #include <Corrade/Containers/StridedArrayView.h>
  • #include <Corrade/Utility/Resource.h>
  • #include <Magnum/GL/CubeMapTexture.h>
  • #include <Magnum/GL/DefaultFramebuffer.h>
  • #include <Magnum/GL/Renderer.h>
  • #include <Magnum/GL/Texture.h>
  • #include <Magnum/GL/TextureFormat.h>
  • #include <Magnum/MeshTools/Compile.h>
  • #include <Magnum/MeshTools/CompressIndices.h>
  • #include <Magnum/MeshTools/Interleave.h>
  • #include <Magnum/Primitives/Axis.h>
  • #include <Magnum/Primitives/Square.h>
  • #include <Magnum/Trade/MeshData.h>
  • #include <Magnum/Trade/PhongMaterialData.h>
"},{"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":"

File: api/base__application_8cpp_source.md

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

  • #include <mutex>
  • #include <unistd.h>
  • #include <unordered_map>
  • #include <robot_dart/gui/helper.hpp>
  • #include <robot_dart/gui/magnum/drawables.hpp>
  • #include <robot_dart/gui/magnum/gs/camera.hpp>
  • #include <robot_dart/gui/magnum/gs/cube_map.hpp>
  • #include <robot_dart/gui/magnum/gs/cube_map_color.hpp>
  • #include <robot_dart/gui/magnum/gs/phong_multi_light.hpp>
  • #include <robot_dart/gui/magnum/gs/shadow_map.hpp>
  • #include <robot_dart/gui/magnum/gs/shadow_map_color.hpp>
  • #include <robot_dart/gui/magnum/types.hpp>
  • #include <robot_dart/utils_headers_external_gui.hpp>
  • #include <Magnum/GL/CubeMapTextureArray.h>
  • #include <Magnum/GL/Framebuffer.h>
  • #include <Magnum/GL/Mesh.h>
  • #include <Magnum/GL/TextureArray.h>
  • #include <Magnum/Platform/GLContext.h>
  • #include <Magnum/Platform/WindowlessEglApplication.h>
  • #include <Magnum/Shaders/DistanceFieldVector.h>
  • #include <Magnum/Shaders/Flat.h>
  • #include <Magnum/Shaders/VertexColor.h>
  • #include <Magnum/Text/AbstractFont.h>
  • #include <Magnum/Text/DistanceFieldGlyphCache.h>
  • #include <Magnum/Text/Renderer.h>
"},{"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 (\n    name\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 (\n    name,\n    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
"},{"location":"api/base__application_8hpp/#define-release_gl_context","title":"define release_gl_context","text":"
#define release_gl_context (\n    name\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\n#include <mutex>\n#include <unistd.h>\n#include <unordered_map>\n\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\n#include <robot_dart/utils_headers_external_gui.hpp>\n\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\n#include <Magnum/Text/AbstractFont.h>\n#include <Magnum/Text/DistanceFieldGlyphCache.h>\n#include <Magnum/Text/Renderer.h>\n\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\n#define get_gl_context(name) get_gl_context_with_sleep(name, 0)\n\n#define release_gl_context(name) robot_dart::gui::magnum::GlobalData::instance()->free_gl_context(name);\n\nnamespace robot_dart {\n    namespace gui {\n        namespace magnum {\n            struct GlobalData {\n            public:\n                static GlobalData* instance()\n                {\n                    static GlobalData gdata;\n                    return &gdata;\n                }\n\n                GlobalData(const GlobalData&) = delete;\n                void operator=(const GlobalData&) = delete;\n\n                Magnum::Platform::WindowlessGLContext* gl_context();\n                void free_gl_context(Magnum::Platform::WindowlessGLContext* context);\n\n                /* You should call this before starting to draw or after finished */\n                void set_max_contexts(size_t N);\n\n            private:\n                GlobalData() = default;\n                ~GlobalData() = default;\n\n                void _create_contexts();\n\n                std::vector<Magnum::Platform::WindowlessGLContext> _gl_contexts;\n                std::vector<bool> _used;\n                std::mutex _context_mutex;\n                size_t _max_contexts = 4;\n            };\n\n            struct GraphicsConfiguration {\n                // General\n                size_t width = 640;\n                size_t height = 480;\n                std::string title = \"DART\";\n\n                // Shadows\n                bool shadowed = true;\n                bool transparent_shadows = true;\n                size_t shadow_map_size = 1024;\n\n                // Lights\n                size_t max_lights = 3;\n                double specular_strength = 0.25; // strength of the specular component\n\n                // These options are only for the main camera\n                bool draw_main_camera = true;\n                bool draw_debug = true;\n                bool draw_text = true;\n\n                // Background (default = black)\n                Eigen::Vector4d bg_color{0.0, 0.0, 0.0, 1.0};\n            };\n\n            struct DebugDrawData {\n                Magnum::Shaders::VertexColorGL3D* axes_shader;\n                Magnum::GL::Mesh* axes_mesh;\n                Magnum::Shaders::FlatGL2D* background_shader;\n                Magnum::GL::Mesh* background_mesh;\n\n                Magnum::Shaders::DistanceFieldVectorGL2D* text_shader;\n                Magnum::GL::Buffer* text_vertices;\n                Magnum::GL::Buffer* text_indices;\n                Magnum::Text::AbstractFont* font;\n                Magnum::Text::DistanceFieldGlyphCache* cache;\n            };\n\n            class BaseApplication {\n            public:\n                BaseApplication(const GraphicsConfiguration& configuration = GraphicsConfiguration());\n                virtual ~BaseApplication() {}\n\n                void init(RobotDARTSimu* simu, const GraphicsConfiguration& configuration);\n\n                void clear_lights();\n                void add_light(const gs::Light& light);\n                gs::Light& light(size_t i);\n                std::vector<gs::Light>& lights();\n                size_t num_lights() const;\n\n                Magnum::SceneGraph::DrawableGroup3D& drawables() { return _drawables; }\n                Scene3D& scene() { return _scene; }\n                gs::Camera& camera() { return *_camera; }\n                const gs::Camera& camera() const { return *_camera; }\n\n                bool done() const;\n\n                void look_at(const Eigen::Vector3d& camera_pos,\n                    const Eigen::Vector3d& look_at,\n                    const Eigen::Vector3d& up);\n\n                virtual void render() {}\n\n                void update_lights(const gs::Camera& camera);\n                void update_graphics();\n                void render_shadows();\n\n                bool attach_camera(gs::Camera& camera, dart::dynamics::BodyNode* body);\n\n                // video (FPS is mandatory here, see the Graphics class for automatic computation)\n                void record_video(const std::string& video_fname, int fps) { _camera->record_video(video_fname, fps); }\n\n                bool shadowed() const { return _shadowed; }\n                bool transparent_shadows() const { return _transparent_shadows; }\n                void enable_shadows(bool enable = true, bool drawTransparentShadows = false);\n\n                Corrade::Containers::Optional<Magnum::Image2D>& image() { return _camera->image(); }\n\n                // This is for visualization purposes\n                GrayscaleImage depth_image();\n\n                // Image filled with depth buffer values\n                GrayscaleImage raw_depth_image();\n\n                // \"Image\" filled with depth buffer values (this returns an array of doubles)\n                DepthImage depth_array();\n\n                // Access to debug data\n                DebugDrawData debug_draw_data()\n                {\n                    DebugDrawData data;\n                    data.axes_shader = _3D_axis_shader.get();\n                    data.background_shader = _background_shader.get();\n                    data.axes_mesh = _3D_axis_mesh.get();\n                    data.background_mesh = _background_mesh.get();\n                    data.text_shader = _text_shader.get();\n                    data.text_vertices = _text_vertices.get();\n                    data.text_indices = _text_indices.get();\n                    data.font = _font.get();\n                    data.cache = _glyph_cache.get();\n\n                    return data;\n                }\n\n            protected:\n                /* Magnum */\n                Scene3D _scene;\n                Magnum::SceneGraph::DrawableGroup3D _drawables, _shadowed_drawables, _shadowed_color_drawables, _cubemap_drawables, _cubemap_color_drawables;\n                std::unique_ptr<gs::PhongMultiLight> _color_shader, _texture_shader;\n\n                std::unique_ptr<gs::Camera> _camera;\n\n                bool _done = false;\n\n                /* GUI Config */\n                GraphicsConfiguration _configuration;\n\n                /* DART */\n                RobotDARTSimu* _simu;\n                std::unique_ptr<Magnum::DartIntegration::World> _dart_world;\n                std::unordered_map<Magnum::DartIntegration::Object*, ObjectStruct*> _drawable_objects;\n                std::vector<gs::Light> _lights;\n\n                /* Shadows */\n                bool _shadowed = true, _transparent_shadows = false;\n                int _transparentSize = 0;\n                std::unique_ptr<gs::ShadowMap> _shadow_shader, _shadow_texture_shader;\n                std::unique_ptr<gs::ShadowMapColor> _shadow_color_shader, _shadow_texture_color_shader;\n                std::unique_ptr<gs::CubeMap> _cubemap_shader, _cubemap_texture_shader;\n                std::unique_ptr<gs::CubeMapColor> _cubemap_color_shader, _cubemap_texture_color_shader;\n                std::vector<ShadowData> _shadow_data;\n                std::unique_ptr<Magnum::GL::Texture2DArray> _shadow_texture, _shadow_color_texture;\n                std::unique_ptr<Magnum::GL::CubeMapTextureArray> _shadow_cube_map, _shadow_color_cube_map;\n                int _max_lights = 5;\n                int _shadow_map_size = 512;\n                std::unique_ptr<Camera3D> _shadow_camera;\n                Object3D* _shadow_camera_object;\n\n                /* Debug visualization */\n                std::unique_ptr<Magnum::GL::Mesh> _3D_axis_mesh;\n                std::unique_ptr<Magnum::Shaders::VertexColorGL3D> _3D_axis_shader;\n                std::unique_ptr<Magnum::GL::Mesh> _background_mesh;\n                std::unique_ptr<Magnum::Shaders::FlatGL2D> _background_shader;\n\n                /* Text visualization */\n                std::unique_ptr<Magnum::Shaders::DistanceFieldVectorGL2D> _text_shader;\n                Corrade::PluginManager::Manager<Magnum::Text::AbstractFont> _font_manager;\n                Corrade::Containers::Pointer<Magnum::Text::DistanceFieldGlyphCache> _glyph_cache;\n                Corrade::Containers::Pointer<Magnum::Text::AbstractFont> _font;\n                Corrade::Containers::Pointer<Magnum::GL::Buffer> _text_vertices;\n                Corrade::Containers::Pointer<Magnum::GL::Buffer> _text_indices;\n\n                /* Importer */\n                Corrade::PluginManager::Manager<Magnum::Trade::AbstractImporter> _importer_manager;\n\n                void _gl_clean_up();\n                void _prepare_shadows();\n            };\n\n            template <typename T>\n            inline BaseApplication* make_application(RobotDARTSimu* simu, const GraphicsConfiguration& configuration = GraphicsConfiguration())\n            {\n                int argc = 0;\n                char** argv = NULL;\n\n                return 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\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

  • #include <robot_dart/gui/base.hpp>
  • #include <robot_dart/gui/magnum/glfw_application.hpp>
  • #include <robot_dart/gui/magnum/gs/helper.hpp>
  • #include <robot_dart/gui/magnum/utils_headers_eigen.hpp>
  • #include <robot_dart/robot_dart_simu.hpp>
  • #include <Corrade/Utility/Resource.h>
"},{"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 () \n

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\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\n// We need this for CORRADE_RESOURCE_INITIALIZE\n#include <Corrade/Utility/Resource.h>\n\ninline static void robot_dart_initialize_magnum_resources()\n{\n    CORRADE_RESOURCE_INITIALIZE(RobotDARTShaders);\n}\n\nnamespace robot_dart {\n    namespace gui {\n        namespace magnum {\n            template <typename T = GlfwApplication>\n            class BaseGraphics : public Base {\n            public:\n                BaseGraphics(const GraphicsConfiguration& configuration = GraphicsConfiguration())\n                    : _configuration(configuration), _enabled(true)\n                {\n                    robot_dart_initialize_magnum_resources();\n                }\n\n                virtual ~BaseGraphics() {}\n\n                virtual void set_simu(RobotDARTSimu* simu) override\n                {\n                    ROBOT_DART_EXCEPTION_ASSERT(simu, \"Simulation pointer is null!\");\n                    _simu = simu;\n                    _magnum_app.reset(make_application<T>(simu, _configuration));\n                }\n\n                size_t width() const override\n                {\n                    ROBOT_DART_EXCEPTION_ASSERT(_magnum_app, \"MagnumApp pointer is null!\");\n                    return _magnum_app->camera().width();\n                }\n\n                size_t height() const override\n                {\n                    ROBOT_DART_EXCEPTION_ASSERT(_magnum_app, \"MagnumApp pointer is null!\");\n                    return _magnum_app->camera().height();\n                }\n\n                bool done() const override\n                {\n                    ROBOT_DART_EXCEPTION_ASSERT(_magnum_app, \"MagnumApp pointer is null!\");\n                    return _magnum_app->done();\n                }\n\n                void refresh() override\n                {\n                    if (!_enabled)\n                        return;\n\n                    ROBOT_DART_EXCEPTION_ASSERT(_magnum_app, \"MagnumApp pointer is null!\");\n                    _magnum_app->render();\n                }\n\n                void set_enable(bool enable) override\n                {\n                    _enabled = enable;\n                }\n\n                void set_fps(int fps) override { _fps = fps; }\n\n                void look_at(const Eigen::Vector3d& camera_pos,\n                    const Eigen::Vector3d& look_at = Eigen::Vector3d(0, 0, 0),\n                    const Eigen::Vector3d& up = Eigen::Vector3d(0, 0, 1))\n                {\n                    ROBOT_DART_EXCEPTION_ASSERT(_magnum_app, \"MagnumApp pointer is null!\");\n                    _magnum_app->look_at(camera_pos, look_at, up);\n                }\n\n                void clear_lights()\n                {\n                    ROBOT_DART_EXCEPTION_ASSERT(_magnum_app, \"MagnumApp pointer is null!\");\n                    _magnum_app->clear_lights();\n                }\n\n                void add_light(const magnum::gs::Light& light)\n                {\n                    ROBOT_DART_EXCEPTION_ASSERT(_magnum_app, \"MagnumApp pointer is null!\");\n                    _magnum_app->add_light(light);\n                }\n\n                std::vector<gs::Light>& lights()\n                {\n                    ROBOT_DART_EXCEPTION_ASSERT(_magnum_app, \"MagnumApp pointer is null!\");\n                    return _magnum_app->lights();\n                }\n\n                size_t num_lights() const\n                {\n                    ROBOT_DART_EXCEPTION_ASSERT(_magnum_app, \"MagnumApp pointer is null!\");\n                    return _magnum_app->num_lights();\n                }\n\n                magnum::gs::Light& light(size_t i)\n                {\n                    ROBOT_DART_EXCEPTION_ASSERT(_magnum_app, \"MagnumApp pointer is null!\");\n                    return _magnum_app->light(i);\n                }\n\n                void record_video(const std::string& video_fname, int fps = -1)\n                {\n                    int fps_computed = (fps == -1) ? _fps : fps;\n                    ROBOT_DART_EXCEPTION_ASSERT(fps_computed != -1, \"Video FPS not set!\");\n                    ROBOT_DART_EXCEPTION_ASSERT(_magnum_app, \"MagnumApp pointer is null!\");\n\n                    _magnum_app->record_video(video_fname, fps_computed);\n                }\n\n                bool shadowed() const\n                {\n                    ROBOT_DART_EXCEPTION_ASSERT(_magnum_app, \"MagnumApp pointer is null!\");\n                    return _magnum_app->shadowed();\n                }\n\n                bool transparent_shadows() const\n                {\n                    ROBOT_DART_EXCEPTION_ASSERT(_magnum_app, \"MagnumApp pointer is null!\");\n                    return _magnum_app->transparent_shadows();\n                }\n\n                void enable_shadows(bool enable = true, bool transparent = true)\n                {\n                    ROBOT_DART_EXCEPTION_ASSERT(_magnum_app, \"MagnumApp pointer is null!\");\n                    _magnum_app->enable_shadows(enable, transparent);\n                }\n\n                Magnum::Image2D* magnum_image()\n                {\n                    ROBOT_DART_EXCEPTION_ASSERT(_magnum_app, \"MagnumApp pointer is null!\");\n                    if (_magnum_app->image())\n                        return &(*_magnum_app->image());\n                    return nullptr;\n                }\n\n                Image image() override\n                {\n                    auto image = magnum_image();\n                    if (image)\n                        return gs::rgb_from_image(image);\n                    return Image();\n                }\n\n                GrayscaleImage depth_image() override\n                {\n                    ROBOT_DART_EXCEPTION_ASSERT(_magnum_app, \"MagnumApp pointer is null!\");\n                    return _magnum_app->depth_image();\n                }\n\n                GrayscaleImage raw_depth_image() override\n                {\n                    ROBOT_DART_EXCEPTION_ASSERT(_magnum_app, \"MagnumApp pointer is null!\");\n                    return _magnum_app->raw_depth_image();\n                }\n\n                DepthImage depth_array() override\n                {\n                    ROBOT_DART_EXCEPTION_ASSERT(_magnum_app, \"MagnumApp pointer is null!\");\n                    return _magnum_app->depth_array();\n                }\n\n                gs::Camera& camera()\n                {\n                    ROBOT_DART_EXCEPTION_ASSERT(_magnum_app, \"MagnumApp pointer is null!\");\n                    return _magnum_app->camera();\n                }\n\n                const gs::Camera& camera() const\n                {\n                    ROBOT_DART_EXCEPTION_ASSERT(_magnum_app, \"MagnumApp pointer is null!\");\n                    return _magnum_app->camera();\n                }\n\n                Eigen::Matrix3d camera_intrinsic_matrix() const\n                {\n                    ROBOT_DART_EXCEPTION_ASSERT(_magnum_app, \"MagnumApp pointer is null!\");\n                    return Magnum::EigenIntegration::cast<Eigen::Matrix3d>(Magnum::Matrix3d(_magnum_app->camera().intrinsic_matrix()));\n                }\n\n                Eigen::Matrix4d camera_extrinsic_matrix() const\n                {\n                    ROBOT_DART_EXCEPTION_ASSERT(_magnum_app, \"MagnumApp pointer is null!\");\n                    return Magnum::EigenIntegration::cast<Eigen::Matrix4d>(Magnum::Matrix4d(_magnum_app->camera().extrinsic_matrix()));\n                }\n\n                BaseApplication* magnum_app()\n                {\n                    ROBOT_DART_EXCEPTION_ASSERT(_magnum_app, \"MagnumApp pointer is null!\");\n                    return &*_magnum_app;\n                }\n\n                const BaseApplication* magnum_app() const\n                {\n                    ROBOT_DART_EXCEPTION_ASSERT(_magnum_app, \"MagnumApp pointer is null!\");\n                    return &*_magnum_app;\n                }\n\n            protected:\n                GraphicsConfiguration _configuration;\n                bool _enabled;\n                int _fps;\n                std::unique_ptr<BaseApplication> _magnum_app;\n\n                Corrade::Utility::Debug _magnum_silence_output{nullptr};\n            };\n        } // namespace magnum\n    } // namespace gui\n} // namespace robot_dart\n\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

  • #include <robot_dart/gui/magnum/drawables.hpp>
  • #include <robot_dart/gui_data.hpp>
  • #include <robot_dart/robot_dart_simu.hpp>
  • #include <robot_dart/utils.hpp>
  • #include <Magnum/GL/CubeMapTexture.h>
  • #include <Magnum/GL/DefaultFramebuffer.h>
  • #include <Magnum/GL/Mesh.h>
  • #include <Magnum/GL/Renderer.h>
  • #include <Magnum/GL/AbstractFramebuffer.h>
  • #include <Magnum/GL/GL.h>
"},{"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\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\n#include <Magnum/GL/AbstractFramebuffer.h>\n#include <Magnum/GL/GL.h>\n\nnamespace robot_dart {\n    namespace gui {\n        namespace magnum {\n            // DrawableObject\n            DrawableObject::DrawableObject(\n                RobotDARTSimu* simu,\n                dart::dynamics::ShapeNode* shape,\n                const std::vector<std::reference_wrapper<Magnum::GL::Mesh>>& meshes,\n                const std::vector<gs::Material>& materials,\n                gs::PhongMultiLight& color,\n                gs::PhongMultiLight& texture,\n                Object3D* parent,\n                Magnum::SceneGraph::DrawableGroup3D* group)\n                : Object3D{parent},\n                  Magnum::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            }\n\n            DrawableObject& DrawableObject::set_meshes(const std::vector<std::reference_wrapper<Magnum::GL::Mesh>>& meshes)\n            {\n                _meshes = meshes;\n                return *this;\n            }\n\n            DrawableObject& DrawableObject::set_materials(const std::vector<gs::Material>& materials)\n            {\n                _materials = materials;\n                return *this;\n            }\n\n            DrawableObject& DrawableObject::set_soft_bodies(const std::vector<bool>& softBody)\n            {\n                _is_soft_body = softBody;\n                return *this;\n            }\n\n            DrawableObject& DrawableObject::set_scalings(const std::vector<Magnum::Vector3>& scalings)\n            {\n                _scalings = scalings;\n\n                _has_negative_scaling.resize(_scalings.size());\n                for (size_t i = 0; i < scalings.size(); i++) {\n                    _has_negative_scaling[i] = false;\n                    for (size_t j = 0; j < 3; j++)\n                        if (_scalings[i][j] < 0.f) {\n                            _has_negative_scaling[i] = true;\n                            break;\n                        }\n                }\n\n                return *this;\n            }\n\n            DrawableObject& DrawableObject::set_transparent(bool transparent)\n            {\n                _isTransparent = transparent;\n                return *this;\n            }\n\n            DrawableObject& DrawableObject::set_color_shader(std::reference_wrapper<gs::PhongMultiLight> shader)\n            {\n                _color_shader = shader;\n                return *this;\n            }\n\n            DrawableObject& DrawableObject::set_texture_shader(std::reference_wrapper<gs::PhongMultiLight> shader)\n            {\n                _texture_shader = shader;\n                return *this;\n            }\n\n            void DrawableObject::draw(const Magnum::Matrix4& transformationMatrix, Magnum::SceneGraph::Camera3D& camera)\n            {\n                for (size_t i = 0; i < _meshes.size(); i++) {\n                    Magnum::GL::Mesh& mesh = _meshes[i];\n                    Magnum::Matrix4 scalingMatrix = Magnum::Matrix4::scaling(_scalings[i]);\n                    bool isColor = !_materials[i].has_diffuse_texture();\n                    if (_is_soft_body[i])\n                        Magnum::GL::Renderer::disable(Magnum::GL::Renderer::Feature::FaceCulling);\n                    else if (_has_negative_scaling[i])\n                        Magnum::GL::Renderer::setFaceCullingMode(Magnum::GL::Renderer::PolygonFacing::Front);\n                    if (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                    }\n                    else {\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                    }\n\n                    if (_is_soft_body[i])\n                        Magnum::GL::Renderer::enable(Magnum::GL::Renderer::Feature::FaceCulling);\n                    else if (_has_negative_scaling[i])\n                        Magnum::GL::Renderer::setFaceCullingMode(Magnum::GL::Renderer::PolygonFacing::Back);\n                }\n            }\n\n            // ShadowedObject\n            ShadowedObject::ShadowedObject(\n                RobotDARTSimu* simu,\n                dart::dynamics::ShapeNode* shape,\n                const std::vector<std::reference_wrapper<Magnum::GL::Mesh>>& meshes,\n                gs::ShadowMap& shader,\n                gs::ShadowMap& texture_shader,\n                Object3D* parent,\n                Magnum::SceneGraph::DrawableGroup3D* group)\n                : Object3D{parent},\n                  Magnum::SceneGraph::Drawable3D{*this, group},\n                  _simu(simu),\n                  _shape(shape),\n                  _meshes{meshes},\n                  _shader{shader},\n                  _texture_shader(texture_shader) {}\n\n            ShadowedObject& ShadowedObject::set_meshes(const std::vector<std::reference_wrapper<Magnum::GL::Mesh>>& meshes)\n            {\n                _meshes = meshes;\n                return *this;\n            }\n\n            ShadowedObject& ShadowedObject::set_materials(const std::vector<gs::Material>& materials)\n            {\n                _materials = materials;\n                return *this;\n            }\n\n            ShadowedObject& ShadowedObject::set_scalings(const std::vector<Magnum::Vector3>& scalings)\n            {\n                _scalings = scalings;\n                return *this;\n            }\n\n            void ShadowedObject::draw(const Magnum::Matrix4& transformationMatrix, Magnum::SceneGraph::Camera3D& camera)\n            {\n                if (!_simu->gui_data()->cast_shadows(_shape))\n                    return;\n                for (size_t i = 0; i < _meshes.size(); i++) {\n                    Magnum::GL::Mesh& mesh = _meshes[i];\n                    Magnum::Matrix4 scalingMatrix = Magnum::Matrix4::scaling(_scalings[i]);\n                    bool isColor = !_materials[i].has_diffuse_texture();\n                    if (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                    }\n                    else {\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\n            // ShadowedColorObject\n            ShadowedColorObject::ShadowedColorObject(\n                RobotDARTSimu* simu,\n                dart::dynamics::ShapeNode* shape,\n                const std::vector<std::reference_wrapper<Magnum::GL::Mesh>>& meshes,\n                gs::ShadowMapColor& shader,\n                gs::ShadowMapColor& texture_shader,\n                Object3D* parent,\n                Magnum::SceneGraph::DrawableGroup3D* group)\n                : Object3D{parent},\n                  Magnum::SceneGraph::Drawable3D{*this, group},\n                  _simu(simu),\n                  _shape(shape),\n                  _meshes{meshes},\n                  _shader{shader},\n                  _texture_shader(texture_shader) {}\n\n            ShadowedColorObject& ShadowedColorObject::set_meshes(const std::vector<std::reference_wrapper<Magnum::GL::Mesh>>& meshes)\n            {\n                _meshes = meshes;\n                return *this;\n            }\n\n            ShadowedColorObject& ShadowedColorObject::set_materials(const std::vector<gs::Material>& materials)\n            {\n                _materials = materials;\n                return *this;\n            }\n\n            ShadowedColorObject& ShadowedColorObject::set_scalings(const std::vector<Magnum::Vector3>& scalings)\n            {\n                _scalings = scalings;\n                return *this;\n            }\n\n            void ShadowedColorObject::draw(const Magnum::Matrix4& transformationMatrix, Magnum::SceneGraph::Camera3D& camera)\n            {\n                if (!_simu->gui_data()->cast_shadows(_shape))\n                    return;\n                for (size_t i = 0; i < _meshes.size(); i++) {\n                    Magnum::GL::Mesh& mesh = _meshes[i];\n                    Magnum::Matrix4 scalingMatrix = Magnum::Matrix4::scaling(_scalings[i]);\n                    bool isColor = !_materials[i].has_diffuse_texture();\n                    if (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                    }\n                    else {\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\n            // CubeMapShadowedObject\n            CubeMapShadowedObject::CubeMapShadowedObject(\n                RobotDARTSimu* simu,\n                dart::dynamics::ShapeNode* shape,\n                const std::vector<std::reference_wrapper<Magnum::GL::Mesh>>& meshes,\n                gs::CubeMap& shader,\n                gs::CubeMap& texture_shader,\n                Object3D* parent,\n                Magnum::SceneGraph::DrawableGroup3D* group)\n                : Object3D{parent},\n                  Magnum::SceneGraph::Drawable3D{*this, group},\n                  _simu(simu),\n                  _shape(shape),\n                  _meshes{meshes},\n                  _shader{shader},\n                  _texture_shader(texture_shader) {}\n\n            CubeMapShadowedObject& CubeMapShadowedObject::set_meshes(const std::vector<std::reference_wrapper<Magnum::GL::Mesh>>& meshes)\n            {\n                _meshes = meshes;\n                return *this;\n            }\n\n            CubeMapShadowedObject& CubeMapShadowedObject::set_materials(const std::vector<gs::Material>& materials)\n            {\n                _materials = materials;\n                return *this;\n            }\n\n            CubeMapShadowedObject& CubeMapShadowedObject::set_scalings(const std::vector<Magnum::Vector3>& scalings)\n            {\n                _scalings = scalings;\n                return *this;\n            }\n\n            void CubeMapShadowedObject::draw(const Magnum::Matrix4&, Magnum::SceneGraph::Camera3D&)\n            {\n                for (size_t i = 0; i < _meshes.size(); i++) {\n                    Magnum::GL::Mesh& mesh = _meshes[i];\n                    Magnum::Matrix4 scalingMatrix = Magnum::Matrix4::scaling(_scalings[i]);\n                    bool isColor = !_materials[i].has_diffuse_texture();\n                    if (isColor) {\n                        (_shader.get())\n                            .set_transformation_matrix(absoluteTransformation() * scalingMatrix)\n                            .set_material(_materials[i])\n                            .draw(mesh);\n                    }\n                    else {\n                        (_texture_shader.get())\n                            .set_transformation_matrix(absoluteTransformation() * scalingMatrix)\n                            .set_material(_materials[i])\n                            .draw(mesh);\n                    }\n                }\n            }\n\n            // CubeMapShadowedColorObject\n            CubeMapShadowedColorObject::CubeMapShadowedColorObject(\n                RobotDARTSimu* simu,\n                dart::dynamics::ShapeNode* shape,\n                const std::vector<std::reference_wrapper<Magnum::GL::Mesh>>& meshes,\n                gs::CubeMapColor& shader,\n                gs::CubeMapColor& texture_shader,\n                Object3D* parent,\n                Magnum::SceneGraph::DrawableGroup3D* group)\n                : Object3D{parent},\n                  Magnum::SceneGraph::Drawable3D{*this, group},\n                  _simu(simu),\n                  _shape(shape),\n                  _meshes{meshes},\n                  _shader{shader},\n                  _texture_shader(texture_shader) {}\n\n            CubeMapShadowedColorObject& CubeMapShadowedColorObject::set_meshes(const std::vector<std::reference_wrapper<Magnum::GL::Mesh>>& meshes)\n            {\n                _meshes = meshes;\n                return *this;\n            }\n\n            CubeMapShadowedColorObject& CubeMapShadowedColorObject::set_materials(const std::vector<gs::Material>& materials)\n            {\n                _materials = materials;\n                return *this;\n            }\n\n            CubeMapShadowedColorObject& CubeMapShadowedColorObject::set_scalings(const std::vector<Magnum::Vector3>& scalings)\n            {\n                _scalings = scalings;\n                return *this;\n            }\n\n            void CubeMapShadowedColorObject::draw(const Magnum::Matrix4&, Magnum::SceneGraph::Camera3D&)\n            {\n                if (!_simu->gui_data()->cast_shadows(_shape))\n                    return;\n                for (size_t i = 0; i < _meshes.size(); i++) {\n                    Magnum::GL::Mesh& mesh = _meshes[i];\n                    Magnum::Matrix4 scalingMatrix = Magnum::Matrix4::scaling(_scalings[i]);\n                    bool isColor = !_materials[i].has_diffuse_texture();\n                    if (isColor) {\n                        (_shader.get())\n                            .set_transformation_matrix(absoluteTransformation() * scalingMatrix)\n                            .set_material(_materials[i])\n                            .draw(mesh);\n                    }\n                    else {\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

  • #include <robot_dart/gui/helper.hpp>
  • #include <robot_dart/gui/magnum/gs/cube_map.hpp>
  • #include <robot_dart/gui/magnum/gs/cube_map_color.hpp>
  • #include <robot_dart/gui/magnum/gs/phong_multi_light.hpp>
  • #include <robot_dart/gui/magnum/gs/shadow_map.hpp>
  • #include <robot_dart/gui/magnum/gs/shadow_map_color.hpp>
  • #include <robot_dart/gui/magnum/types.hpp>
  • #include <Magnum/GL/Framebuffer.h>
  • #include <Magnum/SceneGraph/Drawable.h>
"},{"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\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\n#include <Magnum/GL/Framebuffer.h>\n\n#include <Magnum/SceneGraph/Drawable.h>\n\nnamespace dart {\n    namespace dynamics {\n        class ShapeNode;\n    }\n} // namespace dart\n\nnamespace robot_dart {\n    class RobotDARTSimu;\n\n    namespace gui {\n        namespace magnum {\n            class DrawableObject : public Object3D, public Magnum::SceneGraph::Drawable3D {\n            public:\n                explicit DrawableObject(\n                    RobotDARTSimu* simu,\n                    dart::dynamics::ShapeNode* shape,\n                    const std::vector<std::reference_wrapper<Magnum::GL::Mesh>>& meshes,\n                    const std::vector<gs::Material>& materials,\n                    gs::PhongMultiLight& color,\n                    gs::PhongMultiLight& texture,\n                    Object3D* parent,\n                    Magnum::SceneGraph::DrawableGroup3D* group);\n\n                DrawableObject& set_meshes(const std::vector<std::reference_wrapper<Magnum::GL::Mesh>>& meshes);\n                DrawableObject& set_materials(const std::vector<gs::Material>& materials);\n                DrawableObject& set_soft_bodies(const std::vector<bool>& softBody);\n                DrawableObject& set_scalings(const std::vector<Magnum::Vector3>& scalings);\n                DrawableObject& set_transparent(bool transparent = true);\n\n                DrawableObject& set_color_shader(std::reference_wrapper<gs::PhongMultiLight> shader);\n                DrawableObject& set_texture_shader(std::reference_wrapper<gs::PhongMultiLight> shader);\n\n                const std::vector<gs::Material>& materials() const { return _materials; }\n                bool transparent() const { return _isTransparent; }\n\n                RobotDARTSimu* simu() const { return _simu; }\n                dart::dynamics::ShapeNode* shape() const { return _shape; }\n\n            private:\n                void draw(const Magnum::Matrix4& transformationMatrix, Magnum::SceneGraph::Camera3D& camera) override;\n\n                RobotDARTSimu* _simu;\n                dart::dynamics::ShapeNode* _shape;\n                std::vector<std::reference_wrapper<Magnum::GL::Mesh>> _meshes;\n                std::reference_wrapper<gs::PhongMultiLight> _color_shader;\n                std::reference_wrapper<gs::PhongMultiLight> _texture_shader;\n                std::vector<gs::Material> _materials;\n                std::vector<Magnum::Vector3> _scalings;\n                std::vector<bool> _has_negative_scaling;\n                std::vector<bool> _is_soft_body;\n                bool _isTransparent;\n            };\n\n            class ShadowedObject : public Object3D, public Magnum::SceneGraph::Drawable3D {\n            public:\n                explicit ShadowedObject(\n                    RobotDARTSimu* simu,\n                    dart::dynamics::ShapeNode* shape,\n                    const std::vector<std::reference_wrapper<Magnum::GL::Mesh>>& meshes,\n                    gs::ShadowMap& shader,\n                    gs::ShadowMap& texture_shader,\n                    Object3D* parent,\n                    Magnum::SceneGraph::DrawableGroup3D* group);\n\n                ShadowedObject& set_meshes(const std::vector<std::reference_wrapper<Magnum::GL::Mesh>>& meshes);\n                ShadowedObject& set_materials(const std::vector<gs::Material>& materials);\n                ShadowedObject& set_scalings(const std::vector<Magnum::Vector3>& scalings);\n\n                RobotDARTSimu* simu() const { return _simu; }\n                dart::dynamics::ShapeNode* shape() const { return _shape; }\n\n            private:\n                void draw(const Magnum::Matrix4& transformationMatrix, Magnum::SceneGraph::Camera3D& camera) override;\n\n                RobotDARTSimu* _simu;\n                dart::dynamics::ShapeNode* _shape;\n                std::vector<std::reference_wrapper<Magnum::GL::Mesh>> _meshes;\n                std::reference_wrapper<gs::ShadowMap> _shader, _texture_shader;\n                std::vector<gs::Material> _materials;\n                std::vector<Magnum::Vector3> _scalings;\n            };\n\n            class ShadowedColorObject : public Object3D, public Magnum::SceneGraph::Drawable3D {\n            public:\n                explicit ShadowedColorObject(\n                    RobotDARTSimu* simu,\n                    dart::dynamics::ShapeNode* shape,\n                    const std::vector<std::reference_wrapper<Magnum::GL::Mesh>>& meshes,\n                    gs::ShadowMapColor& shader,\n                    gs::ShadowMapColor& texture_shader,\n                    Object3D* parent,\n                    Magnum::SceneGraph::DrawableGroup3D* group);\n\n                ShadowedColorObject& set_meshes(const std::vector<std::reference_wrapper<Magnum::GL::Mesh>>& meshes);\n                ShadowedColorObject& set_materials(const std::vector<gs::Material>& materials);\n                ShadowedColorObject& set_scalings(const std::vector<Magnum::Vector3>& scalings);\n\n                RobotDARTSimu* simu() const { return _simu; }\n                dart::dynamics::ShapeNode* shape() const { return _shape; }\n\n            private:\n                void draw(const Magnum::Matrix4& transformationMatrix, Magnum::SceneGraph::Camera3D& camera) override;\n\n                RobotDARTSimu* _simu;\n                dart::dynamics::ShapeNode* _shape;\n                std::vector<std::reference_wrapper<Magnum::GL::Mesh>> _meshes;\n                std::reference_wrapper<gs::ShadowMapColor> _shader, _texture_shader;\n                std::vector<gs::Material> _materials;\n                std::vector<Magnum::Vector3> _scalings;\n            };\n\n            class CubeMapShadowedObject : public Object3D, public Magnum::SceneGraph::Drawable3D {\n            public:\n                explicit CubeMapShadowedObject(\n                    RobotDARTSimu* simu,\n                    dart::dynamics::ShapeNode* shape,\n                    const std::vector<std::reference_wrapper<Magnum::GL::Mesh>>& meshes,\n                    gs::CubeMap& shader,\n                    gs::CubeMap& texture_shader,\n                    Object3D* parent,\n                    Magnum::SceneGraph::DrawableGroup3D* group);\n\n                CubeMapShadowedObject& set_meshes(const std::vector<std::reference_wrapper<Magnum::GL::Mesh>>& meshes);\n                CubeMapShadowedObject& set_materials(const std::vector<gs::Material>& materials);\n                CubeMapShadowedObject& set_scalings(const std::vector<Magnum::Vector3>& scalings);\n\n                RobotDARTSimu* simu() const { return _simu; }\n                dart::dynamics::ShapeNode* shape() const { return _shape; }\n\n            private:\n                void draw(const Magnum::Matrix4& transformationMatrix, Magnum::SceneGraph::Camera3D& camera) override;\n\n                RobotDARTSimu* _simu;\n                dart::dynamics::ShapeNode* _shape;\n                std::vector<std::reference_wrapper<Magnum::GL::Mesh>> _meshes;\n                std::reference_wrapper<gs::CubeMap> _shader, _texture_shader;\n                std::vector<gs::Material> _materials;\n                std::vector<Magnum::Vector3> _scalings;\n            };\n\n            class CubeMapShadowedColorObject : public Object3D, public Magnum::SceneGraph::Drawable3D {\n            public:\n                explicit CubeMapShadowedColorObject(\n                    RobotDARTSimu* simu,\n                    dart::dynamics::ShapeNode* shape,\n                    const std::vector<std::reference_wrapper<Magnum::GL::Mesh>>& meshes,\n                    gs::CubeMapColor& shader,\n                    gs::CubeMapColor& texture_shader,\n                    Object3D* parent,\n                    Magnum::SceneGraph::DrawableGroup3D* group);\n\n                CubeMapShadowedColorObject& set_meshes(const std::vector<std::reference_wrapper<Magnum::GL::Mesh>>& meshes);\n                CubeMapShadowedColorObject& set_materials(const std::vector<gs::Material>& materials);\n                CubeMapShadowedColorObject& set_scalings(const std::vector<Magnum::Vector3>& scalings);\n\n                RobotDARTSimu* simu() const { return _simu; }\n                dart::dynamics::ShapeNode* shape() const { return _shape; }\n\n            private:\n                void draw(const Magnum::Matrix4& transformationMatrix, Magnum::SceneGraph::Camera3D& camera) override;\n\n                RobotDARTSimu* _simu;\n                dart::dynamics::ShapeNode* _shape;\n                std::vector<std::reference_wrapper<Magnum::GL::Mesh>> _meshes;\n                std::reference_wrapper<gs::CubeMapColor> _shader, _texture_shader;\n                std::vector<gs::Material> _materials;\n                std::vector<Magnum::Vector3> _scalings;\n            };\n\n            struct ShadowData {\n                Magnum::GL::Framebuffer shadow_framebuffer{Magnum::NoCreate};\n                Magnum::GL::Framebuffer shadow_color_framebuffer{Magnum::NoCreate};\n            };\n\n            struct ObjectStruct {\n                DrawableObject* drawable;\n                ShadowedObject* shadowed;\n                ShadowedColorObject* shadowed_color;\n                CubeMapShadowedObject* cubemapped;\n                CubeMapShadowedColorObject* 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

  • #include \"glfw_application.hpp\"
  • #include \"robot_dart/utils.hpp\"
  • #include <Magnum/GL/DefaultFramebuffer.h>
  • #include <Magnum/GL/Renderer.h>
  • #include <Magnum/GL/Version.h>
  • #include <Magnum/PixelFormat.h>
"},{"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":"

File: api/glfw__application_8cpp_source.md

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

  • #include <robot_dart/gui/magnum/base_application.hpp>
  • #include <Magnum/Platform/GlfwApplication.h>
"},{"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\n#include <robot_dart/gui/magnum/base_application.hpp>\n\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>\n\nnamespace robot_dart {\n    namespace gui {\n        namespace magnum {\n            class GlfwApplication : public BaseApplication, public Magnum::Platform::Application {\n            public:\n                explicit GlfwApplication(int argc, char** argv, RobotDARTSimu* simu, const GraphicsConfiguration& configuration = GraphicsConfiguration());\n\n                ~GlfwApplication();\n\n                void render() override;\n\n            protected:\n                RobotDARTSimu* _simu;\n                Magnum::Float _speed_move, _speed_strafe;\n                bool _draw_main_camera, _draw_debug;\n                Magnum::Color4 _bg_color;\n\n                static constexpr Magnum::Float _speed = 0.05f;\n\n                void viewportEvent(ViewportEvent& event) override;\n\n                void drawEvent() override;\n\n                virtual void keyReleaseEvent(KeyEvent& event) override;\n                virtual void keyPressEvent(KeyEvent& event) override;\n\n                virtual void mouseScrollEvent(MouseScrollEvent& event) override;\n                virtual void mouseMoveEvent(MouseMoveEvent& event) override;\n\n                void exitEvent(ExitEvent& event) override;\n            };\n        } // namespace magnum\n    } // namespace gui\n} // namespace robot_dart\n\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

  • #include <robot_dart/gui/magnum/graphics.hpp>
"},{"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>\n\nnamespace robot_dart {\n    namespace gui {\n        namespace magnum {\n            void Graphics::set_simu(RobotDARTSimu* simu)\n            {\n                BaseGraphics<GlfwApplication>::set_simu(simu);\n                // we synchronize by default if we have the graphics activated\n                simu->scheduler().set_sync(true);\n                // enable summary text when graphics activated\n                simu->enable_text_panel(true);\n                simu->enable_status_bar(true);\n            }\n\n            GraphicsConfiguration Graphics::default_configuration()\n            {\n                return 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

  • #include <robot_dart/gui/magnum/base_graphics.hpp>
"},{"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\n#include <robot_dart/gui/magnum/base_graphics.hpp>\n\nnamespace robot_dart {\n    namespace gui {\n        namespace magnum {\n            class Graphics : public BaseGraphics<GlfwApplication> {\n            public:\n                Graphics(const GraphicsConfiguration& configuration = default_configuration()) : BaseGraphics<GlfwApplication>(configuration) {}\n                ~Graphics() {}\n\n                void set_simu(RobotDARTSimu* simu) override;\n\n                static GraphicsConfiguration default_configuration();\n            };\n        } // namespace magnum\n    } // namespace gui\n} // namespace robot_dart\n\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

  • #include \"camera.hpp\"
  • #include \"robot_dart/gui/magnum/base_application.hpp\"
  • #include \"robot_dart/gui_data.hpp\"
  • #include \"robot_dart/robot_dart_simu.hpp\"
  • #include \"robot_dart/utils.hpp\"
  • #include <external/process.hpp>
  • #include <algorithm>
  • #include <Corrade/Containers/ArrayViewStl.h>
  • #include <Corrade/Containers/StridedArrayView.h>
  • #include <Corrade/Utility/Algorithms.h>
  • #include <Magnum/GL/AbstractFramebuffer.h>
  • #include <Magnum/GL/GL.h>
  • #include <Magnum/GL/PixelFormat.h>
  • #include <Magnum/GL/Renderer.h>
  • #include <Magnum/ImageView.h>
  • #include <Magnum/PixelFormat.h>
  • #include <robot_dart/gui/magnum/utils_headers_eigen.hpp>
  • #include <utheque/utheque.hpp>
"},{"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":"

File: api/gs_2camera_8cpp_source.md

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

  • #include <robot_dart/gui/magnum/gs/light.hpp>
  • #include <robot_dart/gui/magnum/types.hpp>
  • #include <robot_dart/robot_dart_simu.hpp>
  • #include <Corrade/Containers/Optional.h>
  • #include <Magnum/GL/Mesh.h>
  • #include <Magnum/Image.h>
  • #include <Magnum/Shaders/DistanceFieldVector.h>
  • #include <Magnum/Shaders/VertexColor.h>
  • #include <Magnum/Text/Renderer.h>
"},{"location":"api/gs_2camera_8hpp/#namespaces","title":"Namespaces","text":"Type Name namespace TinyProcessLib namespace robot_dart namespace gui namespace magnum namespace gs"},{"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\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\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>\n\nnamespace TinyProcessLib {\n    class Process;\n}\n\nnamespace robot_dart {\n    namespace gui {\n        namespace magnum {\n            struct DebugDrawData;\n\n            namespace gs {\n                // This is partly code from the ThirdPersonCameraController of https://github.com/alexesDev/magnum-tips\n                class Camera : public Object3D {\n                public:\n                    explicit Camera(Object3D& object, Magnum::Int width, Magnum::Int height);\n                    ~Camera();\n\n                    Camera3D& camera() const;\n                    Object3D& root_object();\n                    Object3D& camera_object() const;\n\n                    Camera& set_viewport(const Magnum::Vector2i& size);\n\n                    Camera& move(const Magnum::Vector2i& shift);\n                    Camera& forward(Magnum::Float speed);\n                    Camera& strafe(Magnum::Float speed);\n\n                    Camera& set_speed(const Magnum::Vector2& speed);\n                    Camera& set_near_plane(Magnum::Float near_plane);\n                    Camera& set_far_plane(Magnum::Float far_plane);\n                    Camera& set_fov(Magnum::Float fov);\n                    Camera& set_camera_params(Magnum::Float near_plane, Magnum::Float far_plane, Magnum::Float fov, Magnum::Int width, Magnum::Int height);\n\n                    Magnum::Vector2 speed() const { return _speed; }\n                    Magnum::Float near_plane() const { return _near_plane; }\n                    Magnum::Float far_plane() const { return _far_plane; }\n                    Magnum::Float fov() const { return static_cast<Magnum::Float>(_fov); }\n                    Magnum::Int width() const { return _camera->viewport()[0]; }\n                    Magnum::Int height() const { return _camera->viewport()[1]; }\n                    Magnum::Matrix3 intrinsic_matrix() const;\n                    Magnum::Matrix4 extrinsic_matrix() const;\n\n                    Camera& look_at(const Magnum::Vector3& camera, const Magnum::Vector3& center, const Magnum::Vector3& up = Magnum::Vector3::zAxis());\n\n                    void transform_lights(std::vector<gs::Light>& lights) const;\n\n                    void record(bool recording, bool recording_depth = false)\n                    {\n                        _recording = recording;\n                        _recording_depth = recording_depth;\n                    }\n\n                    // FPS is mandatory here (compared to Graphics and CameraOSR)\n                    void record_video(const std::string& video_fname, int fps);\n                    bool recording() { return _recording; }\n                    bool recording_depth() { return _recording_depth; }\n\n                    Corrade::Containers::Optional<Magnum::Image2D>& image() { return _image; }\n                    Corrade::Containers::Optional<Magnum::Image2D>& depth_image() { return _depth_image; }\n\n                    void draw(Magnum::SceneGraph::DrawableGroup3D& drawables, Magnum::GL::AbstractFramebuffer& framebuffer, Magnum::PixelFormat format, RobotDARTSimu* simu, const DebugDrawData& debug_data, bool draw_debug = true);\n\n                private:\n                    Object3D* _yaw_object;\n                    Object3D* _pitch_object;\n                    Object3D* _camera_object;\n\n                    Camera3D* _camera;\n                    Magnum::Vector2 _speed{-0.01f, 0.01f};\n\n                    Magnum::Vector3 _up, _front, _right;\n                    Magnum::Float _aspect_ratio, _near_plane, _far_plane;\n                    Magnum::Rad _fov;\n                    Magnum::Int _width, _height;\n\n                    bool _recording = false, _recording_depth = false;\n                    bool _recording_video = false;\n                    Corrade::Containers::Optional<Magnum::Image2D> _image, _depth_image;\n\n                    TinyProcessLib::Process* _ffmpeg_process = nullptr;\n\n                    void _clean_up_subprocess();\n                };\n            } // namespace gs\n        } // namespace magnum\n    } // namespace gui\n} // namespace robot_dart\n\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

  • #include <Corrade/Utility/Resource.h>
  • #include <Magnum/GL/Context.h>
  • #include <Magnum/GL/Extensions.h>
  • #include <Magnum/GL/Shader.h>
  • #include <string>
"},{"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\n#include <Corrade/Utility/Resource.h>\n\n#include <Magnum/GL/Context.h>\n#include <Magnum/GL/Extensions.h>\n#include <Magnum/GL/Shader.h>\n\n#include <string>\n\nnamespace robot_dart {\n    namespace gui {\n        namespace magnum {\n            namespace gs {\n                namespace {\n                    enum : Magnum::Int { AmbientTextureLayer = 0,\n                        DiffuseTextureLayer = 1,\n                        SpecularTextureLayer = 2 };\n                }\n            } // namespace gs\n        } // namespace magnum\n    } // namespace gui\n} // namespace robot_dart\n\nnamespace Magnum {\n    namespace Shaders {\n        namespace Implementation {\n\n            inline GL::Shader createCompatibilityShader(const Utility::Resource& rs, GL::Version version, GL::Shader::Type type)\n            {\n                GL::Shader shader(version, type);\n\n#ifndef MAGNUM_TARGET_GLES\n                if (GL::Context::current().isExtensionDisabled<GL::Extensions::ARB::explicit_attrib_location>(version))\n                    shader.addSource(\"#define DISABLE_GL_ARB_explicit_attrib_location\\n\");\n                if (GL::Context::current().isExtensionDisabled<GL::Extensions::ARB::shading_language_420pack>(version))\n                    shader.addSource(\"#define DISABLE_GL_ARB_shading_language_420pack\\n\");\n                if (GL::Context::current().isExtensionDisabled<GL::Extensions::ARB::explicit_uniform_location>(version))\n                    shader.addSource(\"#define DISABLE_GL_ARB_explicit_uniform_location\\n\");\n#endif\n\n#ifndef MAGNUM_TARGET_GLES2\n                if (type == GL::Shader::Type::Vertex && GL::Context::current().isExtensionDisabled<GL::Extensions::MAGNUM::shader_vertex_id>(version))\n                    shader.addSource(\"#define DISABLE_GL_MAGNUM_shader_vertex_id\\n\");\n#endif\n\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\n                shader.addSource(\"#ifndef GL_ES\\n#define GL_ES 1\\n#endif\\n\");\n#endif\n\n                shader.addSource(rs.get(\"compatibility.glsl\"));\n                return shader;\n            }\n\n        } // namespace Implementation\n    } // namespace Shaders\n} // namespace Magnum\n\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

  • #include \"cube_map.hpp\"
  • #include \"create_compatibility_shader.hpp\"
  • #include <Magnum/GL/Texture.h>
"},{"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\n#include <Magnum/GL/Texture.h>\n\nnamespace robot_dart {\n    namespace gui {\n        namespace magnum {\n            namespace gs {\n                CubeMap::CubeMap(CubeMap::Flags flags) : _flags(flags)\n                {\n                    Corrade::Utility::Resource rs_shaders(\"RobotDARTShaders\");\n\n                    const Magnum::GL::Version version = Magnum::GL::Version::GL320;\n\n                    Magnum::GL::Shader vert = Magnum::Shaders::Implementation::createCompatibilityShader(\n                        rs_shaders, version, Magnum::GL::Shader::Type::Vertex);\n                    Magnum::GL::Shader geom = Magnum::Shaders::Implementation::createCompatibilityShader(\n                        rs_shaders, version, Magnum::GL::Shader::Type::Geometry);\n                    Magnum::GL::Shader frag = Magnum::Shaders::Implementation::createCompatibilityShader(\n                        rs_shaders, version, Magnum::GL::Shader::Type::Fragment);\n\n                    std::string defines = \"#define POSITION_ATTRIBUTE_LOCATION \" + std::to_string(Position::Location) + \"\\n\";\n                    defines += \"#define TEXTURECOORDINATES_ATTRIBUTE_LOCATION \" + std::to_string(TextureCoordinates::Location) + \"\\n\";\n\n                    vert.addSource(flags ? \"#define TEXTURED\\n\" : \"\")\n                        .addSource(defines)\n                        .addSource(rs_shaders.get(\"CubeMap.vert\"));\n                    geom.addSource(flags ? \"#define TEXTURED\\n\" : \"\")\n                        .addSource(rs_shaders.get(\"CubeMap.geom\"));\n                    frag.addSource(flags ? \"#define TEXTURED\\n\" : \"\")\n                        .addSource(rs_shaders.get(\"CubeMap.frag\"));\n\n                    CORRADE_INTERNAL_ASSERT_OUTPUT(Magnum::GL::Shader::compile({vert, geom, frag}));\n\n                    attachShaders({vert, geom, frag});\n\n                    if (!Magnum::GL::Context::current().isExtensionSupported<Magnum::GL::Extensions::ARB::explicit_attrib_location>(version)) {\n                        bindAttributeLocation(Position::Location, \"position\");\n                        if (flags)\n                            bindAttributeLocation(TextureCoordinates::Location, \"textureCoords\");\n                    }\n\n                    CORRADE_INTERNAL_ASSERT_OUTPUT(link());\n\n                    if (!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                }\n\n                CubeMap::CubeMap(Magnum::NoCreateT) noexcept : Magnum::GL::AbstractShaderProgram{Magnum::NoCreate} {}\n\n                CubeMap::Flags CubeMap::flags() const { return _flags; }\n\n                CubeMap& CubeMap::set_transformation_matrix(const Magnum::Matrix4& matrix)\n                {\n                    setUniform(_transformation_matrix_uniform, matrix);\n                    return *this;\n                }\n\n                CubeMap& CubeMap::set_shadow_matrices(Magnum::Matrix4 matrices[6])\n                {\n                    for (size_t i = 0; i < 6; i++)\n                        setUniform(_shadow_matrices_uniform + i, matrices[i]);\n                    return *this;\n                }\n\n                CubeMap& CubeMap::set_light_position(const Magnum::Vector3& position)\n                {\n                    setUniform(_light_position_uniform, position);\n                    return *this;\n                }\n\n                CubeMap& CubeMap::set_far_plane(Magnum::Float far_plane)\n                {\n                    setUniform(_far_plane_uniform, far_plane);\n                    return *this;\n                }\n\n                CubeMap& CubeMap::set_light_index(Magnum::Int index)\n                {\n                    setUniform(_light_index_uniform, index);\n                    return *this;\n                }\n\n                CubeMap& CubeMap::set_material(Material& material)\n                {\n                    if (material.has_diffuse_texture() && (_flags & Flag::DiffuseTexture)) {\n                        (*material.diffuse_texture()).bind(DiffuseTextureLayer);\n                        setUniform(_diffuse_color_uniform, Magnum::Color4{1.0f});\n                    }\n                    else\n                        setUniform(_diffuse_color_uniform, material.diffuse_color());\n\n                    return *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

  • #include <robot_dart/gui/magnum/gs/material.hpp>
  • #include <Corrade/Containers/ArrayView.h>
  • #include <Corrade/Containers/Reference.h>
  • #include <Corrade/Utility/Assert.h>
  • #include <Magnum/GL/AbstractShaderProgram.h>
  • #include <Magnum/Math/Color.h>
  • #include <Magnum/Math/Matrix4.h>
  • #include <Magnum/Shaders/Generic.h>
"},{"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\n#include <robot_dart/gui/magnum/gs/material.hpp>\n\n#include <Corrade/Containers/ArrayView.h>\n#include <Corrade/Containers/Reference.h>\n#include <Corrade/Utility/Assert.h>\n\n#include <Magnum/GL/AbstractShaderProgram.h>\n#include <Magnum/Math/Color.h>\n#include <Magnum/Math/Matrix4.h>\n#include <Magnum/Shaders/Generic.h>\n\nnamespace robot_dart {\n    namespace gui {\n        namespace magnum {\n            namespace gs {\n                class CubeMap : public Magnum::GL::AbstractShaderProgram {\n                public:\n                    using Position = Magnum::Shaders::Generic3D::Position;\n                    using TextureCoordinates = Magnum::Shaders::Generic3D::TextureCoordinates;\n\n                    enum class Flag : Magnum::UnsignedByte {\n                        DiffuseTexture = 1 << 0, \n                    };\n\n                    using Flags = Magnum::Containers::EnumSet<Flag>;\n\n                    explicit CubeMap(Flags flags = {});\n                    explicit CubeMap(Magnum::NoCreateT) noexcept;\n\n                    Flags flags() const;\n\n                    CubeMap& set_transformation_matrix(const Magnum::Matrix4& matrix);\n                    CubeMap& set_shadow_matrices(Magnum::Matrix4 matrices[6]);\n                    CubeMap& set_light_position(const Magnum::Vector3& position);\n                    CubeMap& set_far_plane(Magnum::Float far_plane);\n                    CubeMap& set_light_index(Magnum::Int index);\n                    CubeMap& set_material(Material& material);\n\n                private:\n                    Flags _flags;\n                    Magnum::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                };\n\n                CORRADE_ENUMSET_OPERATORS(CubeMap::Flags)\n            } // namespace gs\n        } // namespace magnum\n    } // namespace gui\n} // namespace robot_dart\n\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

  • #include \"cube_map_color.hpp\"
  • #include \"create_compatibility_shader.hpp\"
  • #include <Magnum/GL/CubeMapTextureArray.h>
  • #include <Magnum/GL/Texture.h>
"},{"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\n#include <Magnum/GL/CubeMapTextureArray.h>\n#include <Magnum/GL/Texture.h>\n\nnamespace robot_dart {\n    namespace gui {\n        namespace magnum {\n            namespace gs {\n                CubeMapColor::CubeMapColor(CubeMapColor::Flags flags) : _flags(flags)\n                {\n                    Corrade::Utility::Resource rs_shaders(\"RobotDARTShaders\");\n\n                    const Magnum::GL::Version version = Magnum::GL::Version::GL320;\n\n                    Magnum::GL::Shader vert = Magnum::Shaders::Implementation::createCompatibilityShader(\n                        rs_shaders, version, Magnum::GL::Shader::Type::Vertex);\n                    Magnum::GL::Shader geom = Magnum::Shaders::Implementation::createCompatibilityShader(\n                        rs_shaders, version, Magnum::GL::Shader::Type::Geometry);\n                    Magnum::GL::Shader frag = Magnum::Shaders::Implementation::createCompatibilityShader(\n                        rs_shaders, version, Magnum::GL::Shader::Type::Fragment);\n\n                    std::string defines = \"#define POSITION_ATTRIBUTE_LOCATION \" + std::to_string(Position::Location) + \"\\n\";\n                    defines += \"#define TEXTURECOORDINATES_ATTRIBUTE_LOCATION \" + std::to_string(TextureCoordinates::Location) + \"\\n\";\n\n                    vert.addSource(flags ? \"#define TEXTURED\\n\" : \"\")\n                        .addSource(defines)\n                        .addSource(rs_shaders.get(\"CubeMap.vert\"));\n                    geom.addSource(flags ? \"#define TEXTURED\\n\" : \"\")\n                        .addSource(rs_shaders.get(\"CubeMap.geom\"));\n                    frag.addSource(flags ? \"#define TEXTURED\\n\" : \"\")\n                        .addSource(rs_shaders.get(\"CubeMapColor.frag\"));\n\n                    CORRADE_INTERNAL_ASSERT_OUTPUT(Magnum::GL::Shader::compile({vert, geom, frag}));\n\n                    attachShaders({vert, geom, frag});\n\n                    if (!Magnum::GL::Context::current().isExtensionSupported<Magnum::GL::Extensions::ARB::explicit_attrib_location>(version)) {\n                        bindAttributeLocation(Position::Location, \"position\");\n                        if (flags)\n                            bindAttributeLocation(TextureCoordinates::Location, \"textureCoords\");\n                    }\n\n                    CORRADE_INTERNAL_ASSERT_OUTPUT(link());\n\n                    if (!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\n                    if (!Magnum::GL::Context::current()\n                             .isExtensionSupported<Magnum::GL::Extensions::ARB::shading_language_420pack>(version)) {\n                        setUniform(uniformLocation(\"cubeMapTextures\"), _cube_map_textures_location);\n                        if (flags) {\n                            if (flags & Flag::DiffuseTexture)\n                                setUniform(uniformLocation(\"diffuseTexture\"), DiffuseTextureLayer);\n                        }\n                    }\n                }\n\n                CubeMapColor::CubeMapColor(Magnum::NoCreateT) noexcept : Magnum::GL::AbstractShaderProgram{Magnum::NoCreate} {}\n\n                CubeMapColor::Flags CubeMapColor::flags() const { return _flags; }\n\n                CubeMapColor& CubeMapColor::set_transformation_matrix(const Magnum::Matrix4& matrix)\n                {\n                    setUniform(_transformation_matrix_uniform, matrix);\n                    return *this;\n                }\n\n                CubeMapColor& CubeMapColor::set_shadow_matrices(Magnum::Matrix4 matrices[6])\n                {\n                    for (size_t i = 0; i < 6; i++)\n                        setUniform(_shadow_matrices_uniform + i, matrices[i]);\n                    return *this;\n                }\n\n                CubeMapColor& CubeMapColor::set_light_position(const Magnum::Vector3& position)\n                {\n                    setUniform(_light_position_uniform, position);\n                    return *this;\n                }\n\n                CubeMapColor& CubeMapColor::set_far_plane(Magnum::Float far_plane)\n                {\n                    setUniform(_far_plane_uniform, far_plane);\n                    return *this;\n                }\n\n                CubeMapColor& CubeMapColor::set_light_index(Magnum::Int index)\n                {\n                    setUniform(_light_index_uniform, index);\n                    return *this;\n                }\n\n                CubeMapColor& CubeMapColor::set_material(Material& material)\n                {\n                    if (material.has_diffuse_texture() && (_flags & Flag::DiffuseTexture)) {\n                        (*material.diffuse_texture()).bind(DiffuseTextureLayer);\n                        setUniform(_diffuse_color_uniform, Magnum::Color4{1.0f});\n                    }\n                    else\n                        setUniform(_diffuse_color_uniform, material.diffuse_color());\n\n                    return *this;\n                }\n\n                CubeMapColor& CubeMapColor::bind_cube_map_texture(Magnum::GL::CubeMapTextureArray& texture)\n                {\n                    texture.bind(_cube_map_textures_location);\n                    return *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

  • #include <robot_dart/gui/magnum/gs/material.hpp>
  • #include <Corrade/Containers/ArrayView.h>
  • #include <Corrade/Containers/Reference.h>
  • #include <Corrade/Utility/Assert.h>
  • #include <Magnum/GL/AbstractShaderProgram.h>
  • #include <Magnum/Math/Color.h>
  • #include <Magnum/Math/Matrix4.h>
  • #include <Magnum/Shaders/Generic.h>
"},{"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\n#include <robot_dart/gui/magnum/gs/material.hpp>\n\n#include <Corrade/Containers/ArrayView.h>\n#include <Corrade/Containers/Reference.h>\n#include <Corrade/Utility/Assert.h>\n\n#include <Magnum/GL/AbstractShaderProgram.h>\n#include <Magnum/Math/Color.h>\n#include <Magnum/Math/Matrix4.h>\n#include <Magnum/Shaders/Generic.h>\n\nnamespace robot_dart {\n    namespace gui {\n        namespace magnum {\n            namespace gs {\n                class CubeMapColor : public Magnum::GL::AbstractShaderProgram {\n                public:\n                    using Position = Magnum::Shaders::Generic3D::Position;\n                    using TextureCoordinates = Magnum::Shaders::Generic3D::TextureCoordinates;\n\n                    enum class Flag : Magnum::UnsignedByte {\n                        DiffuseTexture = 1 << 0, \n                    };\n\n                    using Flags = Magnum::Containers::EnumSet<Flag>;\n\n                    explicit CubeMapColor(Flags flags = {});\n                    explicit CubeMapColor(Magnum::NoCreateT) noexcept;\n\n                    Flags flags() const;\n\n                    CubeMapColor& set_transformation_matrix(const Magnum::Matrix4& matrix);\n                    CubeMapColor& set_shadow_matrices(Magnum::Matrix4 matrices[6]);\n                    CubeMapColor& set_light_position(const Magnum::Vector3& position);\n                    CubeMapColor& set_far_plane(Magnum::Float far_plane);\n                    CubeMapColor& set_light_index(Magnum::Int index);\n                    CubeMapColor& set_material(Material& material);\n\n                    CubeMapColor& bind_cube_map_texture(Magnum::GL::CubeMapTextureArray& texture);\n\n                private:\n                    Flags _flags;\n                    Magnum::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                };\n\n                CORRADE_ENUMSET_OPERATORS(CubeMapColor::Flags)\n            } // namespace gs\n        } // namespace magnum\n    } // namespace gui\n} // namespace robot_dart\n\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

  • #include \"helper.hpp\"
  • #include <Corrade/Containers/ArrayViewStl.h>
  • #include <Corrade/Containers/StridedArrayView.h>
  • #include <Corrade/Utility/Algorithms.h>
  • #include <Magnum/Math/Color.h>
  • #include <Magnum/Math/PackingBatch.h>
"},{"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\n#include <Corrade/Containers/ArrayViewStl.h>\n#include <Corrade/Containers/StridedArrayView.h>\n#include <Corrade/Utility/Algorithms.h>\n\n#include <Magnum/Math/Color.h>\n#include <Magnum/Math/PackingBatch.h>\n\nnamespace robot_dart {\n    namespace gui {\n        namespace magnum {\n            namespace gs {\n                Image rgb_from_image(Magnum::Image2D* image)\n                {\n                    Image img;\n\n                    img.width = image->size().x();\n                    img.height = image->size().y();\n                    img.channels = 3;\n                    img.data.resize(image->size().product() * sizeof(Magnum::Color3ub));\n                    Corrade::Containers::StridedArrayView2D<const Magnum::Color3ub> src = image->pixels<Magnum::Color3ub>().flipped<0>();\n                    Corrade::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())}};\n                    Corrade::Utility::copy(src, dst);\n\n                    return img;\n                }\n\n                GrayscaleImage depth_from_image(Magnum::Image2D* image, bool linearize, Magnum::Float near_plane, Magnum::Float far_plane)\n                {\n                    GrayscaleImage img;\n\n                    img.width = image->size().x();\n                    img.height = image->size().y();\n                    img.data.resize(image->size().product() * sizeof(uint8_t));\n\n                    std::vector<Magnum::Float> data = std::vector<Magnum::Float>(image->size().product());\n                    Corrade::Containers::StridedArrayView2D<const Magnum::Float> src = image->pixels<Magnum::Float>().flipped<0>();\n                    Corrade::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())}};\n                    Corrade::Utility::copy(src, dst);\n\n                    if (linearize) {\n                        for (auto& depth : data)\n                            depth = (2.f * near_plane) / (far_plane + near_plane - depth * (far_plane - near_plane));\n                    }\n\n                    Corrade::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())}};\n\n                    Magnum::Math::packInto(dst, new_dst);\n\n                    return img;\n                }\n\n                DepthImage depth_array_from_image(Magnum::Image2D* image, Magnum::Float near_plane, Magnum::Float far_plane)\n                {\n                    DepthImage img;\n                    img.width = image->size().x();\n                    img.height = image->size().y();\n\n                    std::vector<Magnum::Float> data = std::vector<Magnum::Float>(image->size().product());\n                    Corrade::Containers::StridedArrayView2D<const Magnum::Float> src = image->pixels<Magnum::Float>().flipped<0>();\n                    Corrade::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())}};\n                    Corrade::Utility::copy(src, dst);\n\n                    img.data = std::vector<double>(data.begin(), data.end());\n\n                    double zNear = static_cast<double>(near_plane);\n                    double zFar = static_cast<double>(far_plane);\n\n                    // zNear * zFar / (zFar + d * (zNear - zFar));\n                    for (auto& depth : img.data)\n                        // depth = (2. * zNear) / (zFar + zNear - depth * (zFar - zNear));\n                        depth = (zNear * zFar) / (zFar - depth * (zFar - zNear));\n\n                    return 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

  • #include <robot_dart/gui/helper.hpp>
  • #include <vector>
  • #include <Magnum/Image.h>
"},{"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\n#include <robot_dart/gui/helper.hpp>\n\n#include <vector>\n\n#include <Magnum/Image.h>\n\nnamespace robot_dart {\n    namespace gui {\n        namespace magnum {\n            namespace gs {\n                Image rgb_from_image(Magnum::Image2D* image);\n                GrayscaleImage depth_from_image(Magnum::Image2D* image, bool linearize = false, Magnum::Float near_plane = 0.f, Magnum::Float far_plane = 100.f);\n                DepthImage 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\n#endif\n
"},{"location":"api/light_8cpp/","title":"File light.cpp","text":"

FileList > gs > light.cpp

Go to the source code of this file

  • #include \"light.hpp\"
  • #include <Magnum/GL/Texture.h>
"},{"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\n#include <Magnum/GL/Texture.h>\n\nnamespace robot_dart {\n    namespace gui {\n        namespace magnum {\n            namespace gs {\n                Light::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) {}\n\n                Light::Light(const Magnum::Vector4& position, const Material& material, const Magnum::Vector3& spot_direction,\n                    Magnum::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\n                // Magnum::Vector4& Light::position();\n                Magnum::Vector4 Light::position() const { return _position; }\n\n                Magnum::Vector4& Light::transformed_position() { return _transformed_position; }\n                Magnum::Vector4 Light::transformed_position() const { return _transformed_position; }\n\n                Material& Light::material() { return _material; }\n                Material Light::material() const { return _material; }\n\n                // Magnum::Vector3& Light::spot_direction() { return _spot_direction; }\n                Magnum::Vector3 Light::spot_direction() const { return _spot_direction; }\n\n                Magnum::Vector3& Light::transformed_spot_direction() { return _transformed_spot_direction; }\n                Magnum::Vector3 Light::transformed_spot_direction() const { return _transformed_spot_direction; }\n\n                Magnum::Float& Light::spot_exponent() { return _spot_exponent; }\n                Magnum::Float Light::spot_exponent() const { return _spot_exponent; }\n\n                Magnum::Float& Light::spot_cut_off() { return _spot_cut_off; }\n                Magnum::Float Light::spot_cut_off() const { return _spot_cut_off; }\n\n                Magnum::Vector4& Light::attenuation() { return _attenuation; }\n                Magnum::Vector4 Light::attenuation() const { return _attenuation; }\n\n                Magnum::Matrix4 Light::shadow_matrix() const { return _shadow_transform; }\n\n                bool Light::casts_shadows() const { return _cast_shadows; }\n\n                Light& Light::set_position(const Magnum::Vector4& position)\n                {\n                    _position = position;\n                    _transformed_position = position;\n                    return *this;\n                }\n\n                Light& Light::set_transformed_position(const Magnum::Vector4& transformed_position)\n                {\n                    _transformed_position = transformed_position;\n                    return *this;\n                }\n\n                Light& Light::set_material(const Material& material)\n                {\n                    _material = material;\n                    return *this;\n                }\n\n                Light& Light::set_spot_direction(const Magnum::Vector3& spot_direction)\n                {\n                    _spot_direction = spot_direction;\n                    _transformed_spot_direction = _spot_direction;\n                    return *this;\n                }\n\n                Light& Light::set_transformed_spot_direction(const Magnum::Vector3& transformed_spot_direction)\n                {\n                    _transformed_spot_direction = transformed_spot_direction;\n                    return *this;\n                }\n\n                Light& Light::set_spot_exponent(Magnum::Float spot_exponent)\n                {\n                    _spot_exponent = spot_exponent;\n                    return *this;\n                }\n\n                Light& Light::set_spot_cut_off(Magnum::Float spot_cut_off)\n                {\n                    _spot_cut_off = spot_cut_off;\n                    return *this;\n                }\n\n                Light& Light::set_attenuation(const Magnum::Vector4& attenuation)\n                {\n                    _attenuation = attenuation;\n                    return *this;\n                }\n\n                Light& Light::set_shadow_matrix(const Magnum::Matrix4& shadowTransform)\n                {\n                    _shadow_transform = shadowTransform;\n                    return *this;\n                }\n\n                Light& Light::set_casts_shadows(bool cast_shadows)\n                {\n                    _cast_shadows = cast_shadows;\n                    return *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

  • #include <robot_dart/gui/magnum/gs/material.hpp>
  • #include <Magnum/Math/Matrix4.h>
"},{"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\n#include <robot_dart/gui/magnum/gs/material.hpp>\n\n#include <Magnum/Math/Matrix4.h>\n\nnamespace robot_dart {\n    namespace gui {\n        namespace magnum {\n            namespace gs {\n                class Light {\n                public:\n                    Light();\n\n                    Light(const Magnum::Vector4& position, const Material& material, const Magnum::Vector3& spot_direction,\n                        Magnum::Float spot_exponent, Magnum::Float spot_cut_off, const Magnum::Vector4& attenuation, bool cast_shadows = true);\n\n                    // Magnum::Vector4& position();\n                    Magnum::Vector4 position() const;\n                    Magnum::Vector4& transformed_position();\n                    Magnum::Vector4 transformed_position() const;\n\n                    Material& material();\n                    Material material() const;\n\n                    // Magnum::Vector3& spot_direction();\n                    Magnum::Vector3 spot_direction() const;\n\n                    Magnum::Vector3& transformed_spot_direction();\n                    Magnum::Vector3 transformed_spot_direction() const;\n\n                    Magnum::Float& spot_exponent();\n                    Magnum::Float spot_exponent() const;\n\n                    Magnum::Float& spot_cut_off();\n                    Magnum::Float spot_cut_off() const;\n\n                    Magnum::Vector4& attenuation();\n                    Magnum::Vector4 attenuation() const;\n\n                    Magnum::Matrix4 shadow_matrix() const;\n                    bool casts_shadows() const;\n\n                    Light& set_position(const Magnum::Vector4& position);\n                    Light& set_transformed_position(const Magnum::Vector4& transformed_position);\n\n                    Light& set_material(const Material& material);\n\n                    Light& set_spot_direction(const Magnum::Vector3& spot_direction);\n                    Light& set_transformed_spot_direction(const Magnum::Vector3& transformed_spot_direction);\n                    Light& set_spot_exponent(Magnum::Float spot_exponent);\n                    Light& set_spot_cut_off(Magnum::Float spot_cut_off);\n\n                    Light& set_attenuation(const Magnum::Vector4& attenuation);\n\n                    Light& set_shadow_matrix(const Magnum::Matrix4& shadowTransform);\n                    Light& set_casts_shadows(bool cast_shadows);\n\n                protected:\n                    // Position for point-lights and spot-lights\n                    // Direction for directional lights (if position.w == 0)\n                    Magnum::Vector4 _position;\n                    // TO-DO: Handle dirtiness of transformed position\n                    Magnum::Vector4 _transformed_position;\n                    Material _material;\n                    Magnum::Vector3 _spot_direction;\n                    // TO-DO: Handle dirtiness of transformed spot direction\n                    Magnum::Vector3 _transformed_spot_direction;\n                    Magnum::Float _spot_exponent, _spot_cut_off;\n\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)\n                    Magnum::Vector4 _attenuation;\n\n                    // Shadow-Matrix\n                    Magnum::Matrix4 _shadow_transform{};\n\n                    // Whether it casts shadows\n                    bool _cast_shadows = true;\n                };\n\n                // Helpers for creating lights\n                inline Light create_point_light(const Magnum::Vector3& position, const Material& material,\n                    Magnum::Float intensity, const Magnum::Vector3& attenuationTerms)\n                {\n                    Light light;\n                    light.set_material(material);\n                    light.set_position(Magnum::Vector4{position, 1.f})\n                        .set_attenuation(Magnum::Vector4{attenuationTerms, intensity});\n\n                    return light;\n                }\n\n                inline Light create_spot_light(const Magnum::Vector3& position, const Material& material,\n                    const Magnum::Vector3& spot_direction, Magnum::Float spot_exponent, Magnum::Float spot_cut_off,\n                    Magnum::Float intensity, const Magnum::Vector3& attenuationTerms)\n                {\n                    return Light(Magnum::Vector4{position, 1.f}, material, spot_direction, spot_exponent, spot_cut_off,\n                        Magnum::Vector4{attenuationTerms, intensity});\n                }\n\n                inline Light create_directional_light(\n                    const Magnum::Vector3& direction, const Material& material)\n                {\n                    Light light;\n                    light.set_material(material);\n                    light.set_position(Magnum::Vector4{direction, 0.f});\n\n                    return light;\n                }\n            } // namespace gs\n        } // namespace magnum\n    } // namespace gui\n} // namespace robot_dart\n\n#endif\n
"},{"location":"api/material_8cpp/","title":"File material.cpp","text":"

FileList > gs > material.cpp

Go to the source code of this file

  • #include \"material.hpp\"
  • #include <Magnum/GL/Texture.h>
"},{"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\n#include <Magnum/GL/Texture.h>\n\nnamespace robot_dart {\n    namespace gui {\n        namespace magnum {\n            namespace gs {\n                Material::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) {}\n\n                Material::Material(const Magnum::Color4& ambient, const Magnum::Color4& diffuse,\n                    const Magnum::Color4& specular, Magnum::Float shininess) : _ambient(ambient),\n                                                                               _diffuse(diffuse),\n                                                                               _specular(specular),\n                                                                               _shininess(shininess) {}\n\n                Material::Material(Magnum::GL::Texture2D* ambient_texture,\n                    Magnum::GL::Texture2D* diffuse_texture,\n                    Magnum::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) {}\n\n                Magnum::Color4& Material::ambient_color() { return _ambient; }\n                Magnum::Color4 Material::ambient_color() const { return _ambient; }\n\n                Magnum::Color4& Material::diffuse_color() { return _diffuse; }\n                Magnum::Color4 Material::diffuse_color() const { return _diffuse; }\n\n                Magnum::Color4& Material::specular_color() { return _specular; }\n                Magnum::Color4 Material::specular_color() const { return _specular; }\n\n                Magnum::Float& Material::shininess() { return _shininess; }\n                Magnum::Float Material::shininess() const { return _shininess; }\n\n                Magnum::GL::Texture2D* Material::ambient_texture() { return _ambient_texture; }\n                Magnum::GL::Texture2D* Material::diffuse_texture() { return _diffuse_texture; }\n                Magnum::GL::Texture2D* Material::specular_texture() { return _specular_texture; }\n\n                bool Material::has_ambient_texture() const { return _ambient_texture != NULL; }\n                bool Material::has_diffuse_texture() const { return _diffuse_texture != NULL; }\n                bool Material::has_specular_texture() const { return _specular_texture != NULL; }\n\n                Material& Material::set_ambient_color(const Magnum::Color4& ambient)\n                {\n                    _ambient = ambient;\n                    return *this;\n                }\n\n                Material& Material::set_diffuse_color(const Magnum::Color4& diffuse)\n                {\n                    _diffuse = diffuse;\n                    return *this;\n                }\n\n                Material& Material::set_specular_color(const Magnum::Color4& specular)\n                {\n                    _specular = specular;\n                    return *this;\n                }\n\n                Material& Material::set_shininess(Magnum::Float shininess)\n                {\n                    _shininess = shininess;\n                    return *this;\n                }\n\n                Material& Material::set_ambient_texture(Magnum::GL::Texture2D* ambient_texture)\n                {\n                    _ambient_texture = ambient_texture;\n                    return *this;\n                }\n\n                Material& Material::set_diffuse_texture(Magnum::GL::Texture2D* diffuse_texture)\n                {\n                    _diffuse_texture = diffuse_texture;\n                    return *this;\n                }\n\n                Material& Material::set_specular_texture(Magnum::GL::Texture2D* specular_texture)\n                {\n                    _specular_texture = specular_texture;\n                    return *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

  • #include <Corrade/Containers/Optional.h>
  • #include <Magnum/GL/GL.h>
  • #include <Magnum/Magnum.h>
  • #include <Magnum/Math/Color.h>
"},{"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\n#include <Corrade/Containers/Optional.h>\n\n#include <Magnum/GL/GL.h>\n#include <Magnum/Magnum.h>\n#include <Magnum/Math/Color.h>\n\nnamespace robot_dart {\n    namespace gui {\n        namespace magnum {\n            namespace gs {\n                class Material {\n                public:\n                    Material();\n\n                    Material(const Magnum::Color4& ambient, const Magnum::Color4& diffuse,\n                        const Magnum::Color4& specular, Magnum::Float shininess);\n\n                    Material(Magnum::GL::Texture2D* ambient_texture,\n                        Magnum::GL::Texture2D* diffuse_texture,\n                        Magnum::GL::Texture2D* specular_texture, Magnum::Float shininess);\n\n                    Magnum::Color4& ambient_color();\n                    Magnum::Color4 ambient_color() const;\n\n                    Magnum::Color4& diffuse_color();\n                    Magnum::Color4 diffuse_color() const;\n\n                    Magnum::Color4& specular_color();\n                    Magnum::Color4 specular_color() const;\n\n                    Magnum::Float& shininess();\n                    Magnum::Float shininess() const;\n\n                    Magnum::GL::Texture2D* ambient_texture();\n                    Magnum::GL::Texture2D* diffuse_texture();\n                    Magnum::GL::Texture2D* specular_texture();\n\n                    bool has_ambient_texture() const;\n                    bool has_diffuse_texture() const;\n                    bool has_specular_texture() const;\n\n                    Material& set_ambient_color(const Magnum::Color4& ambient);\n                    Material& set_diffuse_color(const Magnum::Color4& diffuse);\n                    Material& set_specular_color(const Magnum::Color4& specular);\n                    Material& set_shininess(Magnum::Float shininess);\n\n                    Material& set_ambient_texture(Magnum::GL::Texture2D* ambient_texture);\n                    Material& set_diffuse_texture(Magnum::GL::Texture2D* diffuse_texture);\n                    Material& set_specular_texture(Magnum::GL::Texture2D* specular_texture);\n\n                protected:\n                    Magnum::Color4 _ambient, _diffuse, _specular;\n                    Magnum::Float _shininess;\n                    Magnum::GL::Texture2D* _ambient_texture = NULL;\n                    Magnum::GL::Texture2D* _diffuse_texture = NULL;\n                    Magnum::GL::Texture2D* _specular_texture = NULL;\n                };\n            } // namespace gs\n        } // namespace magnum\n    } // namespace gui\n} // namespace robot_dart\n\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

  • #include \"phong_multi_light.hpp\"
  • #include \"create_compatibility_shader.hpp\"
  • #include <Magnum/GL/CubeMapTextureArray.h>
  • #include <Magnum/GL/Texture.h>
  • #include <Magnum/GL/TextureArray.h>
"},{"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\n#include <Magnum/GL/CubeMapTextureArray.h>\n#include <Magnum/GL/Texture.h>\n#include <Magnum/GL/TextureArray.h>\n\nnamespace robot_dart {\n    namespace gui {\n        namespace magnum {\n            namespace gs {\n                PhongMultiLight::PhongMultiLight(PhongMultiLight::Flags flags, Magnum::Int max_lights) : _flags(flags), _max_lights(max_lights)\n                {\n                    Corrade::Utility::Resource rs_shaders(\"RobotDARTShaders\");\n\n                    const Magnum::GL::Version version = Magnum::GL::Version::GL320;\n\n                    Magnum::GL::Shader vert = Magnum::Shaders::Implementation::createCompatibilityShader(\n                        rs_shaders, version, Magnum::GL::Shader::Type::Vertex);\n                    Magnum::GL::Shader frag = Magnum::Shaders::Implementation::createCompatibilityShader(\n                        rs_shaders, version, Magnum::GL::Shader::Type::Fragment);\n\n                    std::string defines = \"#define LIGHT_COUNT \" + std::to_string(_max_lights) + \"\\n\";\n                    defines += \"#define POSITION_ATTRIBUTE_LOCATION \" + std::to_string(Position::Location) + \"\\n\";\n                    defines += \"#define NORMAL_ATTRIBUTE_LOCATION \" + std::to_string(Normal::Location) + \"\\n\";\n                    defines += \"#define TEXTURECOORDINATES_ATTRIBUTE_LOCATION \" + std::to_string(TextureCoordinates::Location) + \"\\n\";\n\n                    vert.addSource(flags ? \"#define TEXTURED\\n\" : \"\")\n                        .addSource(defines)\n                        .addSource(rs_shaders.get(\"PhongMultiLight.vert\"));\n                    frag.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\"));\n\n                    CORRADE_INTERNAL_ASSERT_OUTPUT(Magnum::GL::Shader::compile({vert, frag}));\n\n                    attachShaders({vert, frag});\n\n                    if (!Magnum::GL::Context::current().isExtensionSupported<Magnum::GL::Extensions::ARB::explicit_attrib_location>(version)) {\n                        bindAttributeLocation(Position::Location, \"position\");\n                        bindAttributeLocation(Normal::Location, \"normal\");\n                        if (flags)\n                            bindAttributeLocation(TextureCoordinates::Location, \"textureCoords\");\n                    }\n\n                    CORRADE_INTERNAL_ASSERT_OUTPUT(link());\n\n                    /* Get light matrices uniform */\n                    _lights_matrices_uniform = uniformLocation(\"lightMatrices[0]\");\n\n                    if (!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                    }\n\n                    if (!Magnum::GL::Context::current()\n                             .isExtensionSupported<Magnum::GL::Extensions::ARB::shading_language_420pack>(version)) {\n                        setUniform(uniformLocation(\"shadowTextures\"), _shadow_textures_location);\n                        setUniform(uniformLocation(\"cubeMapTextures\"), _cube_map_textures_location);\n                        setUniform(uniformLocation(\"shadowColorTextures\"), _shadow_color_textures_location);\n                        setUniform(uniformLocation(\"cubeMapColorTextures\"), _cube_map_color_textures_location);\n                        if (flags) {\n                            if (flags & Flag::AmbientTexture)\n                                setUniform(uniformLocation(\"ambientTexture\"), AmbientTextureLayer);\n                            if (flags & Flag::DiffuseTexture)\n                                setUniform(uniformLocation(\"diffuseTexture\"), DiffuseTextureLayer);\n                            if (flags & Flag::SpecularTexture)\n                                setUniform(uniformLocation(\"specularTexture\"), SpecularTextureLayer);\n                        }\n                    }\n\n                    /* Set defaults (normally they are set in shader code itself, but just in case) */\n                    Material material;\n\n                    /* Default to fully opaque white so we can see the textures */\n                    if (flags & Flag::AmbientTexture)\n                        material.set_ambient_color(Magnum::Color4{1.0f});\n                    else\n                        material.set_ambient_color(Magnum::Color4{0.0f, 1.0f});\n\n                    if (flags & Flag::DiffuseTexture)\n                        material.set_diffuse_color(Magnum::Color4{1.0f});\n\n                    material.set_specular_color(Magnum::Color4{1.0f});\n                    material.set_shininess(80.0f);\n\n                    set_material(material);\n\n                    /* Lights defaults need to be set by code */\n                    /* All lights are disabled i.e., color equal to black */\n                    Light light;\n                    for (Magnum::Int i = 0; i < _max_lights; i++)\n                        set_light(i, light);\n                }\n\n                PhongMultiLight::PhongMultiLight(Magnum::NoCreateT) noexcept : Magnum::GL::AbstractShaderProgram{Magnum::NoCreate} {}\n\n                PhongMultiLight::Flags PhongMultiLight::flags() const { return _flags; }\n\n                PhongMultiLight& PhongMultiLight::set_material(Material& material)\n                {\n                    // TO-DO: Check if we should do this or let the user define the proper\n                    // material\n                    if (material.has_ambient_texture() && (_flags & Flag::AmbientTexture)) {\n                        (*material.ambient_texture()).bind(AmbientTextureLayer);\n                        setUniform(_ambient_color_uniform, Magnum::Color4{1.0f});\n                    }\n                    else\n                        setUniform(_ambient_color_uniform, material.ambient_color());\n\n                    if (material.has_diffuse_texture() && (_flags & Flag::DiffuseTexture)) {\n                        (*material.diffuse_texture()).bind(DiffuseTextureLayer);\n                        setUniform(_diffuse_color_uniform, Magnum::Color4{1.0f});\n                    }\n                    else\n                        setUniform(_diffuse_color_uniform, material.diffuse_color());\n\n                    if (material.has_specular_texture() && (_flags & Flag::SpecularTexture)) {\n                        (*material.specular_texture()).bind(SpecularTextureLayer);\n                        setUniform(_specular_color_uniform, Magnum::Color4{1.0f});\n                    }\n                    else\n                        setUniform(_specular_color_uniform, material.specular_color());\n\n                    setUniform(_shininess_uniform, material.shininess());\n\n                    return *this;\n                }\n\n                PhongMultiLight& PhongMultiLight::set_light(Magnum::Int i, const Light& light)\n                {\n                    CORRADE_INTERNAL_ASSERT(i >= 0 && i < _max_lights);\n                    Magnum::Vector4 attenuation = light.attenuation();\n\n                    // light position\n                    setUniform(_lights_uniform + i * _light_loc_size, light.transformed_position());\n                    // light material\n                    setUniform(_lights_uniform + i * _light_loc_size + 1, light.material().ambient_color());\n                    setUniform(_lights_uniform + i * _light_loc_size + 2, light.material().diffuse_color());\n                    setUniform(_lights_uniform + i * _light_loc_size + 3, light.material().specular_color());\n                    // spotlight properties\n                    setUniform(_lights_uniform + i * _light_loc_size + 4, light.transformed_spot_direction());\n                    setUniform(_lights_uniform + i * _light_loc_size + 5, light.spot_exponent());\n                    setUniform(_lights_uniform + i * _light_loc_size + 6, light.spot_cut_off());\n                    // intesity\n                    setUniform(_lights_uniform + i * _light_loc_size + 7, attenuation[3]);\n                    // constant attenuation term\n                    setUniform(_lights_uniform + i * _light_loc_size + 8, attenuation[0]);\n                    // linear attenuation term\n                    setUniform(_lights_uniform + i * _light_loc_size + 9, attenuation[1]);\n                    // quadratic attenuation term\n                    setUniform(_lights_uniform + i * _light_loc_size + 10, attenuation[2]);\n                    // world position\n                    setUniform(_lights_uniform + i * _light_loc_size + 11, light.position());\n                    // casts shadows?\n                    setUniform(_lights_uniform + i * _light_loc_size + 12, light.casts_shadows());\n\n                    setUniform(_lights_matrices_uniform + i, light.shadow_matrix());\n\n                    return *this;\n                }\n\n                PhongMultiLight& PhongMultiLight::set_transformation_matrix(const Magnum::Matrix4& matrix)\n                {\n                    setUniform(_transformation_matrix_uniform, matrix);\n                    return *this;\n                }\n\n                PhongMultiLight& PhongMultiLight::set_camera_matrix(const Magnum::Matrix4& matrix)\n                {\n                    setUniform(_camera_matrix_uniform, matrix);\n                    return *this;\n                }\n\n                PhongMultiLight& PhongMultiLight::set_normal_matrix(const Magnum::Matrix3x3& matrix)\n                {\n                    setUniform(_normal_matrix_uniform, matrix);\n                    return *this;\n                }\n\n                PhongMultiLight& PhongMultiLight::set_projection_matrix(const Magnum::Matrix4& matrix)\n                {\n                    setUniform(_projection_matrix_uniform, matrix);\n                    return *this;\n                }\n\n                PhongMultiLight& PhongMultiLight::set_far_plane(Magnum::Float far_plane)\n                {\n                    setUniform(_far_plane_uniform, far_plane);\n                    return *this;\n                }\n\n                PhongMultiLight& PhongMultiLight::set_is_shadowed(bool shadows)\n                {\n                    setUniform(_is_shadowed_uniform, shadows);\n                    return *this;\n                }\n\n                PhongMultiLight& PhongMultiLight::set_transparent_shadows(bool shadows)\n                {\n                    setUniform(_transparent_shadows_uniform, shadows);\n                    return *this;\n                }\n\n                PhongMultiLight& PhongMultiLight::set_specular_strength(Magnum::Float specular_strength)\n                {\n                    setUniform(_specular_strength_uniform, std::max(0.f, specular_strength));\n                    return *this;\n                }\n\n                PhongMultiLight& PhongMultiLight::bind_shadow_texture(Magnum::GL::Texture2DArray& texture)\n                {\n                    texture.bind(_shadow_textures_location);\n                    return *this;\n                }\n\n                PhongMultiLight& PhongMultiLight::bind_shadow_color_texture(Magnum::GL::Texture2DArray& texture)\n                {\n                    texture.bind(_shadow_color_textures_location);\n                    return *this;\n                }\n\n                PhongMultiLight& PhongMultiLight::bind_cube_map_texture(Magnum::GL::CubeMapTextureArray& texture)\n                {\n                    texture.bind(_cube_map_textures_location);\n                    return *this;\n                }\n\n                PhongMultiLight& PhongMultiLight::bind_cube_map_color_texture(Magnum::GL::CubeMapTextureArray& texture)\n                {\n                    texture.bind(_cube_map_color_textures_location);\n                    return *this;\n                }\n\n                Magnum::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

  • #include <robot_dart/gui/magnum/gs/light.hpp>
  • #include <Corrade/Containers/ArrayView.h>
  • #include <Corrade/Containers/Reference.h>
  • #include <Corrade/Utility/Assert.h>
  • #include <Magnum/GL/AbstractShaderProgram.h>
  • #include <Magnum/Math/Color.h>
  • #include <Magnum/Math/Matrix4.h>
  • #include <Magnum/Shaders/Generic.h>
"},{"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\n#include <robot_dart/gui/magnum/gs/light.hpp>\n\n#include <Corrade/Containers/ArrayView.h>\n#include <Corrade/Containers/Reference.h>\n#include <Corrade/Utility/Assert.h>\n\n#include <Magnum/GL/AbstractShaderProgram.h>\n#include <Magnum/Math/Color.h>\n#include <Magnum/Math/Matrix4.h>\n#include <Magnum/Shaders/Generic.h>\n\nnamespace robot_dart {\n    namespace gui {\n        namespace magnum {\n            namespace gs {\n                class PhongMultiLight : public Magnum::GL::AbstractShaderProgram {\n                public:\n                    using Position = Magnum::Shaders::Generic3D::Position;\n                    using Normal = Magnum::Shaders::Generic3D::Normal;\n                    using TextureCoordinates = Magnum::Shaders::Generic3D::TextureCoordinates;\n\n                    enum class Flag : Magnum::UnsignedByte {\n                        AmbientTexture = 1 << 0, \n                        DiffuseTexture = 1 << 1, \n                        SpecularTexture = 1 << 2 \n                    };\n\n                    using Flags = Magnum::Containers::EnumSet<Flag>;\n\n                    explicit PhongMultiLight(Flags flags = {}, Magnum::Int max_lights = 10);\n                    explicit PhongMultiLight(Magnum::NoCreateT) noexcept;\n\n                    Flags flags() const;\n\n                    PhongMultiLight& set_material(Material& material);\n                    PhongMultiLight& set_light(Magnum::Int i, const Light& light);\n\n                    PhongMultiLight& set_transformation_matrix(const Magnum::Matrix4& matrix);\n                    PhongMultiLight& set_camera_matrix(const Magnum::Matrix4& matrix);\n                    PhongMultiLight& set_normal_matrix(const Magnum::Matrix3x3& matrix);\n                    PhongMultiLight& set_projection_matrix(const Magnum::Matrix4& matrix);\n\n                    PhongMultiLight& set_far_plane(Magnum::Float far_plane);\n                    PhongMultiLight& set_is_shadowed(bool shadows);\n                    PhongMultiLight& set_transparent_shadows(bool shadows);\n                    PhongMultiLight& set_specular_strength(Magnum::Float specular_strength);\n\n                    PhongMultiLight& bind_shadow_texture(Magnum::GL::Texture2DArray& texture);\n                    PhongMultiLight& bind_shadow_color_texture(Magnum::GL::Texture2DArray& texture);\n                    PhongMultiLight& bind_cube_map_texture(Magnum::GL::CubeMapTextureArray& texture);\n                    PhongMultiLight& bind_cube_map_color_texture(Magnum::GL::CubeMapTextureArray& texture);\n\n                    Magnum::Int max_lights() const;\n\n                private:\n                    Flags _flags;\n                    Magnum::Int _max_lights = 10;\n                    Magnum::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};\n                    const Magnum::Int _light_loc_size = 13;\n                };\n\n                CORRADE_ENUMSET_OPERATORS(PhongMultiLight::Flags)\n            } // namespace gs\n        } // namespace magnum\n    } // namespace gui\n} // namespace robot_dart\n\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

  • #include \"shadow_map.hpp\"
  • #include \"create_compatibility_shader.hpp\"
  • #include <Magnum/GL/Texture.h>
"},{"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\n#include <Magnum/GL/Texture.h>\n\nnamespace robot_dart {\n    namespace gui {\n        namespace magnum {\n            namespace gs {\n                ShadowMap::ShadowMap(ShadowMap::Flags flags) : _flags(flags)\n                {\n                    Corrade::Utility::Resource rs_shaders(\"RobotDARTShaders\");\n\n                    const Magnum::GL::Version version = Magnum::GL::Version::GL320;\n\n                    Magnum::GL::Shader vert = Magnum::Shaders::Implementation::createCompatibilityShader(\n                        rs_shaders, version, Magnum::GL::Shader::Type::Vertex);\n                    Magnum::GL::Shader frag = Magnum::Shaders::Implementation::createCompatibilityShader(\n                        rs_shaders, version, Magnum::GL::Shader::Type::Fragment);\n\n                    std::string defines = \"#define POSITION_ATTRIBUTE_LOCATION \" + std::to_string(Position::Location) + \"\\n\";\n                    defines += \"#define TEXTURECOORDINATES_ATTRIBUTE_LOCATION \" + std::to_string(TextureCoordinates::Location) + \"\\n\";\n\n                    vert.addSource(flags ? \"#define TEXTURED\\n\" : \"\")\n                        .addSource(defines)\n                        .addSource(rs_shaders.get(\"ShadowMap.vert\"));\n                    frag.addSource(flags ? \"#define TEXTURED\\n\" : \"\")\n                        .addSource(rs_shaders.get(\"ShadowMap.frag\"));\n\n                    CORRADE_INTERNAL_ASSERT_OUTPUT(Magnum::GL::Shader::compile({vert, frag}));\n\n                    attachShaders({vert, frag});\n\n                    if (!Magnum::GL::Context::current().isExtensionSupported<Magnum::GL::Extensions::ARB::explicit_attrib_location>(version)) {\n                        bindAttributeLocation(Position::Location, \"position\");\n                        if (flags)\n                            bindAttributeLocation(TextureCoordinates::Location, \"textureCoords\");\n                    }\n\n                    CORRADE_INTERNAL_ASSERT_OUTPUT(link());\n\n                    if (!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                    }\n\n                    if (!Magnum::GL::Context::current()\n                             .isExtensionSupported<Magnum::GL::Extensions::ARB::shading_language_420pack>(version)\n                        && flags) {\n                        setUniform(uniformLocation(\"diffuseTexture\"), DiffuseTextureLayer);\n                    }\n                }\n\n                ShadowMap::ShadowMap(Magnum::NoCreateT) noexcept : Magnum::GL::AbstractShaderProgram{Magnum::NoCreate} {}\n\n                ShadowMap::Flags ShadowMap::flags() const { return _flags; }\n\n                ShadowMap& ShadowMap::set_transformation_matrix(const Magnum::Matrix4& matrix)\n                {\n                    setUniform(_transformation_matrix_uniform, matrix);\n                    return *this;\n                }\n\n                ShadowMap& ShadowMap::set_projection_matrix(const Magnum::Matrix4& matrix)\n                {\n                    setUniform(_projection_matrix_uniform, matrix);\n                    return *this;\n                }\n\n                ShadowMap& ShadowMap::set_material(Material& material)\n                {\n                    if (material.has_diffuse_texture() && (_flags & Flag::DiffuseTexture)) {\n                        (*material.diffuse_texture()).bind(DiffuseTextureLayer);\n                        setUniform(_diffuse_color_uniform, Magnum::Color4{1.0f});\n                    }\n                    else\n                        setUniform(_diffuse_color_uniform, material.diffuse_color());\n\n                    return *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

  • #include <robot_dart/gui/magnum/gs/material.hpp>
  • #include <Corrade/Containers/ArrayView.h>
  • #include <Corrade/Containers/Reference.h>
  • #include <Corrade/Utility/Assert.h>
  • #include <Magnum/GL/AbstractShaderProgram.h>
  • #include <Magnum/Math/Color.h>
  • #include <Magnum/Math/Matrix4.h>
  • #include <Magnum/Shaders/Generic.h>
"},{"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\n#include <robot_dart/gui/magnum/gs/material.hpp>\n\n#include <Corrade/Containers/ArrayView.h>\n#include <Corrade/Containers/Reference.h>\n#include <Corrade/Utility/Assert.h>\n\n#include <Magnum/GL/AbstractShaderProgram.h>\n#include <Magnum/Math/Color.h>\n#include <Magnum/Math/Matrix4.h>\n#include <Magnum/Shaders/Generic.h>\n\nnamespace robot_dart {\n    namespace gui {\n        namespace magnum {\n            namespace gs {\n                class ShadowMap : public Magnum::GL::AbstractShaderProgram {\n                public:\n                    using Position = Magnum::Shaders::Generic3D::Position;\n                    using TextureCoordinates = Magnum::Shaders::Generic3D::TextureCoordinates;\n\n                    enum class Flag : Magnum::UnsignedByte {\n                        DiffuseTexture = 1 << 0, \n                    };\n\n                    using Flags = Magnum::Containers::EnumSet<Flag>;\n\n                    explicit ShadowMap(Flags flags = {});\n                    explicit ShadowMap(Magnum::NoCreateT) noexcept;\n\n                    Flags flags() const;\n\n                    ShadowMap& set_transformation_matrix(const Magnum::Matrix4& matrix);\n                    ShadowMap& set_projection_matrix(const Magnum::Matrix4& matrix);\n                    ShadowMap& set_material(Material& material);\n\n                private:\n                    Flags _flags;\n                    Magnum::Int _transformation_matrix_uniform{0}, _projection_matrix_uniform{1}, _diffuse_color_uniform{2};\n                };\n\n                CORRADE_ENUMSET_OPERATORS(ShadowMap::Flags)\n            } // namespace gs\n        } // namespace magnum\n    } // namespace gui\n} // namespace robot_dart\n\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

  • #include \"shadow_map_color.hpp\"
  • #include \"create_compatibility_shader.hpp\"
  • #include <Magnum/GL/Texture.h>
"},{"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\n#include <Magnum/GL/Texture.h>\n\nnamespace robot_dart {\n    namespace gui {\n        namespace magnum {\n            namespace gs {\n                ShadowMapColor::ShadowMapColor(ShadowMapColor::Flags flags) : _flags(flags)\n                {\n                    Corrade::Utility::Resource rs_shaders(\"RobotDARTShaders\");\n\n                    const Magnum::GL::Version version = Magnum::GL::Version::GL320;\n\n                    Magnum::GL::Shader vert = Magnum::Shaders::Implementation::createCompatibilityShader(\n                        rs_shaders, version, Magnum::GL::Shader::Type::Vertex);\n                    Magnum::GL::Shader frag = Magnum::Shaders::Implementation::createCompatibilityShader(\n                        rs_shaders, version, Magnum::GL::Shader::Type::Fragment);\n\n                    std::string defines = \"#define POSITION_ATTRIBUTE_LOCATION \" + std::to_string(Position::Location) + \"\\n\";\n                    defines += \"#define TEXTURECOORDINATES_ATTRIBUTE_LOCATION \" + std::to_string(TextureCoordinates::Location) + \"\\n\";\n\n                    vert.addSource(flags ? \"#define TEXTURED\\n\" : \"\")\n                        .addSource(defines)\n                        .addSource(rs_shaders.get(\"ShadowMap.vert\"));\n                    frag.addSource(flags ? \"#define TEXTURED\\n\" : \"\")\n                        .addSource(rs_shaders.get(\"ShadowMapColor.frag\"));\n\n                    CORRADE_INTERNAL_ASSERT_OUTPUT(Magnum::GL::Shader::compile({vert, frag}));\n\n                    attachShaders({vert, frag});\n\n                    if (!Magnum::GL::Context::current().isExtensionSupported<Magnum::GL::Extensions::ARB::explicit_attrib_location>(version)) {\n                        bindAttributeLocation(Position::Location, \"position\");\n                        if (flags)\n                            bindAttributeLocation(TextureCoordinates::Location, \"textureCoords\");\n                    }\n\n                    CORRADE_INTERNAL_ASSERT_OUTPUT(link());\n\n                    if (!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                    }\n\n                    if (!Magnum::GL::Context::current()\n                             .isExtensionSupported<Magnum::GL::Extensions::ARB::shading_language_420pack>(version)\n                        && flags) {\n                        setUniform(uniformLocation(\"diffuseTexture\"), DiffuseTextureLayer);\n                    }\n                }\n\n                ShadowMapColor::ShadowMapColor(Magnum::NoCreateT) noexcept : Magnum::GL::AbstractShaderProgram{Magnum::NoCreate} {}\n\n                ShadowMapColor::Flags ShadowMapColor::flags() const { return _flags; }\n\n                ShadowMapColor& ShadowMapColor::set_transformation_matrix(const Magnum::Matrix4& matrix)\n                {\n                    setUniform(_transformation_matrix_uniform, matrix);\n                    return *this;\n                }\n\n                ShadowMapColor& ShadowMapColor::set_projection_matrix(const Magnum::Matrix4& matrix)\n                {\n                    setUniform(_projection_matrix_uniform, matrix);\n                    return *this;\n                }\n\n                ShadowMapColor& ShadowMapColor::set_material(Material& material)\n                {\n                    if (material.has_diffuse_texture() && (_flags & Flag::DiffuseTexture)) {\n                        (*material.diffuse_texture()).bind(DiffuseTextureLayer);\n                        setUniform(_diffuse_color_uniform, Magnum::Color4{1.0f});\n                    }\n                    else\n                        setUniform(_diffuse_color_uniform, material.diffuse_color());\n\n                    return *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

  • #include <robot_dart/gui/magnum/gs/material.hpp>
  • #include <Corrade/Containers/ArrayView.h>
  • #include <Corrade/Containers/Reference.h>
  • #include <Corrade/Utility/Assert.h>
  • #include <Magnum/GL/AbstractShaderProgram.h>
  • #include <Magnum/Math/Color.h>
  • #include <Magnum/Math/Matrix4.h>
  • #include <Magnum/Shaders/Generic.h>
"},{"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\n#include <robot_dart/gui/magnum/gs/material.hpp>\n\n#include <Corrade/Containers/ArrayView.h>\n#include <Corrade/Containers/Reference.h>\n#include <Corrade/Utility/Assert.h>\n\n#include <Magnum/GL/AbstractShaderProgram.h>\n#include <Magnum/Math/Color.h>\n#include <Magnum/Math/Matrix4.h>\n#include <Magnum/Shaders/Generic.h>\n\nnamespace robot_dart {\n    namespace gui {\n        namespace magnum {\n            namespace gs {\n                class ShadowMapColor : public Magnum::GL::AbstractShaderProgram {\n                public:\n                    using Position = Magnum::Shaders::Generic3D::Position;\n                    using TextureCoordinates = Magnum::Shaders::Generic3D::TextureCoordinates;\n\n                    enum class Flag : Magnum::UnsignedByte {\n                        DiffuseTexture = 1 << 0, \n                    };\n\n                    using Flags = Magnum::Containers::EnumSet<Flag>;\n\n                    explicit ShadowMapColor(Flags flags = {});\n                    explicit ShadowMapColor(Magnum::NoCreateT) noexcept;\n\n                    Flags flags() const;\n\n                    ShadowMapColor& set_transformation_matrix(const Magnum::Matrix4& matrix);\n                    ShadowMapColor& set_projection_matrix(const Magnum::Matrix4& matrix);\n                    ShadowMapColor& set_material(Material& material);\n\n                private:\n                    Flags _flags;\n                    Magnum::Int _transformation_matrix_uniform{0}, _projection_matrix_uniform{1}, _diffuse_color_uniform{2};\n                };\n\n                CORRADE_ENUMSET_OPERATORS(ShadowMapColor::Flags)\n            } // namespace gs\n        } // namespace magnum\n    } // namespace gui\n} // namespace robot_dart\n\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

  • #include \"camera.hpp\"
  • #include <Corrade/Containers/ArrayViewStl.h>
  • #include <Corrade/Containers/StridedArrayView.h>
  • #include <Corrade/Utility/Algorithms.h>
  • #include <Magnum/GL/PixelFormat.h>
  • #include <Magnum/GL/RenderbufferFormat.h>
  • #include <Magnum/GL/Renderer.h>
  • #include <Magnum/GL/TextureFormat.h>
  • #include <Magnum/ImageView.h>
  • #include <Magnum/PixelFormat.h>
  • #include <robot_dart/gui/magnum/utils_headers_eigen.hpp>
"},{"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":"

File: api/sensor_2camera_8cpp_source.md

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

  • #include <robot_dart/gui/magnum/base_application.hpp>
  • #include <robot_dart/gui/magnum/gs/helper.hpp>
  • #include <robot_dart/sensor/sensor.hpp>
  • #include <Magnum/GL/Framebuffer.h>
  • #include <Magnum/GL/Renderbuffer.h>
  • #include <Magnum/PixelFormat.h>
"},{"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\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\n#include <Magnum/GL/Framebuffer.h>\n#include <Magnum/GL/Renderbuffer.h>\n#include <Magnum/PixelFormat.h>\n\nnamespace robot_dart {\n    namespace gui {\n        namespace magnum {\n            namespace sensor {\n                class Camera : public robot_dart::sensor::Sensor {\n                public:\n                    Camera(BaseApplication* app, size_t width, size_t height, size_t freq = 30, bool draw_debug = false);\n                    ~Camera() {}\n\n                    void init() override;\n\n                    void calculate(double) override;\n\n                    std::string type() const override;\n\n                    void attach_to_body(dart::dynamics::BodyNode* body, const Eigen::Isometry3d& tf = Eigen::Isometry3d::Identity()) override;\n\n                    void attach_to_joint(dart::dynamics::Joint*, const Eigen::Isometry3d&) override\n                    {\n                        ROBOT_DART_WARNING(true, \"You cannot attach a camera to a joint!\");\n                    }\n\n                    gs::Camera& camera() { return *_camera; }\n                    const gs::Camera& camera() const { return *_camera; }\n\n                    Eigen::Matrix3d camera_intrinsic_matrix() const;\n                    Eigen::Matrix4d camera_extrinsic_matrix() const;\n\n                    bool drawing_debug() const { return _draw_debug; }\n                    void draw_debug(bool draw = true) { _draw_debug = draw; }\n\n                    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));\n\n                    // this will use the default FPS of the camera if fps == -1\n                    void record_video(const std::string& video_fname)\n                    {\n                        _camera->record_video(video_fname, _frequency);\n                    }\n\n                    Magnum::Image2D* magnum_image()\n                    {\n                        if (_camera->image())\n                            return &(*_camera->image());\n                        return nullptr;\n                    }\n\n                    Image image()\n                    {\n                        auto image = magnum_image();\n                        if (image)\n                            return gs::rgb_from_image(image);\n                        return Image();\n                    }\n\n                    Magnum::Image2D* magnum_depth_image()\n                    {\n                        if (_camera->depth_image())\n                            return &(*_camera->depth_image());\n                        return nullptr;\n                    }\n\n                    // This is for visualization purposes\n                    GrayscaleImage depth_image();\n\n                    // Image filled with depth buffer values\n                    GrayscaleImage raw_depth_image();\n\n                    // \"Image\" filled with depth buffer values (this returns an array of doubles)\n                    DepthImage depth_array();\n\n                protected:\n                    Magnum::GL::Framebuffer _framebuffer{Magnum::NoCreate};\n                    Magnum::PixelFormat _format;\n                    Magnum::GL::Renderbuffer _color, _depth;\n\n                    BaseApplication* _magnum_app;\n                    size_t _width, _height;\n\n                    std::unique_ptr<gs::Camera> _camera;\n\n                    bool _draw_debug;\n                };\n            } // namespace sensor\n        } // namespace magnum\n    } // namespace gui\n\n    namespace sensor {\n        using gui::magnum::sensor::Camera;\n    }\n} // namespace robot_dart\n\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

  • #include <Magnum/SceneGraph/Camera.h>
  • #include <Magnum/SceneGraph/MatrixTransformation3D.h>
  • #include <Magnum/SceneGraph/Scene.h>
"},{"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\n#include <Magnum/SceneGraph/Camera.h>\n#include <Magnum/SceneGraph/MatrixTransformation3D.h>\n#include <Magnum/SceneGraph/Scene.h>\n\nnamespace robot_dart {\n    namespace gui {\n        namespace magnum {\n            using Object3D = Magnum::SceneGraph::Object<Magnum::SceneGraph::MatrixTransformation3D>;\n            using Scene3D = Magnum::SceneGraph::Scene<Magnum::SceneGraph::MatrixTransformation3D>;\n            using Camera3D = Magnum::SceneGraph::Camera3D;\n        } // namespace magnum\n    } // namespace gui\n} // namespace robot_dart\n\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

  • #include <Magnum/EigenIntegration/GeometryIntegration.h>
  • #include <Magnum/EigenIntegration/Integration.h>

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\n#pragma GCC system_header\n\n#include <Magnum/EigenIntegration/GeometryIntegration.h>\n#include <Magnum/EigenIntegration/Integration.h>\n\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

  • #include \"windowless_gl_application.hpp\"
  • #include <Magnum/GL/RenderbufferFormat.h>
  • #include <Magnum/GL/Renderer.h>
"},{"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":"

File: api/windowless__gl__application_8cpp_source.md

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

  • #include <robot_dart/gui/magnum/base_application.hpp>
  • #include <Magnum/GL/Renderbuffer.h>
  • #include <Magnum/PixelFormat.h>
"},{"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\n#include <robot_dart/gui/magnum/base_application.hpp>\n\n#include <Magnum/GL/Renderbuffer.h>\n#include <Magnum/PixelFormat.h>\n\nnamespace robot_dart {\n    namespace gui {\n        namespace magnum {\n            class WindowlessGLApplication : public BaseApplication, public Magnum::Platform::WindowlessApplication {\n            public:\n                explicit WindowlessGLApplication(int argc, char** argv, RobotDARTSimu* simu, const GraphicsConfiguration& configuration = GraphicsConfiguration());\n                ~WindowlessGLApplication();\n\n                void render() override;\n\n            protected:\n                RobotDARTSimu* _simu;\n                bool _draw_main_camera, _draw_debug;\n                Magnum::Color4 _bg_color;\n                Magnum::GL::Framebuffer _framebuffer{Magnum::NoCreate};\n                Magnum::PixelFormat _format;\n                Magnum::GL::Renderbuffer _color{Magnum::NoCreate}, _depth{Magnum::NoCreate};\n                // size_t _index = 0;\n\n                virtual int exec() override { return 0; }\n            };\n        } // namespace magnum\n    } // namespace gui\n} // namespace robot_dart\n\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

  • #include <robot_dart/gui/magnum/windowless_graphics.hpp>
"},{"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>\n\nnamespace robot_dart {\n    namespace gui {\n        namespace magnum {\n            void WindowlessGraphics::set_simu(RobotDARTSimu* simu)\n            {\n                BaseGraphics<WindowlessGLApplication>::set_simu(simu);\n                // we should not synchronize by default if we want windowless graphics (usually used only for sensors)\n                simu->scheduler().set_sync(false);\n                // disable summary text when windowless graphics activated\n                simu->enable_text_panel(false);\n                simu->enable_status_bar(false);\n            }\n\n            GraphicsConfiguration WindowlessGraphics::default_configuration()\n            {\n                GraphicsConfiguration config;\n                // by default we do not draw text in windowless mode\n                config.draw_debug = false;\n                config.draw_text = false;\n\n                return 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

  • #include <robot_dart/gui/magnum/base_graphics.hpp>
  • #include <robot_dart/gui/magnum/windowless_gl_application.hpp>
"},{"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\n#include <robot_dart/gui/magnum/base_graphics.hpp>\n#include <robot_dart/gui/magnum/windowless_gl_application.hpp>\n\nnamespace robot_dart {\n    namespace gui {\n        namespace magnum {\n            class WindowlessGraphics : public BaseGraphics<WindowlessGLApplication> {\n            public:\n                WindowlessGraphics(const GraphicsConfiguration& configuration = default_configuration()) : BaseGraphics<WindowlessGLApplication>(configuration) {}\n                ~WindowlessGraphics() {}\n\n                void set_simu(RobotDARTSimu* simu) override;\n\n                static GraphicsConfiguration default_configuration();\n            };\n        } // namespace magnum\n    } // namespace gui\n} // namespace robot_dart\n\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

  • #include <stdlib.h>
"},{"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 (\n    int flip_boolean\n) \n
"},{"location":"api/stb__image__write_8h/#function-stbi_write_bmp","title":"function stbi_write_bmp","text":"
STBIWDEF int stbi_write_bmp (\n    char const * filename,\n    int w,\n    int h,\n    int comp,\n    const void * data\n) \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 (\n    stbi_write_func * func,\n    void * context,\n    int w,\n    int h,\n    int comp,\n    const void * data\n) \n
"},{"location":"api/stb__image__write_8h/#function-stbi_write_hdr","title":"function stbi_write_hdr","text":"
STBIWDEF int stbi_write_hdr (\n    char const * filename,\n    int w,\n    int h,\n    int comp,\n    const float * data\n) \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 (\n    stbi_write_func * func,\n    void * context,\n    int w,\n    int h,\n    int comp,\n    const float * data\n) \n
"},{"location":"api/stb__image__write_8h/#function-stbi_write_jpg","title":"function stbi_write_jpg","text":"
STBIWDEF int stbi_write_jpg (\n    char const * filename,\n    int x,\n    int y,\n    int comp,\n    const void * data,\n    int quality\n) \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 (\n    stbi_write_func * func,\n    void * context,\n    int x,\n    int y,\n    int comp,\n    const void * data,\n    int quality\n) \n
"},{"location":"api/stb__image__write_8h/#function-stbi_write_png","title":"function stbi_write_png","text":"
STBIWDEF int stbi_write_png (\n    char const * filename,\n    int w,\n    int h,\n    int comp,\n    const void * data,\n    int stride_in_bytes\n) \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 (\n    stbi_write_func * func,\n    void * context,\n    int w,\n    int h,\n    int comp,\n    const void * data,\n    int stride_in_bytes\n) \n
"},{"location":"api/stb__image__write_8h/#function-stbi_write_tga","title":"function stbi_write_tga","text":"
STBIWDEF int stbi_write_tga (\n    char const * filename,\n    int w,\n    int h,\n    int comp,\n    const void * data\n) \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 (\n    stbi_write_func * func,\n    void * context,\n    int w,\n    int h,\n    int comp,\n    const void * data\n) \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\n   Before #including,\n\n       #define STB_IMAGE_WRITE_IMPLEMENTATION\n\n   in the file that you want to have the implementation.\n\n   Will probably not work correctly with strict-aliasing optimizations.\n\nABOUT:\n\n   This header file is a library for writing images to C stdio or a callback.\n\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.\n\nBUILDING:\n\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),\n\nUNICODE:\n\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.\n\nUSAGE:\n\n   There are five functions, one for each image file format:\n\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\n     void stbi_flip_vertically_on_write(int flag); // flag is non-zero to flip data vertically\n\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\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\n   where the callback is:\n      void stbi_write_func(void *context, void *data, int size);\n\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\n\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\n   Each function returns 0 on failure and non-0 on success.\n\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\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\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\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\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\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\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).\n\nCREDITS:\n\n\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\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\n\nLICENSE\n\n  See end of file for license information.\n\n*/\n\n#pragma GCC system_header\n\n#ifndef INCLUDE_STB_IMAGE_WRITE_H\n#define INCLUDE_STB_IMAGE_WRITE_H\n\n#include <stdlib.h>\n\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\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\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\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\n\ntypedef void stbi_write_func(void *context, void *data, int size);\n\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);\n\nSTBIWDEF void stbi_flip_vertically_on_write(int flip_boolean);\n\n#endif//INCLUDE_STB_IMAGE_WRITE_H\n\n#ifdef STB_IMAGE_WRITE_IMPLEMENTATION\n\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\n#ifndef STBI_WRITE_NO_STDIO\n#include <stdio.h>\n#endif // STBI_WRITE_NO_STDIO\n\n#include <stdarg.h>\n#include <stdlib.h>\n#include <string.h>\n#include <math.h>\n\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\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\n#ifndef STBIW_REALLOC_SIZED\n#define STBIW_REALLOC_SIZED(p,oldsz,newsz) STBIW_REALLOC(p,newsz)\n#endif\n\n\n#ifndef STBIW_MEMMOVE\n#define STBIW_MEMMOVE(a,b,sz) memmove(a,b,sz)\n#endif\n\n\n#ifndef STBIW_ASSERT\n#include <assert.h>\n#define STBIW_ASSERT(x) assert(x)\n#endif\n\n#define STBIW_UCHAR(x) (unsigned char) ((x) & 0xff)\n\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\n\nSTBIWDEF void stbi_flip_vertically_on_write(int flag)\n{\n   stbi__flip_vertically_on_write = flag;\n}\n\ntypedef struct\n{\n   stbi_write_func *func;\n   void *context;\n} stbi__write_context;\n\n// initialize a callback-based context\nstatic void stbi__start_write_callbacks(stbi__write_context *s, stbi_write_func *c, void *context)\n{\n   s->func    = c;\n   s->context = context;\n}\n\n#ifndef STBI_WRITE_NO_STDIO\n\nstatic void stbi__stdio_write(void *context, void *data, int size)\n{\n   fwrite(data,1,size,(FILE*) context);\n}\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);\n\nSTBIWDEF int stbiw_convert_wchar_to_utf8(char *buffer, size_t bufferlen, const wchar_t* input)\n{\n    return WideCharToMultiByte(65001 /* UTF8 */, 0, input, -1, buffer, (int) bufferlen, NULL, NULL);\n}\n#endif\n\nstatic FILE *stbiw__fopen(char const *filename, char const *mode)\n{\n   FILE *f;\n#if defined(_MSC_VER) && defined(STBI_WINDOWS_UTF8)\n   wchar_t wMode[64];\n   wchar_t wFilename[1024];\n    if (0 == MultiByteToWideChar(65001 /* UTF8 */, 0, filename, -1, wFilename, sizeof(wFilename)))\n      return 0;\n\n    if (0 == MultiByteToWideChar(65001 /* UTF8 */, 0, mode, -1, wMode, sizeof(wMode)))\n      return 0;\n\n#if _MSC_VER >= 1400\n    if (0 != _wfopen_s(&f, wFilename, wMode))\n        f = 0;\n#else\n   f = _wfopen(wFilename, wMode);\n#endif\n\n#elif defined(_MSC_VER) && _MSC_VER >= 1400\n   if (0 != fopen_s(&f, filename, mode))\n      f=0;\n#else\n   f = fopen(filename, mode);\n#endif\n   return f;\n}\n\nstatic int stbi__start_write_file(stbi__write_context *s, const char *filename)\n{\n   FILE *f = stbiw__fopen(filename, \"wb\");\n   stbi__start_write_callbacks(s, stbi__stdio_write, (void *) f);\n   return f != NULL;\n}\n\nstatic void stbi__end_write_file(stbi__write_context *s)\n{\n   fclose((FILE *)s->context);\n}\n\n#endif // !STBI_WRITE_NO_STDIO\n\ntypedef unsigned int stbiw_uint32;\ntypedef int stb_image_write_test[sizeof(stbiw_uint32)==4 ? 1 : -1];\n\nstatic void stbiw__writefv(stbi__write_context *s, const char *fmt, va_list v)\n{\n   while (*fmt) {\n      switch (*fmt++) {\n         case ' ': break;\n         case '1': { unsigned char x = STBIW_UCHAR(va_arg(v, int));\n                     s->func(s->context,&x,1);\n                     break; }\n         case '2': { int x = va_arg(v,int);\n                     unsigned char b[2];\n                     b[0] = STBIW_UCHAR(x);\n                     b[1] = STBIW_UCHAR(x>>8);\n                     s->func(s->context,b,2);\n                     break; }\n         case '4': { stbiw_uint32 x = va_arg(v,int);\n                     unsigned char b[4];\n                     b[0]=STBIW_UCHAR(x);\n                     b[1]=STBIW_UCHAR(x>>8);\n                     b[2]=STBIW_UCHAR(x>>16);\n                     b[3]=STBIW_UCHAR(x>>24);\n                     s->func(s->context,b,4);\n                     break; }\n         default:\n            STBIW_ASSERT(0);\n            return;\n      }\n   }\n}\n\nstatic void stbiw__writef(stbi__write_context *s, const char *fmt, ...)\n{\n   va_list v;\n   va_start(v, fmt);\n   stbiw__writefv(s, fmt, v);\n   va_end(v);\n}\n\nstatic void stbiw__putc(stbi__write_context *s, unsigned char c)\n{\n   s->func(s->context, &c, 1);\n}\n\nstatic void stbiw__write3(stbi__write_context *s, unsigned char a, unsigned char b, unsigned char c)\n{\n   unsigned char arr[3];\n   arr[0] = a; arr[1] = b; arr[2] = c;\n   s->func(s->context, arr, 3);\n}\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{\n   unsigned char bg[3] = { 255, 0, 255}, px[3];\n   int k;\n\n   if (write_alpha < 0)\n      s->func(s->context, &d[comp - 1], 1);\n\n   switch (comp) {\n      case 2: // 2 pixels = mono + alpha, alpha is written separately, so same as 1-channel case\n      case 1:\n         if (expand_mono)\n            stbiw__write3(s, d[0], d[0], d[0]); // monochrome bmp\n         else\n            s->func(s->context, d, 1);  // monochrome TGA\n         break;\n      case 4:\n         if (!write_alpha) {\n            // composite against pink background\n            for (k = 0; k < 3; ++k)\n               px[k] = bg[k] + ((d[k] - bg[k]) * d[3]) / 255;\n            stbiw__write3(s, px[1 - rgb_dir], px[1], px[1 + rgb_dir]);\n            break;\n         }\n         /* FALLTHROUGH */\n      case 3:\n         stbiw__write3(s, d[1 - rgb_dir], d[1], d[1 + rgb_dir]);\n         break;\n   }\n   if (write_alpha > 0)\n      s->func(s->context, &d[comp - 1], 1);\n}\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{\n   stbiw_uint32 zero = 0;\n   int i,j, j_end;\n\n   if (y <= 0)\n      return;\n\n   if (stbi__flip_vertically_on_write)\n      vdir *= -1;\n\n   if (vdir < 0) {\n      j_end = -1; j = y-1;\n   } else {\n      j_end =  y; j = 0;\n   }\n\n   for (; j != j_end; j += vdir) {\n      for (i=0; i < x; ++i) {\n         unsigned char *d = (unsigned char *) data + (j*x+i)*comp;\n         stbiw__write_pixel(s, rgb_dir, comp, write_alpha, expand_mono, d);\n      }\n      s->func(s->context, &zero, scanline_pad);\n   }\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{\n   if (y < 0 || x < 0) {\n      return 0;\n   } else {\n      va_list v;\n      va_start(v, fmt);\n      stbiw__writefv(s, fmt, v);\n      va_end(v);\n      stbiw__write_pixels(s,rgb_dir,vdir,x,y,comp,data,alpha,pad, expand_mono);\n      return 1;\n   }\n}\n\nstatic int stbi_write_bmp_core(stbi__write_context *s, int x, int y, int comp, const void *data)\n{\n   int pad = (-x*3) & 3;\n   return 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\n            40, x,y, 1,24, 0,0,0,0,0,0);             // bitmap header\n}\n\nSTBIWDEF int stbi_write_bmp_to_func(stbi_write_func *func, void *context, int x, int y, int comp, const void *data)\n{\n   stbi__write_context s;\n   stbi__start_write_callbacks(&s, func, context);\n   return stbi_write_bmp_core(&s, x, y, comp, data);\n}\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{\n   stbi__write_context s;\n   if (stbi__start_write_file(&s,filename)) {\n      int r = stbi_write_bmp_core(&s, x, y, comp, data);\n      stbi__end_write_file(&s);\n      return r;\n   } else\n      return 0;\n}\n#endif \n\nstatic int stbi_write_tga_core(stbi__write_context *s, int x, int y, int comp, void *data)\n{\n   int has_alpha = (comp == 2 || comp == 4);\n   int colorbytes = has_alpha ? comp-1 : comp;\n   int format = colorbytes < 2 ? 3 : 2; // 3 color channels (RGB/RGBA) = 2, 1 color channel (Y/YA) = 3\n\n   if (y < 0 || x < 0)\n      return 0;\n\n   if (!stbi_write_tga_with_rle) {\n      return 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 {\n      int i,j,k;\n      int jend, jdir;\n\n      stbiw__writef(s, \"111 221 2222 11\", 0,0,format+8, 0,0,0, 0,0,x,y, (colorbytes + has_alpha) * 8, has_alpha * 8);\n\n      if (stbi__flip_vertically_on_write) {\n         j = 0;\n         jend = y;\n         jdir = 1;\n      } else {\n         j = y-1;\n         jend = -1;\n         jdir = -1;\n      }\n      for (; j != jend; j += jdir) {\n         unsigned char *row = (unsigned char *) data + j * x * comp;\n         int len;\n\n         for (i = 0; i < x; i += len) {\n            unsigned char *begin = row + i * comp;\n            int diff = 1;\n            len = 1;\n\n            if (i < x - 1) {\n               ++len;\n               diff = memcmp(begin, row + (i + 1) * comp, comp);\n               if (diff) {\n                  const unsigned char *prev = begin;\n                  for (k = i + 2; k < x && len < 128; ++k) {\n                     if (memcmp(prev, row + k * comp, comp)) {\n                        prev += comp;\n                        ++len;\n                     } else {\n                        --len;\n                        break;\n                     }\n                  }\n               } else {\n                  for (k = i + 2; k < x && len < 128; ++k) {\n                     if (!memcmp(begin, row + k * comp, comp)) {\n                        ++len;\n                     } else {\n                        break;\n                     }\n                  }\n               }\n            }\n\n            if (diff) {\n               unsigned char header = STBIW_UCHAR(len - 1);\n               s->func(s->context, &header, 1);\n               for (k = 0; k < len; ++k) {\n                  stbiw__write_pixel(s, -1, comp, has_alpha, 0, begin + k * comp);\n               }\n            } else {\n               unsigned char header = STBIW_UCHAR(len - 129);\n               s->func(s->context, &header, 1);\n               stbiw__write_pixel(s, -1, comp, has_alpha, 0, begin);\n            }\n         }\n      }\n   }\n   return 1;\n}\n\nSTBIWDEF int stbi_write_tga_to_func(stbi_write_func *func, void *context, int x, int y, int comp, const void *data)\n{\n   stbi__write_context s;\n   stbi__start_write_callbacks(&s, func, context);\n   return stbi_write_tga_core(&s, x, y, comp, (void *) data);\n}\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{\n   stbi__write_context s;\n   if (stbi__start_write_file(&s,filename)) {\n      int r = stbi_write_tga_core(&s, x, y, comp, (void *) data);\n      stbi__end_write_file(&s);\n      return r;\n   } else\n      return 0;\n}\n#endif\n\n// *************************************************************************************************\n// Radiance RGBE HDR writer\n// by Baldur Karlsson\n\n#define stbiw__max(a, b)  ((a) > (b) ? (a) : (b))\n\nstatic void stbiw__linear_to_rgbe(unsigned char *rgbe, float *linear)\n{\n   int exponent;\n   float maxcomp = stbiw__max(linear[0], stbiw__max(linear[1], linear[2]));\n\n   if (maxcomp < 1e-32f) {\n      rgbe[0] = rgbe[1] = rgbe[2] = rgbe[3] = 0;\n   } else {\n      float normalize = (float) frexp(maxcomp, &exponent) * 256.0f/maxcomp;\n\n      rgbe[0] = (unsigned char)(linear[0] * normalize);\n      rgbe[1] = (unsigned char)(linear[1] * normalize);\n      rgbe[2] = (unsigned char)(linear[2] * normalize);\n      rgbe[3] = (unsigned char)(exponent + 128);\n   }\n}\n\nstatic void stbiw__write_run_data(stbi__write_context *s, int length, unsigned char databyte)\n{\n   unsigned char lengthbyte = STBIW_UCHAR(length+128);\n   STBIW_ASSERT(length+128 <= 255);\n   s->func(s->context, &lengthbyte, 1);\n   s->func(s->context, &databyte, 1);\n}\n\nstatic void stbiw__write_dump_data(stbi__write_context *s, int length, unsigned char *data)\n{\n   unsigned char lengthbyte = STBIW_UCHAR(length);\n   STBIW_ASSERT(length <= 128); // inconsistent with spec but consistent with official code\n   s->func(s->context, &lengthbyte, 1);\n   s->func(s->context, data, length);\n}\n\nstatic void stbiw__write_hdr_scanline(stbi__write_context *s, int width, int ncomp, unsigned char *scratch, float *scanline)\n{\n   unsigned char scanlineheader[4] = { 2, 2, 0, 0 };\n   unsigned char rgbe[4];\n   float linear[3];\n   int x;\n\n   scanlineheader[2] = (width&0xff00)>>8;\n   scanlineheader[3] = (width&0x00ff);\n\n   /* skip RLE for images too small or large */\n   if (width < 8 || width >= 32768) {\n      for (x=0; x < width; x++) {\n         switch (ncomp) {\n            case 4: /* fallthrough */\n            case 3: linear[2] = scanline[x*ncomp + 2];\n                    linear[1] = scanline[x*ncomp + 1];\n                    linear[0] = scanline[x*ncomp + 0];\n                    break;\n            default:\n                    linear[0] = linear[1] = linear[2] = scanline[x*ncomp + 0];\n                    break;\n         }\n         stbiw__linear_to_rgbe(rgbe, linear);\n         s->func(s->context, rgbe, 4);\n      }\n   } else {\n      int c,r;\n      /* encode into scratch buffer */\n      for (x=0; x < width; x++) {\n         switch(ncomp) {\n            case 4: /* fallthrough */\n            case 3: linear[2] = scanline[x*ncomp + 2];\n                    linear[1] = scanline[x*ncomp + 1];\n                    linear[0] = scanline[x*ncomp + 0];\n                    break;\n            default:\n                    linear[0] = linear[1] = linear[2] = scanline[x*ncomp + 0];\n                    break;\n         }\n         stbiw__linear_to_rgbe(rgbe, linear);\n         scratch[x + width*0] = rgbe[0];\n         scratch[x + width*1] = rgbe[1];\n         scratch[x + width*2] = rgbe[2];\n         scratch[x + width*3] = rgbe[3];\n      }\n\n      s->func(s->context, scanlineheader, 4);\n\n      /* RLE each component separately */\n      for (c=0; c < 4; c++) {\n         unsigned char *comp = &scratch[width*c];\n\n         x = 0;\n         while (x < width) {\n            // find first run\n            r = x;\n            while (r+2 < width) {\n               if (comp[r] == comp[r+1] && comp[r] == comp[r+2])\n                  break;\n               ++r;\n            }\n            if (r+2 >= width)\n               r = width;\n            // dump up to first run\n            while (x < r) {\n               int len = r-x;\n               if (len > 128) len = 128;\n               stbiw__write_dump_data(s, len, &comp[x]);\n               x += len;\n            }\n            // if there's a run, output it\n            if (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\n               while (r < width && comp[r] == comp[x])\n                  ++r;\n               // output run up to r\n               while (x < r) {\n                  int len = r-x;\n                  if (len > 127) len = 127;\n                  stbiw__write_run_data(s, len, comp[x]);\n                  x += len;\n               }\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{\n   if (y <= 0 || x <= 0 || data == NULL)\n      return 0;\n   else {\n      // Each component is stored separately. Allocate scratch space for full output scanline.\n      unsigned char *scratch = (unsigned char *) STBIW_MALLOC(x*4);\n      int i, len;\n      char buffer[128];\n      char header[] = \"#?RADIANCE\\n# Written by stb_image_write.h\\nFORMAT=32-bit_rle_rgbe\\n\";\n      s->func(s->context, header, sizeof(header)-1);\n\n#ifdef __STDC_WANT_SECURE_LIB__\n      len = sprintf_s(buffer, sizeof(buffer), \"EXPOSURE=          1.0000000000000\\n\\n-Y %d +X %d\\n\", y, x);\n#else\n      len = sprintf(buffer, \"EXPOSURE=          1.0000000000000\\n\\n-Y %d +X %d\\n\", y, x);\n#endif\n      s->func(s->context, buffer, len);\n\n      for(i=0; i < y; i++)\n         stbiw__write_hdr_scanline(s, x, comp, scratch, data + comp*x*(stbi__flip_vertically_on_write ? y-1-i : i));\n      STBIW_FREE(scratch);\n      return 1;\n   }\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{\n   stbi__write_context s;\n   stbi__start_write_callbacks(&s, func, context);\n   return stbi_write_hdr_core(&s, x, y, comp, (float *) data);\n}\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{\n   stbi__write_context s;\n   if (stbi__start_write_file(&s,filename)) {\n      int r = stbi_write_hdr_core(&s, x, y, comp, (float *) data);\n      stbi__end_write_file(&s);\n      return r;\n   } else\n      return 0;\n}\n#endif // STBI_WRITE_NO_STDIO\n\n\n//\n// PNG writer\n//\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\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\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)\n\nstatic void *stbiw__sbgrowf(void **arr, int increment, int itemsize)\n{\n   int m = *arr ? 2*stbiw__sbm(*arr)+increment : increment+1;\n   void *p = STBIW_REALLOC_SIZED(*arr ? stbiw__sbraw(*arr) : 0, *arr ? (stbiw__sbm(*arr)*itemsize + sizeof(int)*2) : 0, itemsize * m + sizeof(int)*2);\n   STBIW_ASSERT(p);\n   if (p) {\n      if (!*arr) ((int *) p)[1] = 0;\n      *arr = (void *) ((int *) p + 2);\n      stbiw__sbm(*arr) = m;\n   }\n   return *arr;\n}\n\nstatic unsigned char *stbiw__zlib_flushf(unsigned char *data, unsigned int *bitbuffer, int *bitcount)\n{\n   while (*bitcount >= 8) {\n      stbiw__sbpush(data, STBIW_UCHAR(*bitbuffer));\n      *bitbuffer >>= 8;\n      *bitcount -= 8;\n   }\n   return data;\n}\n\nstatic int stbiw__zlib_bitrev(int code, int codebits)\n{\n   int res=0;\n   while (codebits--) {\n      res = (res << 1) | (code & 1);\n      code >>= 1;\n   }\n   return res;\n}\n\nstatic unsigned int stbiw__zlib_countm(unsigned char *a, unsigned char *b, int limit)\n{\n   int i;\n   for (i=0; i < limit && i < 258; ++i)\n      if (a[i] != b[i]) break;\n   return i;\n}\n\nstatic unsigned int stbiw__zhash(unsigned char *data)\n{\n   stbiw_uint32 hash = data[0] + (data[1] << 8) + (data[2] << 16);\n   hash ^= hash << 3;\n   hash += hash >> 5;\n   hash ^= hash << 4;\n   hash += hash >> 17;\n   hash ^= hash << 25;\n   hash += hash >> 6;\n   return hash;\n}\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\n#define stbiw__ZHASH   16384\n\n#endif // STBIW_ZLIB_COMPRESS\n\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\n   return STBIW_ZLIB_COMPRESS(data, data_len, out_len, quality);\n#else // use builtin\n   static 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 };\n   static 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 };\n   static 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 };\n   static 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 };\n   unsigned int bitbuf=0;\n   int i,j, bitcount=0;\n   unsigned char *out = NULL;\n   unsigned char ***hash_table = (unsigned char***) STBIW_MALLOC(stbiw__ZHASH * sizeof(unsigned char**));\n   if (hash_table == NULL)\n      return NULL;\n   if (quality < 5) quality = 5;\n\n   stbiw__sbpush(out, 0x78);   // DEFLATE 32K window\n   stbiw__sbpush(out, 0x5e);   // FLEVEL = 1\n   stbiw__zlib_add(1,1);  // BFINAL = 1\n   stbiw__zlib_add(1,2);  // BTYPE = 1 -- fixed huffman\n\n   for (i=0; i < stbiw__ZHASH; ++i)\n      hash_table[i] = NULL;\n\n   i=0;\n   while (i < data_len-3) {\n      // hash next 3 bytes of data to be compressed\n      int h = stbiw__zhash(data+i)&(stbiw__ZHASH-1), best=3;\n      unsigned char *bestloc = 0;\n      unsigned char **hlist = hash_table[h];\n      int n = stbiw__sbcount(hlist);\n      for (j=0; j < n; ++j) {\n         if (hlist[j]-data > i-32768) { // if entry lies within window\n            int d = stbiw__zlib_countm(hlist[j], data+i, data_len-i);\n            if (d >= best) { best=d; bestloc=hlist[j]; }\n         }\n      }\n      // when hash table entry is too long, delete half the entries\n      if (hash_table[h] && stbiw__sbn(hash_table[h]) == 2*quality) {\n         STBIW_MEMMOVE(hash_table[h], hash_table[h]+quality, sizeof(hash_table[h][0])*quality);\n         stbiw__sbn(hash_table[h]) = quality;\n      }\n      stbiw__sbpush(hash_table[h],data+i);\n\n      if (bestloc) {\n         // \"lazy matching\" - check match at *next* byte, and if it's better, do cur byte as literal\n         h = stbiw__zhash(data+i+1)&(stbiw__ZHASH-1);\n         hlist = hash_table[h];\n         n = stbiw__sbcount(hlist);\n         for (j=0; j < n; ++j) {\n            if (hlist[j]-data > i-32767) {\n               int e = stbiw__zlib_countm(hlist[j], data+i+1, data_len-i-1);\n               if (e > best) { // if next match is better, bail on current match\n                  bestloc = NULL;\n                  break;\n               }\n            }\n         }\n      }\n\n      if (bestloc) {\n         int d = (int) (data+i - bestloc); // distance back\n         STBIW_ASSERT(d <= 32767 && best <= 258);\n         for (j=0; best > lengthc[j+1]-1; ++j);\n         stbiw__zlib_huff(j+257);\n         if (lengtheb[j]) stbiw__zlib_add(best - lengthc[j], lengtheb[j]);\n         for (j=0; d > distc[j+1]-1; ++j);\n         stbiw__zlib_add(stbiw__zlib_bitrev(j,5),5);\n         if (disteb[j]) stbiw__zlib_add(d - distc[j], disteb[j]);\n         i += best;\n      } else {\n         stbiw__zlib_huffb(data[i]);\n         ++i;\n      }\n   }\n   // write out final bytes\n   for (;i < data_len; ++i)\n      stbiw__zlib_huffb(data[i]);\n   stbiw__zlib_huff(256); // end of block\n   // pad with 0 bits to byte boundary\n   while (bitcount)\n      stbiw__zlib_add(0,1);\n\n   for (i=0; i < stbiw__ZHASH; ++i)\n      (void) stbiw__sbfree(hash_table[i]);\n   STBIW_FREE(hash_table);\n\n   {\n      // compute adler32 on input\n      unsigned int s1=1, s2=0;\n      int blocklen = (int) (data_len % 5552);\n      j=0;\n      while (j < data_len) {\n         for (i=0; i < blocklen; ++i) { s1 += data[j+i]; s2 += s1; }\n         s1 %= 65521; s2 %= 65521;\n         j += blocklen;\n         blocklen = 5552;\n      }\n      stbiw__sbpush(out, STBIW_UCHAR(s2 >> 8));\n      stbiw__sbpush(out, STBIW_UCHAR(s2));\n      stbiw__sbpush(out, STBIW_UCHAR(s1 >> 8));\n      stbiw__sbpush(out, STBIW_UCHAR(s1));\n   }\n   *out_len = stbiw__sbn(out);\n   // make returned pointer freeable\n   STBIW_MEMMOVE(stbiw__sbraw(out), out, *out_len);\n   return (unsigned char *) stbiw__sbraw(out);\n#endif // STBIW_ZLIB_COMPRESS\n}\n\nstatic unsigned int stbiw__crc32(unsigned char *buffer, int len)\n{\n#ifdef STBIW_CRC32\n    return STBIW_CRC32(buffer, len);\n#else\n   static unsigned int crc_table[256] =\n   {\n      0x00000000, 0x77073096, 0xEE0E612C, 0x990951BA, 0x076DC419, 0x706AF48F, 0xE963A535, 0x9E6495A3,\n      0x0eDB8832, 0x79DCB8A4, 0xE0D5E91E, 0x97D2D988, 0x09B64C2B, 0x7EB17CBD, 0xE7B82D07, 0x90BF1D91,\n      0x1DB71064, 0x6AB020F2, 0xF3B97148, 0x84BE41DE, 0x1ADAD47D, 0x6DDDE4EB, 0xF4D4B551, 0x83D385C7,\n      0x136C9856, 0x646BA8C0, 0xFD62F97A, 0x8A65C9EC, 0x14015C4F, 0x63066CD9, 0xFA0F3D63, 0x8D080DF5,\n      0x3B6E20C8, 0x4C69105E, 0xD56041E4, 0xA2677172, 0x3C03E4D1, 0x4B04D447, 0xD20D85FD, 0xA50AB56B,\n      0x35B5A8FA, 0x42B2986C, 0xDBBBC9D6, 0xACBCF940, 0x32D86CE3, 0x45DF5C75, 0xDCD60DCF, 0xABD13D59,\n      0x26D930AC, 0x51DE003A, 0xC8D75180, 0xBFD06116, 0x21B4F4B5, 0x56B3C423, 0xCFBA9599, 0xB8BDA50F,\n      0x2802B89E, 0x5F058808, 0xC60CD9B2, 0xB10BE924, 0x2F6F7C87, 0x58684C11, 0xC1611DAB, 0xB6662D3D,\n      0x76DC4190, 0x01DB7106, 0x98D220BC, 0xEFD5102A, 0x71B18589, 0x06B6B51F, 0x9FBFE4A5, 0xE8B8D433,\n      0x7807C9A2, 0x0F00F934, 0x9609A88E, 0xE10E9818, 0x7F6A0DBB, 0x086D3D2D, 0x91646C97, 0xE6635C01,\n      0x6B6B51F4, 0x1C6C6162, 0x856530D8, 0xF262004E, 0x6C0695ED, 0x1B01A57B, 0x8208F4C1, 0xF50FC457,\n      0x65B0D9C6, 0x12B7E950, 0x8BBEB8EA, 0xFCB9887C, 0x62DD1DDF, 0x15DA2D49, 0x8CD37CF3, 0xFBD44C65,\n      0x4DB26158, 0x3AB551CE, 0xA3BC0074, 0xD4BB30E2, 0x4ADFA541, 0x3DD895D7, 0xA4D1C46D, 0xD3D6F4FB,\n      0x4369E96A, 0x346ED9FC, 0xAD678846, 0xDA60B8D0, 0x44042D73, 0x33031DE5, 0xAA0A4C5F, 0xDD0D7CC9,\n      0x5005713C, 0x270241AA, 0xBE0B1010, 0xC90C2086, 0x5768B525, 0x206F85B3, 0xB966D409, 0xCE61E49F,\n      0x5EDEF90E, 0x29D9C998, 0xB0D09822, 0xC7D7A8B4, 0x59B33D17, 0x2EB40D81, 0xB7BD5C3B, 0xC0BA6CAD,\n      0xEDB88320, 0x9ABFB3B6, 0x03B6E20C, 0x74B1D29A, 0xEAD54739, 0x9DD277AF, 0x04DB2615, 0x73DC1683,\n      0xE3630B12, 0x94643B84, 0x0D6D6A3E, 0x7A6A5AA8, 0xE40ECF0B, 0x9309FF9D, 0x0A00AE27, 0x7D079EB1,\n      0xF00F9344, 0x8708A3D2, 0x1E01F268, 0x6906C2FE, 0xF762575D, 0x806567CB, 0x196C3671, 0x6E6B06E7,\n      0xFED41B76, 0x89D32BE0, 0x10DA7A5A, 0x67DD4ACC, 0xF9B9DF6F, 0x8EBEEFF9, 0x17B7BE43, 0x60B08ED5,\n      0xD6D6A3E8, 0xA1D1937E, 0x38D8C2C4, 0x4FDFF252, 0xD1BB67F1, 0xA6BC5767, 0x3FB506DD, 0x48B2364B,\n      0xD80D2BDA, 0xAF0A1B4C, 0x36034AF6, 0x41047A60, 0xDF60EFC3, 0xA867DF55, 0x316E8EEF, 0x4669BE79,\n      0xCB61B38C, 0xBC66831A, 0x256FD2A0, 0x5268E236, 0xCC0C7795, 0xBB0B4703, 0x220216B9, 0x5505262F,\n      0xC5BA3BBE, 0xB2BD0B28, 0x2BB45A92, 0x5CB36A04, 0xC2D7FFA7, 0xB5D0CF31, 0x2CD99E8B, 0x5BDEAE1D,\n      0x9B64C2B0, 0xEC63F226, 0x756AA39C, 0x026D930A, 0x9C0906A9, 0xEB0E363F, 0x72076785, 0x05005713,\n      0x95BF4A82, 0xE2B87A14, 0x7BB12BAE, 0x0CB61B38, 0x92D28E9B, 0xE5D5BE0D, 0x7CDCEFB7, 0x0BDBDF21,\n      0x86D3D2D4, 0xF1D4E242, 0x68DDB3F8, 0x1FDA836E, 0x81BE16CD, 0xF6B9265B, 0x6FB077E1, 0x18B74777,\n      0x88085AE6, 0xFF0F6A70, 0x66063BCA, 0x11010B5C, 0x8F659EFF, 0xF862AE69, 0x616BFFD3, 0x166CCF45,\n      0xA00AE278, 0xD70DD2EE, 0x4E048354, 0x3903B3C2, 0xA7672661, 0xD06016F7, 0x4969474D, 0x3E6E77DB,\n      0xAED16A4A, 0xD9D65ADC, 0x40DF0B66, 0x37D83BF0, 0xA9BCAE53, 0xDEBB9EC5, 0x47B2CF7F, 0x30B5FFE9,\n      0xBDBDF21C, 0xCABAC28A, 0x53B39330, 0x24B4A3A6, 0xBAD03605, 0xCDD70693, 0x54DE5729, 0x23D967BF,\n      0xB3667A2E, 0xC4614AB8, 0x5D681B02, 0x2A6F2B94, 0xB40BBE37, 0xC30C8EA1, 0x5A05DF1B, 0x2D02EF8D\n   };\n\n   unsigned int crc = ~0u;\n   int i;\n   for (i=0; i < len; ++i)\n      crc = (crc >> 8) ^ crc_table[buffer[i] ^ (crc & 0xff)];\n   return ~crc;\n#endif\n}\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])\n\nstatic void stbiw__wpcrc(unsigned char **data, int len)\n{\n   unsigned int crc = stbiw__crc32(*data - len - 4, len+4);\n   stbiw__wp32(*data, crc);\n}\n\nstatic unsigned char stbiw__paeth(int a, int b, int c)\n{\n   int p = a + b - c, pa = abs(p-a), pb = abs(p-b), pc = abs(p-c);\n   if (pa <= pb && pa <= pc) return STBIW_UCHAR(a);\n   if (pb <= pc) return STBIW_UCHAR(b);\n   return STBIW_UCHAR(c);\n}\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{\n   static int mapping[] = { 0,1,2,3,4 };\n   static int firstmap[] = { 0,1,0,5,6 };\n   int *mymap = (y != 0) ? mapping : firstmap;\n   int i;\n   int type = mymap[filter_type];\n   unsigned char *z = pixels + stride_bytes * (stbi__flip_vertically_on_write ? height-1-y : y);\n   int signed_stride = stbi__flip_vertically_on_write ? -stride_bytes : stride_bytes;\n\n   if (type==0) {\n      memcpy(line_buffer, z, width*n);\n      return;\n   }\n\n   // first loop isn't optimized since it's just one pixel    \n   for (i = 0; i < n; ++i) {\n      switch (type) {\n         case 1: line_buffer[i] = z[i]; break;\n         case 2: line_buffer[i] = z[i] - z[i-signed_stride]; break;\n         case 3: line_buffer[i] = z[i] - (z[i-signed_stride]>>1); break;\n         case 4: line_buffer[i] = (signed char) (z[i] - stbiw__paeth(0,z[i-signed_stride],0)); break;\n         case 5: line_buffer[i] = z[i]; break;\n         case 6: line_buffer[i] = z[i]; break;\n      }\n   }\n   switch (type) {\n      case 1: for (i=n; i < width*n; ++i) line_buffer[i] = z[i] - z[i-n]; break;\n      case 2: for (i=n; i < width*n; ++i) line_buffer[i] = z[i] - z[i-signed_stride]; break;\n      case 3: for (i=n; i < width*n; ++i) line_buffer[i] = z[i] - ((z[i-n] + z[i-signed_stride])>>1); break;\n      case 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;\n      case 5: for (i=n; i < width*n; ++i) line_buffer[i] = z[i] - (z[i-n]>>1); break;\n      case 6: for (i=n; i < width*n; ++i) line_buffer[i] = z[i] - stbiw__paeth(z[i-n], 0,0); break;\n   }\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{\n   int force_filter = stbi_write_force_png_filter;\n   int ctype[5] = { -1, 0, 4, 2, 6 };\n   unsigned char sig[8] = { 137,80,78,71,13,10,26,10 };\n   unsigned char *out,*o, *filt, *zlib;\n   signed char *line_buffer;\n   int j,zlen;\n\n   if (stride_bytes == 0)\n      stride_bytes = x * n;\n\n   if (force_filter >= 5) {\n      force_filter = -1;\n   }\n\n   filt = (unsigned char *) STBIW_MALLOC((x*n+1) * y); if (!filt) return 0;\n   line_buffer = (signed char *) STBIW_MALLOC(x * n); if (!line_buffer) { STBIW_FREE(filt); return 0; }\n   for (j=0; j < y; ++j) {\n      int filter_type;\n      if (force_filter > -1) {\n         filter_type = force_filter;\n         stbiw__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:\n         int best_filter = 0, best_filter_val = 0x7fffffff, est, i;\n         for (filter_type = 0; filter_type < 5; filter_type++) {\n            stbiw__encode_png_line((unsigned char*)(pixels), stride_bytes, x, y, j, n, filter_type, line_buffer);\n\n            // Estimate the entropy of the line using this filter; the less, the better.\n            est = 0;\n            for (i = 0; i < x*n; ++i) {\n               est += abs((signed char) line_buffer[i]);\n            }\n            if (est < best_filter_val) {\n               best_filter_val = est;\n               best_filter = filter_type;\n            }\n         }\n         if (filter_type != best_filter) {  // If the last iteration already got us the best filter, don't redo it\n            stbiw__encode_png_line((unsigned char*)(pixels), stride_bytes, x, y, j, n, best_filter, line_buffer);\n            filter_type = best_filter;\n         }\n      }\n      // when we get here, filter_type contains the filter type, and line_buffer contains the data\n      filt[j*(x*n+1)] = (unsigned char) filter_type;\n      STBIW_MEMMOVE(filt+j*(x*n+1)+1, line_buffer, x*n);\n   }\n   STBIW_FREE(line_buffer);\n   zlib = stbi_zlib_compress(filt, y*( x*n+1), &zlen, stbi_write_png_compression_level);\n   STBIW_FREE(filt);\n   if (!zlib) return 0;\n\n   // each tag requires 12 bytes of overhead\n   out = (unsigned char *) STBIW_MALLOC(8 + 12+13 + 12+zlen + 12);\n   if (!out) return 0;\n   *out_len = 8 + 12+13 + 12+zlen + 12;\n\n   o=out;\n   STBIW_MEMMOVE(o,sig,8); o+= 8;\n   stbiw__wp32(o, 13); // header length\n   stbiw__wptag(o, \"IHDR\");\n   stbiw__wp32(o, x);\n   stbiw__wp32(o, y);\n   *o++ = 8;\n   *o++ = STBIW_UCHAR(ctype[n]);\n   *o++ = 0;\n   *o++ = 0;\n   *o++ = 0;\n   stbiw__wpcrc(&o,13);\n\n   stbiw__wp32(o, zlen);\n   stbiw__wptag(o, \"IDAT\");\n   STBIW_MEMMOVE(o, zlib, zlen);\n   o += zlen;\n   STBIW_FREE(zlib);\n   stbiw__wpcrc(&o, zlen);\n\n   stbiw__wp32(o,0);\n   stbiw__wptag(o, \"IEND\");\n   stbiw__wpcrc(&o,0);\n\n   STBIW_ASSERT(o == out + *out_len);\n\n   return out;\n}\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{\n   FILE *f;\n   int len;\n   unsigned char *png = stbi_write_png_to_mem((const unsigned char *) data, stride_bytes, x, y, comp, &len);\n   if (png == NULL) return 0;\n\n   f = stbiw__fopen(filename, \"wb\");\n   if (!f) { STBIW_FREE(png); return 0; }\n   fwrite(png, 1, len, f);\n   fclose(f);\n   STBIW_FREE(png);\n   return 1;\n}\n#endif\n\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{\n   int len;\n   unsigned char *png = stbi_write_png_to_mem((const unsigned char *) data, stride_bytes, x, y, comp, &len);\n   if (png == NULL) return 0;\n   func(context, png, len);\n   STBIW_FREE(png);\n   return 1;\n}\n\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 */\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,\n      24,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 };\n\nstatic void stbiw__jpg_writeBits(stbi__write_context *s, int *bitBufP, int *bitCntP, const unsigned short *bs) {\n   int bitBuf = *bitBufP, bitCnt = *bitCntP;\n   bitCnt += bs[1];\n   bitBuf |= bs[0] << (24 - bitCnt);\n   while(bitCnt >= 8) {\n      unsigned char c = (bitBuf >> 16) & 255;\n      stbiw__putc(s, c);\n      if(c == 255) {\n         stbiw__putc(s, 0);\n      }\n      bitBuf <<= 8;\n      bitCnt -= 8;\n   }\n   *bitBufP = bitBuf;\n   *bitCntP = bitCnt;\n}\n\nstatic void stbiw__jpg_DCT(float *d0p, float *d1p, float *d2p, float *d3p, float *d4p, float *d5p, float *d6p, float *d7p) {\n   float d0 = *d0p, d1 = *d1p, d2 = *d2p, d3 = *d3p, d4 = *d4p, d5 = *d5p, d6 = *d6p, d7 = *d7p;\n   float z1, z2, z3, z4, z5, z11, z13;\n\n   float tmp0 = d0 + d7;\n   float tmp7 = d0 - d7;\n   float tmp1 = d1 + d6;\n   float tmp6 = d1 - d6;\n   float tmp2 = d2 + d5;\n   float tmp5 = d2 - d5;\n   float tmp3 = d3 + d4;\n   float tmp4 = d3 - d4;\n\n   // Even part\n   float tmp10 = tmp0 + tmp3;   // phase 2\n   float tmp13 = tmp0 - tmp3;\n   float tmp11 = tmp1 + tmp2;\n   float tmp12 = tmp1 - tmp2;\n\n   d0 = tmp10 + tmp11;       // phase 3\n   d4 = tmp10 - tmp11;\n\n   z1 = (tmp12 + tmp13) * 0.707106781f; // c4\n   d2 = tmp13 + z1;       // phase 5\n   d6 = tmp13 - z1;\n\n   // Odd part\n   tmp10 = tmp4 + tmp5;       // phase 2\n   tmp11 = tmp5 + tmp6;\n   tmp12 = tmp6 + tmp7;\n\n   // The rotator is modified from fig 4-8 to avoid extra negations.\n   z5 = (tmp10 - tmp12) * 0.382683433f; // c6\n   z2 = tmp10 * 0.541196100f + z5; // c2-c6\n   z4 = tmp12 * 1.306562965f + z5; // c2+c6\n   z3 = tmp11 * 0.707106781f; // c4\n\n   z11 = tmp7 + z3;      // phase 5\n   z13 = tmp7 - z3;\n\n   *d5p = z13 + z2;         // phase 6\n   *d3p = z13 - z2;\n   *d1p = z11 + z4;\n   *d7p = z11 - z4;\n\n   *d0p = d0;  *d2p = d2;  *d4p = d4;  *d6p = d6;\n}\n\nstatic void stbiw__jpg_calcBits(int val, unsigned short bits[2]) {\n   int tmp1 = val < 0 ? -val : val;\n   val = val < 0 ? val-1 : val;\n   bits[1] = 1;\n   while(tmp1 >>= 1) {\n      ++bits[1];\n   }\n   bits[0] = val & ((1<<bits[1])-1);\n}\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]) {\n   const unsigned short EOB[2] = { HTAC[0x00][0], HTAC[0x00][1] };\n   const unsigned short M16zeroes[2] = { HTAC[0xF0][0], HTAC[0xF0][1] };\n   int dataOff, i, diff, end0pos;\n   int DU[64];\n\n   // DCT rows\n   for(dataOff=0; dataOff<64; dataOff+=8) {\n      stbiw__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\n   for(dataOff=0; dataOff<8; ++dataOff) {\n      stbiw__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\n   for(i=0; i<64; ++i) {\n      float 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?\n      DU[stbiw__jpg_ZigZag[i]] = (int)(v < 0 ? v - 0.5f : v + 0.5f);\n   }\n\n   // Encode DC\n   diff = DU[0] - DC;\n   if (diff == 0) {\n      stbiw__jpg_writeBits(s, bitBuf, bitCnt, HTDC[0]);\n   } else {\n      unsigned short bits[2];\n      stbiw__jpg_calcBits(diff, bits);\n      stbiw__jpg_writeBits(s, bitBuf, bitCnt, HTDC[bits[1]]);\n      stbiw__jpg_writeBits(s, bitBuf, bitCnt, bits);\n   }\n   // Encode ACs\n   end0pos = 63;\n   for(; (end0pos>0)&&(DU[end0pos]==0); --end0pos) {\n   }\n   // end0pos = first element in reverse order !=0\n   if(end0pos == 0) {\n      stbiw__jpg_writeBits(s, bitBuf, bitCnt, EOB);\n      return DU[0];\n   }\n   for(i = 1; i <= end0pos; ++i) {\n      int startpos = i;\n      int nrzeroes;\n      unsigned short bits[2];\n      for (; DU[i]==0 && i<=end0pos; ++i) {\n      }\n      nrzeroes = i-startpos;\n      if ( nrzeroes >= 16 ) {\n         int lng = nrzeroes>>4;\n         int nrmarker;\n         for (nrmarker=1; nrmarker <= lng; ++nrmarker)\n            stbiw__jpg_writeBits(s, bitBuf, bitCnt, M16zeroes);\n         nrzeroes &= 15;\n      }\n      stbiw__jpg_calcBits(DU[i], bits);\n      stbiw__jpg_writeBits(s, bitBuf, bitCnt, HTAC[(nrzeroes<<4)+bits[1]]);\n      stbiw__jpg_writeBits(s, bitBuf, bitCnt, bits);\n   }\n   if(end0pos != 63) {\n      stbiw__jpg_writeBits(s, bitBuf, bitCnt, EOB);\n   }\n   return DU[0];\n}\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\n   static const unsigned char std_dc_luminance_nrcodes[] = {0,0,1,5,1,1,1,1,1,1,0,0,0,0,0,0,0};\n   static const unsigned char std_dc_luminance_values[] = {0,1,2,3,4,5,6,7,8,9,10,11};\n   static const unsigned char std_ac_luminance_nrcodes[] = {0,0,2,1,3,3,2,4,3,5,5,4,4,0,0,1,0x7d};\n   static const unsigned char std_ac_luminance_values[] = {\n      0x01,0x02,0x03,0x00,0x04,0x11,0x05,0x12,0x21,0x31,0x41,0x06,0x13,0x51,0x61,0x07,0x22,0x71,0x14,0x32,0x81,0x91,0xa1,0x08,\n      0x23,0x42,0xb1,0xc1,0x15,0x52,0xd1,0xf0,0x24,0x33,0x62,0x72,0x82,0x09,0x0a,0x16,0x17,0x18,0x19,0x1a,0x25,0x26,0x27,0x28,\n      0x29,0x2a,0x34,0x35,0x36,0x37,0x38,0x39,0x3a,0x43,0x44,0x45,0x46,0x47,0x48,0x49,0x4a,0x53,0x54,0x55,0x56,0x57,0x58,0x59,\n      0x5a,0x63,0x64,0x65,0x66,0x67,0x68,0x69,0x6a,0x73,0x74,0x75,0x76,0x77,0x78,0x79,0x7a,0x83,0x84,0x85,0x86,0x87,0x88,0x89,\n      0x8a,0x92,0x93,0x94,0x95,0x96,0x97,0x98,0x99,0x9a,0xa2,0xa3,0xa4,0xa5,0xa6,0xa7,0xa8,0xa9,0xaa,0xb2,0xb3,0xb4,0xb5,0xb6,\n      0xb7,0xb8,0xb9,0xba,0xc2,0xc3,0xc4,0xc5,0xc6,0xc7,0xc8,0xc9,0xca,0xd2,0xd3,0xd4,0xd5,0xd6,0xd7,0xd8,0xd9,0xda,0xe1,0xe2,\n      0xe3,0xe4,0xe5,0xe6,0xe7,0xe8,0xe9,0xea,0xf1,0xf2,0xf3,0xf4,0xf5,0xf6,0xf7,0xf8,0xf9,0xfa\n   };\n   static const unsigned char std_dc_chrominance_nrcodes[] = {0,0,3,1,1,1,1,1,1,1,1,1,0,0,0,0,0};\n   static const unsigned char std_dc_chrominance_values[] = {0,1,2,3,4,5,6,7,8,9,10,11};\n   static const unsigned char std_ac_chrominance_nrcodes[] = {0,0,2,1,2,4,4,3,4,7,5,4,4,0,1,2,0x77};\n   static const unsigned char std_ac_chrominance_values[] = {\n      0x00,0x01,0x02,0x03,0x11,0x04,0x05,0x21,0x31,0x06,0x12,0x41,0x51,0x07,0x61,0x71,0x13,0x22,0x32,0x81,0x08,0x14,0x42,0x91,\n      0xa1,0xb1,0xc1,0x09,0x23,0x33,0x52,0xf0,0x15,0x62,0x72,0xd1,0x0a,0x16,0x24,0x34,0xe1,0x25,0xf1,0x17,0x18,0x19,0x1a,0x26,\n      0x27,0x28,0x29,0x2a,0x35,0x36,0x37,0x38,0x39,0x3a,0x43,0x44,0x45,0x46,0x47,0x48,0x49,0x4a,0x53,0x54,0x55,0x56,0x57,0x58,\n      0x59,0x5a,0x63,0x64,0x65,0x66,0x67,0x68,0x69,0x6a,0x73,0x74,0x75,0x76,0x77,0x78,0x79,0x7a,0x82,0x83,0x84,0x85,0x86,0x87,\n      0x88,0x89,0x8a,0x92,0x93,0x94,0x95,0x96,0x97,0x98,0x99,0x9a,0xa2,0xa3,0xa4,0xa5,0xa6,0xa7,0xa8,0xa9,0xaa,0xb2,0xb3,0xb4,\n      0xb5,0xb6,0xb7,0xb8,0xb9,0xba,0xc2,0xc3,0xc4,0xc5,0xc6,0xc7,0xc8,0xc9,0xca,0xd2,0xd3,0xd4,0xd5,0xd6,0xd7,0xd8,0xd9,0xda,\n      0xe2,0xe3,0xe4,0xe5,0xe6,0xe7,0xe8,0xe9,0xea,0xf2,0xf3,0xf4,0xf5,0xf6,0xf7,0xf8,0xf9,0xfa\n   };\n   // Huffman tables\n   static 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}};\n   static 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}};\n   static 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   };\n   static 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   };\n   static 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,\n                             37,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};\n   static 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,\n                              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,99};\n   static const float aasf[] = { 1.0f * 2.828427125f, 1.387039845f * 2.828427125f, 1.306562965f * 2.828427125f, 1.175875602f * 2.828427125f, \n                                 1.0f * 2.828427125f, 0.785694958f * 2.828427125f, 0.541196100f * 2.828427125f, 0.275899379f * 2.828427125f };\n\n   int row, col, i, k;\n   float fdtbl_Y[64], fdtbl_UV[64];\n   unsigned char YTable[64], UVTable[64];\n\n   if(!data || !width || !height || comp > 4 || comp < 1) {\n      return 0;\n   }\n\n   quality = quality ? quality : 90;\n   quality = quality < 1 ? 1 : quality > 100 ? 100 : quality;\n   quality = quality < 50 ? 5000 / quality : 200 - quality * 2;\n\n   for(i = 0; i < 64; ++i) {\n      int uvti, yti = (YQT[i]*quality+50)/100;\n      YTable[stbiw__jpg_ZigZag[i]] = (unsigned char) (yti < 1 ? 1 : yti > 255 ? 255 : yti);\n      uvti = (UVQT[i]*quality+50)/100;\n      UVTable[stbiw__jpg_ZigZag[i]] = (unsigned char) (uvti < 1 ? 1 : uvti > 255 ? 255 : uvti);\n   }\n\n   for(row = 0, k = 0; row < 8; ++row) {\n      for(col = 0; col < 8; ++col, ++k) {\n         fdtbl_Y[k]  = 1 / (YTable [stbiw__jpg_ZigZag[k]] * aasf[row] * aasf[col]);\n         fdtbl_UV[k] = 1 / (UVTable[stbiw__jpg_ZigZag[k]] * aasf[row] * aasf[col]);\n      }\n   }\n\n   // Write Headers\n   {\n      static 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 };\n      static const unsigned char head2[] = { 0xFF,0xDA,0,0xC,3,1,0,2,0x11,3,0x11,0,0x3F,0 };\n      const unsigned char head1[] = { 0xFF,0xC0,0,0x11,8,(unsigned char)(height>>8),STBIW_UCHAR(height),(unsigned char)(width>>8),STBIW_UCHAR(width),\n                                      3,1,0x11,0,2,0x11,1,3,0x11,1,0xFF,0xC4,0x01,0xA2,0 };\n      s->func(s->context, (void*)head0, sizeof(head0));\n      s->func(s->context, (void*)YTable, sizeof(YTable));\n      stbiw__putc(s, 1);\n      s->func(s->context, UVTable, sizeof(UVTable));\n      s->func(s->context, (void*)head1, sizeof(head1));\n      s->func(s->context, (void*)(std_dc_luminance_nrcodes+1), sizeof(std_dc_luminance_nrcodes)-1);\n      s->func(s->context, (void*)std_dc_luminance_values, sizeof(std_dc_luminance_values));\n      stbiw__putc(s, 0x10); // HTYACinfo\n      s->func(s->context, (void*)(std_ac_luminance_nrcodes+1), sizeof(std_ac_luminance_nrcodes)-1);\n      s->func(s->context, (void*)std_ac_luminance_values, sizeof(std_ac_luminance_values));\n      stbiw__putc(s, 1); // HTUDCinfo\n      s->func(s->context, (void*)(std_dc_chrominance_nrcodes+1), sizeof(std_dc_chrominance_nrcodes)-1);\n      s->func(s->context, (void*)std_dc_chrominance_values, sizeof(std_dc_chrominance_values));\n      stbiw__putc(s, 0x11); // HTUACinfo\n      s->func(s->context, (void*)(std_ac_chrominance_nrcodes+1), sizeof(std_ac_chrominance_nrcodes)-1);\n      s->func(s->context, (void*)std_ac_chrominance_values, sizeof(std_ac_chrominance_values));\n      s->func(s->context, (void*)head2, sizeof(head2));\n   }\n\n   // Encode 8x8 macroblocks\n   {\n      static const unsigned short fillBits[] = {0x7F, 7};\n      const unsigned char *imageData = (const unsigned char *)data;\n      int DCY=0, DCU=0, DCV=0;\n      int bitBuf=0, bitCnt=0;\n      // comp == 2 is grey+alpha (alpha is ignored)\n      int ofsG = comp > 2 ? 1 : 0, ofsB = comp > 2 ? 2 : 0;\n      int x, y, pos;\n      for(y = 0; y < height; y += 8) {\n         for(x = 0; x < width; x += 8) {\n            float YDU[64], UDU[64], VDU[64];\n            for(row = y, pos = 0; row < y+8; ++row) {\n               // row >= height => use last input row\n               int clamped_row = (row < height) ? row : height - 1;\n               int base_p = (stbi__flip_vertically_on_write ? (height-1-clamped_row) : clamped_row)*width*comp;\n               for(col = x; col < x+8; ++col, ++pos) {\n                  float r, g, b;\n                  // if col >= width => use pixel from last input column\n                  int p = base_p + ((col < width) ? col : (width-1))*comp;\n\n                  r = imageData[p+0];\n                  g = imageData[p+ofsG];\n                  b = imageData[p+ofsB];\n                  YDU[pos]=+0.29900f*r+0.58700f*g+0.11400f*b-128;\n                  UDU[pos]=-0.16874f*r-0.33126f*g+0.50000f*b;\n                  VDU[pos]=+0.50000f*r-0.41869f*g-0.08131f*b;\n               }\n            }\n\n            DCY = stbiw__jpg_processDU(s, &bitBuf, &bitCnt, YDU, fdtbl_Y, DCY, YDC_HT, YAC_HT);\n            DCU = stbiw__jpg_processDU(s, &bitBuf, &bitCnt, UDU, fdtbl_UV, DCU, UVDC_HT, UVAC_HT);\n            DCV = stbiw__jpg_processDU(s, &bitBuf, &bitCnt, VDU, fdtbl_UV, DCV, UVDC_HT, UVAC_HT);\n         }\n      }\n\n      // Do the bit alignment of the EOI marker\n      stbiw__jpg_writeBits(s, &bitBuf, &bitCnt, fillBits);\n   }\n\n   // EOI\n   stbiw__putc(s, 0xFF);\n   stbiw__putc(s, 0xD9);\n\n   return 1;\n}\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{\n   stbi__write_context s;\n   stbi__start_write_callbacks(&s, func, context);\n   return stbi_write_jpg_core(&s, x, y, comp, (void *) data, quality);\n}\n\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{\n   stbi__write_context s;\n   if (stbi__start_write_file(&s,filename)) {\n      int r = stbi_write_jpg_core(&s, x, y, comp, data, quality);\n      stbi__end_write_file(&s);\n      return r;\n   } else\n      return 0;\n}\n#endif\n\n#endif // STB_IMAGE_WRITE_IMPLEMENTATION\n\n/* Revision history\n      1.11  (2019-08-11)\n\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/*\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

  • #include \"robot_dart/robots/a1.hpp\"
  • #include \"robot_dart/robot_dart_simu.hpp\"
"},{"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\"\n\nnamespace robot_dart {\n    namespace robots {\n        A1::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        {\n            set_color_mode(\"material\");\n            set_self_collision(true);\n            set_position_enforced(true);\n\n            // put above ground\n            set_base_pose(robot_dart::make_vector({0., 0., 0., 0., 0., 0.5}));\n\n            // standing pose\n            auto names = dof_names(true, true, true);\n            names = std::vector<std::string>(names.begin() + 6, names.end());\n            set_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\n        void A1::reset()\n        {\n            Robot::reset();\n\n            // put above ground\n            set_base_pose(robot_dart::make_vector({0., 0., 0., 0., 0., 0.5}));\n\n            // standing pose\n            auto names = dof_names(true, true, true);\n            names = std::vector<std::string>(names.begin() + 6, names.end());\n            set_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

  • #include \"robot_dart/robot.hpp\"
  • #include \"robot_dart/sensor/imu.hpp\"
"},{"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\n#include \"robot_dart/robot.hpp\"\n#include \"robot_dart/sensor/imu.hpp\"\n\nnamespace robot_dart {\n    namespace robots {\n        class A1 : public Robot {\n        public:\n            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'));\n\n            void reset() override;\n\n            const sensor::IMU& imu() const { return *_imu; }\n\n        protected:\n            std::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

  • #include \"robot_dart/robot.hpp\"
"},{"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\n#include \"robot_dart/robot.hpp\"\n\nnamespace robot_dart {\n    namespace robots {\n        class Arm : public Robot {\n        public:\n            Arm(const std::string& urdf = \"arm.urdf\") : Robot(urdf)\n            {\n                fix_to_world();\n                set_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

  • #include \"robot_dart/robots/franka.hpp\"
  • #include \"robot_dart/robot_dart_simu.hpp\"
"},{"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\"\n\nnamespace robot_dart {\n    namespace robots {\n        Franka::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        {\n            fix_to_world();\n            set_position_enforced(true);\n            set_color_mode(\"material\");\n        }\n\n        void Franka::_post_addition(RobotDARTSimu* simu)\n        {\n            // We do not want to add sensors if we are a ghost robot\n            if (ghost())\n                return;\n            simu->add_sensor(_ft_wrist);\n        }\n\n        void Franka::_post_removal(RobotDARTSimu* simu)\n        {\n            simu->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

  • #include \"robot_dart/robot.hpp\"
  • #include \"robot_dart/sensor/force_torque.hpp\"
"},{"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\n#include \"robot_dart/robot.hpp\"\n#include \"robot_dart/sensor/force_torque.hpp\"\n\nnamespace robot_dart {\n    namespace robots {\n        class Franka : public Robot {\n        public:\n            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'));\n\n            const sensor::ForceTorque& ft_wrist() const { return *_ft_wrist; }\n\n        protected:\n            std::shared_ptr<sensor::ForceTorque> _ft_wrist;\n            void _post_addition(RobotDARTSimu* simu) override;\n            void _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

  • #include \"robot_dart/robot.hpp\"
"},{"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\n#include \"robot_dart/robot.hpp\"\n\nnamespace robot_dart {\n    namespace robots {\n        class Hexapod : public Robot {\n        public:\n            Hexapod(const std::string& urdf = \"pexod.urdf\") : Robot(urdf)\n            {\n                set_position_enforced(true);\n                skeleton()->enableSelfCollisionCheck();\n                set_base_pose(robot_dart::make_vector({0., 0., 0., 0., 0., 0.2}));\n            }\n\n            void reset() override\n            {\n                Robot::reset();\n                set_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

  • #include \"robot_dart/robots/icub.hpp\"
  • #include \"robot_dart/robot_dart_simu.hpp\"
"},{"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\"\n\nnamespace robot_dart {\n    namespace robots {\n        ICub::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        {\n            set_color_mode(\"material\");\n\n            set_position_enforced(true);\n\n            // position iCub\n            set_base_pose(robot_dart::make_vector({0., 0., M_PI / 2., 0., 0., 0.46}));\n        }\n\n        void ICub::reset()\n        {\n            Robot::reset();\n\n            // position iCub\n            set_base_pose(robot_dart::make_vector({0., 0., M_PI / 2., 0., 0., 0.46}));\n        }\n\n        void ICub::_post_addition(RobotDARTSimu* simu)\n        {\n            // We do not want to add sensors if we are a ghost robot\n            if (ghost())\n                return;\n            simu->add_sensor(_imu);\n            simu->add_sensor(_ft_foot_left);\n            simu->add_sensor(_ft_foot_right);\n        }\n\n        void ICub::_post_removal(RobotDARTSimu* simu)\n        {\n            simu->remove_sensor(_imu);\n            simu->remove_sensor(_ft_foot_left);\n            simu->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

  • #include \"robot_dart/robot.hpp\"
  • #include \"robot_dart/sensor/force_torque.hpp\"
  • #include \"robot_dart/sensor/imu.hpp\"
"},{"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\n#include \"robot_dart/robot.hpp\"\n#include \"robot_dart/sensor/force_torque.hpp\"\n#include \"robot_dart/sensor/imu.hpp\"\n\nnamespace robot_dart {\n    namespace robots {\n        class ICub : public Robot {\n        public:\n            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'));\n\n            void reset() override;\n\n            const sensor::IMU& imu() const { return *_imu; }\n            const sensor::ForceTorque& ft_foot_left() const { return *_ft_foot_left; }\n            const sensor::ForceTorque& ft_foot_right() const { return *_ft_foot_right; }\n\n        protected:\n            std::shared_ptr<sensor::IMU> _imu;\n            std::shared_ptr<sensor::ForceTorque> _ft_foot_left;\n            std::shared_ptr<sensor::ForceTorque> _ft_foot_right;\n\n            void _post_addition(RobotDARTSimu* simu) override;\n            void _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

  • #include \"robot_dart/robots/iiwa.hpp\"
  • #include \"robot_dart/robot_dart_simu.hpp\"
"},{"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\"\n\nnamespace robot_dart {\n    namespace robots {\n        Iiwa::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        {\n            fix_to_world();\n            set_position_enforced(true);\n        }\n\n        void Iiwa::_post_addition(RobotDARTSimu* simu)\n        {\n            // We do not want to add sensors if we are a ghost robot\n            if (ghost())\n                return;\n            simu->add_sensor(_ft_wrist);\n        }\n\n        void Iiwa::_post_removal(RobotDARTSimu* simu)\n        {\n            simu->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

  • #include \"robot_dart/robot.hpp\"
  • #include \"robot_dart/sensor/force_torque.hpp\"
"},{"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\n#include \"robot_dart/robot.hpp\"\n#include \"robot_dart/sensor/force_torque.hpp\"\n\nnamespace robot_dart {\n    namespace robots {\n        class Iiwa : public Robot {\n        public:\n            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'));\n\n            const sensor::ForceTorque& ft_wrist() const { return *_ft_wrist; }\n\n        protected:\n            std::shared_ptr<sensor::ForceTorque> _ft_wrist;\n            void _post_addition(RobotDARTSimu* simu) override;\n            void _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

  • #include \"robot_dart/robot.hpp\"
"},{"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\n#include \"robot_dart/robot.hpp\"\n\nnamespace robot_dart {\n    namespace robots {\n        class Pendulum : public Robot {\n        public:\n            Pendulum(const std::string& urdf = \"pendulum.urdf\") : Robot(urdf)\n            {\n                fix_to_world();\n                set_position_enforced(true);\n                set_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

  • #include \"robot_dart/robots/talos.hpp\"
  • #include \"robot_dart/robot_dart_simu.hpp\"
"},{"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\"\n\nnamespace robot_dart {\n    namespace robots {\n        Talos::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\n            set_position_enforced(true);\n\n            // position Talos\n            set_base_pose(robot_dart::make_vector({0., 0., M_PI / 2., 0., 0., 1.1}));\n        }\n\n        void Talos::reset()\n        {\n            Robot::reset();\n\n            // position Talos\n            set_base_pose(robot_dart::make_vector({0., 0., M_PI / 2., 0., 0., 1.1}));\n        }\n\n        void Talos::_post_addition(RobotDARTSimu* simu)\n        {\n            // We do not want to add sensors if we are a ghost robot\n            if (ghost())\n                return;\n            simu->add_sensor(_imu);\n\n            simu->add_sensor(_ft_foot_left);\n            simu->add_sensor(_ft_foot_right);\n            simu->add_sensor(_ft_wrist_left);\n            simu->add_sensor(_ft_wrist_right);\n\n            // torques sensors\n            std::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\n            };\n            for (auto& s : joints) {\n                auto t = std::make_shared<sensor::Torque>(joint(s), _frequency);\n                _torques[s] = t;\n                simu->add_sensor(t);\n            }\n        }\n\n        void Talos::_post_removal(RobotDARTSimu* simu)\n        {\n            simu->remove_sensor(_imu);\n\n            simu->remove_sensor(_ft_foot_left);\n            simu->remove_sensor(_ft_foot_right);\n            simu->remove_sensor(_ft_wrist_left);\n            simu->remove_sensor(_ft_wrist_right);\n\n            for (auto& t : _torques) {\n                simu->remove_sensor(t.second);\n            }\n        }\n\n        void TalosFastCollision::_post_addition(RobotDARTSimu* simu)\n        {\n            Talos::_post_addition(simu);\n            auto vec = TalosFastCollision::collision_vec();\n            for (auto& t : vec) {\n                simu->set_collision_masks(simu->robots().size() - 1, std::get<0>(t), std::get<1>(t), std::get<2>(t));\n            }\n        }\n\n        std::vector<std::tuple<std::string, uint32_t, uint32_t>> TalosFastCollision::collision_vec()\n        {\n            std::vector<std::tuple<std::string, uint32_t, uint32_t>> vec;\n            vec.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));\n            vec.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));\n            vec.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));\n            vec.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));\n            vec.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));\n            vec.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));\n            vec.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));\n            vec.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));\n            vec.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));\n            vec.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));\n            vec.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));\n            vec.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));\n            vec.push_back(std::make_tuple(\"torso_2_link\", 0x1000, 0x1 | 0x2 | 0x4 | 0x8 | 0x10 | 0x20 | 0x40 | 0x80 | 0x100 | 0x200 | 0x800 | 0x1000 | 0x4000 | 0x8000));\n            vec.push_back(std::make_tuple(\"base_link\", 0x2000, 0x1 | 0x2 | 0x4 | 0x8 | 0x10 | 0x20 | 0x40 | 0x80 | 0x100 | 0x200 | 0x800 | 0x2000 | 0x10000));\n            vec.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));\n            vec.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));\n            vec.push_back(std::make_tuple(\"head_2_link\", 0x10000, 0x1 | 0x2 | 0x4 | 0x8 | 0x10 | 0x20 | 0x40 | 0x80 | 0x100 | 0x200 | 0x800 | 0x2000 | 0x4000 | 0x8000 | 0x10000));\n            return 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

  • #include \"robot_dart/robot.hpp\"
  • #include \"robot_dart/sensor/force_torque.hpp\"
  • #include \"robot_dart/sensor/imu.hpp\"
  • #include \"robot_dart/sensor/torque.hpp\"
"},{"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\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\"\n\nnamespace robot_dart {\n    namespace robots {\n        class Talos : public Robot {\n        public:\n            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'));\n\n            void reset() override;\n\n            const sensor::IMU& imu() const { return *_imu; }\n            const sensor::ForceTorque& ft_foot_left() const { return *_ft_foot_left; }\n            const sensor::ForceTorque& ft_foot_right() const { return *_ft_foot_right; }\n            const sensor::ForceTorque& ft_wrist_left() const { return *_ft_wrist_left; }\n            const sensor::ForceTorque& ft_wrist_right() const { return *_ft_wrist_right; }\n\n            using torque_map_t = std::unordered_map<std::string, std::shared_ptr<sensor::Torque>>;\n            const torque_map_t& torques() const { return _torques; }\n\n        protected:\n            std::shared_ptr<sensor::IMU> _imu;\n            std::shared_ptr<sensor::ForceTorque> _ft_foot_left;\n            std::shared_ptr<sensor::ForceTorque> _ft_foot_right;\n            std::shared_ptr<sensor::ForceTorque> _ft_wrist_left;\n            std::shared_ptr<sensor::ForceTorque> _ft_wrist_right;\n            torque_map_t _torques;\n            size_t _frequency;\n\n            void _post_addition(RobotDARTSimu* simu) override;\n            void _post_removal(RobotDARTSimu* simu) override;\n        };\n\n        class TalosLight : public Talos {\n        public:\n            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')) : Talos(frequency, urdf, packages) {}\n        };\n\n        // for talos_fast_collision.urdf or talos_box.urdf which have simple box collision shapes\n        class TalosFastCollision : public Talos {\n        public:\n            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')) : Talos(frequency, urdf, packages) { set_self_collision(); }\n            static std::vector<std::tuple<std::string, uint32_t, uint32_t>> collision_vec();\n\n        protected:\n            void _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

  • #include \"robot_dart/robots/tiago.hpp\"
  • #include \"robot_dart/robot_dart_simu.hpp\"
"},{"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\"\n\nnamespace robot_dart {\n    namespace robots {\n        Tiago::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        {\n            set_position_enforced(true);\n            // We use servo actuators, but not for the caster joints\n            set_actuator_types(\"servo\");\n\n            // position Tiago\n            set_base_pose(robot_dart::make_vector({0., 0., M_PI / 2., 0., 0., 0.}));\n        }\n\n        void Tiago::reset()\n        {\n            Robot::reset();\n\n            // position Tiago\n            set_base_pose(robot_dart::make_vector({0., 0., M_PI / 2., 0., 0., 0.}));\n        }\n\n        void 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        {\n            auto jt = joint_names;\n            if (!override_caster) {\n                if (joint_names.size() == 0)\n                    jt = Robot::joint_names();\n                for (const auto& jnt : caster_joints()) {\n                    auto it = std::find(jt.begin(), jt.end(), jnt);\n                    if (it != jt.end()) {\n                        jt.erase(it);\n                    }\n                }\n            }\n            Robot::set_actuator_types(type, jt, override_mimic, override_base);\n        }\n\n        void Tiago::set_actuator_type(const std::string& type, const std::string& joint_name, bool override_mimic, bool override_base, bool override_caster)\n        {\n            set_actuator_types(type, {joint_name}, override_mimic, override_base, override_caster);\n        }\n\n        void Tiago::_post_addition(RobotDARTSimu* simu)\n        {\n            // We do not want to add sensors if we are a ghost robot\n            if (ghost())\n                return;\n            simu->add_sensor(_ft_wrist);\n        }\n\n        void Tiago::_post_removal(RobotDARTSimu* simu)\n        {\n            simu->remove_sensor(_ft_wrist);\n        }\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

  • #include \"robot_dart/robot.hpp\"
  • #include \"robot_dart/sensor/force_torque.hpp\"
"},{"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\n#include \"robot_dart/robot.hpp\"\n#include \"robot_dart/sensor/force_torque.hpp\"\n\nnamespace robot_dart {\n    namespace robots {\n        class Tiago : public Robot {\n        public:\n            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'));\n\n            void reset() override;\n\n            const sensor::ForceTorque& ft_wrist() const { return *_ft_wrist; }\n\n            std::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\"}; }\n\n            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);\n            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);\n\n        protected:\n            std::shared_ptr<sensor::ForceTorque> _ft_wrist;\n            void _post_addition(RobotDARTSimu* simu) override;\n            void _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

  • #include \"robot_dart/robots/ur3e.hpp\"
  • #include \"robot_dart/robot_dart_simu.hpp\"
"},{"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\"\n\nnamespace robot_dart {\n    namespace robots {\n        Ur3e::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        {\n            fix_to_world();\n            set_position_enforced(true);\n            set_color_mode(\"material\");\n        }\n\n        void Ur3e::_post_addition(RobotDARTSimu* simu)\n        {\n            // We do not want to add sensors if we are a ghost robot\n            if (ghost())\n                return;\n            simu->add_sensor(_ft_wrist);\n        }\n\n        void Ur3e::_post_removal(RobotDARTSimu* simu)\n        {\n            simu->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

  • #include \"robot_dart/robot.hpp\"
  • #include \"robot_dart/sensor/force_torque.hpp\"
"},{"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\n#include \"robot_dart/robot.hpp\"\n#include \"robot_dart/sensor/force_torque.hpp\"\n\nnamespace robot_dart {\n    namespace robots {\n        class Ur3e : public Robot {\n        public:\n            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'));\n\n            const sensor::ForceTorque& ft_wrist() const { return *_ft_wrist; }\n\n        protected:\n            std::shared_ptr<sensor::ForceTorque> _ft_wrist;\n            void _post_addition(RobotDARTSimu* simu) override;\n            void _post_removal(RobotDARTSimu* simu) override;\n        };\n\n        class Ur3eHand : public Ur3e {\n        public:\n            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')) : 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

  • #include \"robot_dart/robot.hpp\"
"},{"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\n#include \"robot_dart/robot.hpp\"\n\nnamespace robot_dart {\n    namespace robots {\n        class Vx300 : public Robot {\n        public:\n            Vx300(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            {\n                fix_to_world();\n                set_position_enforced(true);\n                set_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

  • #include \"force_torque.hpp\"
  • #include <robot_dart/utils_headers_dart_dynamics.hpp>
"},{"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\n#include <robot_dart/utils_headers_dart_dynamics.hpp>\n\nnamespace robot_dart {\n    namespace sensor {\n        ForceTorque::ForceTorque(dart::dynamics::Joint* joint, size_t frequency, const std::string& direction) : Sensor(frequency), _direction(direction)\n        {\n            attach_to_joint(joint, Eigen::Isometry3d::Identity());\n        }\n\n        void ForceTorque::init()\n        {\n            _wrench.setZero();\n\n            attach_to_joint(_joint_attached, Eigen::Isometry3d::Identity());\n            _active = true;\n        }\n\n        void ForceTorque::calculate(double)\n        {\n            if (!_attached_to_joint)\n                return; // cannot compute anything if not attached to a joint\n\n            Eigen::Vector6d wrench = Eigen::Vector6d::Zero();\n            auto child_body = _joint_attached->getChildBodyNode();\n            ROBOT_DART_ASSERT(child_body != nullptr, \"Child BodyNode is nullptr\", );\n\n            wrench = -dart::math::dAdT(_joint_attached->getTransformFromChildBodyNode(), child_body->getBodyForce());\n\n            // We always compute things in SENSOR frame (aka joint frame)\n            if (_direction == \"parent_to_child\") {\n                _wrench = wrench;\n            }\n            else // \"child_to_parent\" (default)\n            {\n                _wrench = -wrench;\n            }\n        }\n\n        std::string ForceTorque::type() const { return \"ft\"; }\n\n        Eigen::Vector3d ForceTorque::force() const\n        {\n            return _wrench.tail(3);\n        }\n\n        Eigen::Vector3d ForceTorque::torque() const\n        {\n            return _wrench.head(3);\n        }\n\n        const Eigen::Vector6d& ForceTorque::wrench() const\n        {\n            return _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

  • #include <robot_dart/sensor/sensor.hpp>
"},{"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\n#include <robot_dart/sensor/sensor.hpp>\n\nnamespace robot_dart {\n    namespace sensor {\n        class ForceTorque : public Sensor {\n        public:\n            ForceTorque(dart::dynamics::Joint* joint, size_t frequency = 1000, const std::string& direction = \"child_to_parent\");\n            ForceTorque(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) {}\n\n            void init() override;\n\n            void calculate(double) override;\n\n            std::string type() const override;\n\n            Eigen::Vector3d force() const;\n            Eigen::Vector3d torque() const;\n            const Eigen::Vector6d& wrench() const;\n\n            void attach_to_body(dart::dynamics::BodyNode*, const Eigen::Isometry3d&) override\n            {\n                ROBOT_DART_WARNING(true, \"You cannot attach a force/torque sensor to a body!\");\n            }\n\n        protected:\n            std::string _direction;\n\n            Eigen::Vector6d _wrench;\n        };\n    } // namespace sensor\n} // namespace robot_dart\n\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

  • #include \"imu.hpp\"
  • #include <robot_dart/robot_dart_simu.hpp>
  • #include <robot_dart/utils_headers_dart_dynamics.hpp>
"},{"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\n#include <robot_dart/robot_dart_simu.hpp>\n#include <robot_dart/utils_headers_dart_dynamics.hpp>\n\nnamespace robot_dart {\n    namespace sensor {\n        IMU::IMU(const IMUConfig& config) : Sensor(config.frequency), _config(config) {}\n\n        void IMU::init()\n        {\n            _angular_vel.setZero();\n            _linear_accel.setZero();\n\n            attach_to_body(_config.body, Eigen::Isometry3d::Identity());\n            if (_simu)\n                _active = true;\n        }\n\n        void IMU::calculate(double)\n        {\n            if (!_attached_to_body)\n                return; // cannot compute anything if not attached to a link\n            ROBOT_DART_EXCEPTION_ASSERT(_simu, \"Simulation pointer is null!\");\n\n            Eigen::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\n            // add biases\n            _angular_vel += _config.gyro_bias;\n            _linear_accel += _config.accel_bias;\n\n            // add gravity to acceleration\n            _linear_accel -= _world_pose.linear().transpose() * _simu->gravity();\n        }\n\n        std::string IMU::type() const { return \"imu\"; }\n\n        const Eigen::AngleAxisd& IMU::angular_position() const\n        {\n            return _angular_pos;\n        }\n\n        Eigen::Vector3d IMU::angular_position_vec() const\n        {\n            return _angular_pos.angle() * _angular_pos.axis();\n        }\n\n        const Eigen::Vector3d& IMU::angular_velocity() const\n        {\n            return _angular_vel;\n        }\n\n        const Eigen::Vector3d& IMU::linear_acceleration() const\n        {\n            return _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

  • #include <robot_dart/sensor/sensor.hpp>
"},{"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\n#include <robot_dart/sensor/sensor.hpp>\n\nnamespace robot_dart {\n    namespace sensor {\n        // TO-DO: Implement some noise models (e.g., https://github.com/ethz-asl/kalibr/wiki/IMU-Noise-Model)\n        struct IMUConfig {\n            IMUConfig(dart::dynamics::BodyNode* b, size_t f) : gyro_bias(Eigen::Vector3d::Zero()), accel_bias(Eigen::Vector3d::Zero()), body(b), frequency(f){};\n            IMUConfig(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){};\n            IMUConfig() : gyro_bias(Eigen::Vector3d::Zero()), accel_bias(Eigen::Vector3d::Zero()), body(nullptr), frequency(200) {}\n\n            // We assume fixed bias; TO-DO: Make this time-dependent\n            Eigen::Vector3d gyro_bias = Eigen::Vector3d::Zero();\n            Eigen::Vector3d accel_bias = Eigen::Vector3d::Zero();\n\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\n            // BodyNode/Link attached to\n            dart::dynamics::BodyNode* body = nullptr;\n            // Eigen::Isometry3d _tf = Eigen::Isometry3d::Identity();\n\n            // Frequency\n            size_t frequency = 200;\n        };\n\n        class IMU : public Sensor {\n        public:\n            IMU(const IMUConfig& config);\n\n            void init() override;\n\n            void calculate(double) override;\n\n            std::string type() const override;\n\n            const Eigen::AngleAxisd& angular_position() const;\n            Eigen::Vector3d angular_position_vec() const;\n            const Eigen::Vector3d& angular_velocity() const;\n            const Eigen::Vector3d& linear_acceleration() const;\n\n            void attach_to_joint(dart::dynamics::Joint*, const Eigen::Isometry3d&) override\n            {\n                ROBOT_DART_WARNING(true, \"You cannot attach an IMU sensor to a joint!\");\n            }\n\n        protected:\n            // double _prev_time = 0.;\n            IMUConfig _config;\n\n            Eigen::AngleAxisd _angular_pos; // TO-DO: Check how to do this as close as possible to real sensors\n            Eigen::Vector3d _angular_vel;\n            Eigen::Vector3d _linear_accel;\n        };\n    } // namespace sensor\n} // namespace robot_dart\n\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

  • #include \"sensor.hpp\"
  • #include \"robot_dart/robot_dart_simu.hpp\"
  • #include \"robot_dart/utils.hpp\"
  • #include \"robot_dart/utils_headers_dart_dynamics.hpp\"
"},{"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\"\n\nnamespace robot_dart {\n    namespace sensor {\n        Sensor::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) {}\n\n        void Sensor::activate(bool enable)\n        {\n            _active = false;\n            if (enable) {\n                init();\n            }\n        }\n\n        bool Sensor::active() const\n        {\n            return _active;\n        }\n\n        void Sensor::set_simu(RobotDARTSimu* simu)\n        {\n            ROBOT_DART_EXCEPTION_ASSERT(simu, \"Simulation pointer is null!\");\n            _simu = simu;\n            bool check = static_cast<int>(_frequency) > simu->physics_freq();\n            ROBOT_DART_WARNING(check, \"Sensor frequency is bigger than simulation physics. Setting it to simulation rate!\");\n            if (check)\n                _frequency = simu->physics_freq();\n        }\n\n        const RobotDARTSimu* Sensor::simu() const\n        {\n            return _simu;\n        }\n\n        size_t Sensor::frequency() const { return _frequency; }\n        void Sensor::set_frequency(size_t freq) { _frequency = freq; }\n\n        void Sensor::set_pose(const Eigen::Isometry3d& tf) { _world_pose = tf; }\n        const Eigen::Isometry3d& Sensor::pose() const { return _world_pose; }\n\n        void 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        }\n\n        void Sensor::refresh(double t)\n        {\n            if (!_active)\n                return;\n            if (_attaching_to_body && !_attached_to_body) {\n                attach_to_body(_body_attached, _attached_tf);\n            }\n            else if (_attaching_to_joint && !_attached_to_joint) {\n                attach_to_joint(_joint_attached, _attached_tf);\n            }\n\n            if (_attached_to_body && _body_attached) {\n                _world_pose = _body_attached->getWorldTransform() * _attached_tf;\n            }\n            else if (_attached_to_joint && _joint_attached) {\n                dart::dynamics::BodyNode* body = nullptr;\n                Eigen::Isometry3d tf = Eigen::Isometry3d::Identity();\n\n                if (_joint_attached->getParentBodyNode()) {\n                    body = _joint_attached->getParentBodyNode();\n                    tf = _joint_attached->getTransformFromParentBodyNode();\n                }\n                else if (_joint_attached->getChildBodyNode()) {\n                    body = _joint_attached->getChildBodyNode();\n                    tf = _joint_attached->getTransformFromChildBodyNode();\n                }\n\n                if (body)\n                    _world_pose = body->getWorldTransform() * tf * _attached_tf;\n            }\n            calculate(t);\n        }\n\n        void Sensor::attach_to_body(dart::dynamics::BodyNode* body, const Eigen::Isometry3d& tf)\n        {\n            _body_attached = body;\n            _attached_tf = tf;\n\n            if (_body_attached) {\n                _attaching_to_body = false;\n                _attached_to_body = true;\n\n                _attaching_to_joint = false;\n                _attached_to_joint = false;\n                _joint_attached = nullptr;\n            }\n            else { // we cannot keep attaching to a null BodyNode\n                _attaching_to_body = false;\n                _attached_to_body = false;\n            }\n        }\n\n        void Sensor::attach_to_joint(dart::dynamics::Joint* joint, const Eigen::Isometry3d& tf)\n        {\n            _joint_attached = joint;\n            _attached_tf = tf;\n\n            if (_joint_attached) {\n                _attaching_to_joint = false;\n                _attached_to_joint = true;\n\n                _attaching_to_body = false;\n                _attached_to_body = false;\n            }\n            else { // we cannot keep attaching to a null Joint\n                _attaching_to_joint = false;\n                _attached_to_joint = false;\n            }\n        }\n        const std::string& Sensor::attached_to() const\n        {\n            ROBOT_DART_EXCEPTION_ASSERT(_attached_to_body || _attached_to_joint, \"Joint is not attached to anything\");\n            if (_attached_to_body)\n                return _body_attached->getName();\n            // attached to joint\n            return _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

  • #include <robot_dart/robot.hpp>
  • #include <robot_dart/utils.hpp>
  • #include <memory>
  • #include <vector>
"},{"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\n#include <robot_dart/robot.hpp>\n#include <robot_dart/utils.hpp>\n\n#include <memory>\n#include <vector>\n\nnamespace dart {\n    namespace dynamics {\n        class BodyNode;\n        class Joint;\n    } // namespace dynamics\n} // namespace dart\n\nnamespace robot_dart {\n    class RobotDARTSimu;\n\n    namespace sensor {\n        class Sensor {\n        public:\n            Sensor(size_t freq = 40);\n            virtual ~Sensor() {}\n\n            void activate(bool enable = true);\n            bool active() const;\n\n            void set_simu(RobotDARTSimu* simu);\n            const RobotDARTSimu* simu() const;\n\n            size_t frequency() const;\n            void set_frequency(size_t freq);\n\n            void set_pose(const Eigen::Isometry3d& tf);\n            const Eigen::Isometry3d& pose() const;\n\n            void refresh(double t);\n\n            virtual void init() = 0;\n            // TO-DO: Maybe make this const?\n            virtual void calculate(double) = 0;\n\n            virtual std::string type() const = 0;\n\n            virtual void attach_to_body(dart::dynamics::BodyNode* body, const Eigen::Isometry3d& tf = Eigen::Isometry3d::Identity());\n            void 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); }\n\n            virtual void attach_to_joint(dart::dynamics::Joint* joint, const Eigen::Isometry3d& tf = Eigen::Isometry3d::Identity());\n            void 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); }\n\n            void detach();\n            const std::string& attached_to() const;\n\n        protected:\n            RobotDARTSimu* _simu = nullptr;\n            bool _active;\n            size_t _frequency;\n\n            Eigen::Isometry3d _world_pose;\n\n            bool _attaching_to_body = false, _attached_to_body = false;\n            bool _attaching_to_joint = false, _attached_to_joint = false;\n            Eigen::Isometry3d _attached_tf;\n            dart::dynamics::BodyNode* _body_attached;\n            dart::dynamics::Joint* _joint_attached;\n        };\n    } // namespace sensor\n} // namespace robot_dart\n\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

  • #include \"torque.hpp\"
  • #include <robot_dart/robot_dart_simu.hpp>
  • #include <robot_dart/utils_headers_dart_dynamics.hpp>
"},{"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\n#include <robot_dart/robot_dart_simu.hpp>\n#include <robot_dart/utils_headers_dart_dynamics.hpp>\n\nnamespace robot_dart {\n    namespace sensor {\n        Torque::Torque(dart::dynamics::Joint* joint, size_t frequency) : Sensor(frequency), _torques(joint->getNumDofs())\n        {\n            attach_to_joint(joint, Eigen::Isometry3d::Identity());\n        }\n\n        void Torque::init()\n        {\n            _torques.setZero();\n\n            attach_to_joint(_joint_attached, Eigen::Isometry3d::Identity());\n            _active = true;\n        }\n\n        void Torque::calculate(double)\n        {\n            if (!_attached_to_joint)\n                return; // cannot compute anything if not attached to a joint\n\n            Eigen::Vector6d wrench = Eigen::Vector6d::Zero();\n            auto child_body = _joint_attached->getChildBodyNode();\n            ROBOT_DART_ASSERT(child_body != nullptr, \"Child BodyNode is nullptr\", );\n\n            wrench = child_body->getBodyForce();\n\n            // get forces for only the only degrees of freedom in this joint\n            _torques = _joint_attached->getRelativeJacobian().transpose() * wrench;\n        }\n\n        std::string Torque::type() const { return \"t\"; }\n\n        const Eigen::VectorXd& Torque::torques() const\n        {\n            return _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

  • #include <robot_dart/sensor/sensor.hpp>
"},{"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\n#include <robot_dart/sensor/sensor.hpp>\n\nnamespace robot_dart {\n    namespace sensor {\n        class Torque : public Sensor {\n        public:\n            Torque(dart::dynamics::Joint* joint, size_t frequency = 1000);\n            Torque(const std::shared_ptr<Robot>& robot, const std::string& joint_name, size_t frequency = 1000) : Torque(robot->joint(joint_name), frequency) {}\n\n            void init() override;\n\n            void calculate(double) override;\n\n            std::string type() const override;\n\n            const Eigen::VectorXd& torques() const;\n\n            void attach_to_body(dart::dynamics::BodyNode*, const Eigen::Isometry3d&) override\n            {\n                ROBOT_DART_WARNING(true, \"You cannot attach a torque sensor to a body!\");\n            }\n\n        protected:\n            Eigen::VectorXd _torques;\n        };\n    } // namespace sensor\n} // namespace robot_dart\n\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

  • #include \"robot_dart_simu.hpp\"
  • #include \"gui_data.hpp\"
  • #include \"utils.hpp\"
  • #include \"utils_headers_dart_collision.hpp\"
  • #include \"utils_headers_dart_dynamics.hpp\"
  • #include <sstream>
"},{"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\n#include <sstream>\n\nnamespace robot_dart {\n    namespace 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\n        class BitmaskContactFilter : public dart::collision::BodyNodeCollisionFilter {\n        public:\n            using DartCollisionConstPtr = const dart::collision::CollisionObject*;\n            using DartShapeConstPtr = const dart::dynamics::ShapeNode*;\n\n            struct Masks {\n                uint32_t collision_mask = 0xffffffff;\n                uint32_t category_mask = 0xffffffff;\n            };\n\n            virtual ~BitmaskContactFilter() = default;\n\n            // This function follows DART's coding style as it needs to override a function\n            bool ignoresCollision(DartCollisionConstPtr object1, DartCollisionConstPtr object2) const override\n            {\n                auto shape_node1 = object1->getShapeFrame()->asShapeNode();\n                auto shape_node2 = object2->getShapeFrame()->asShapeNode();\n\n                if (dart::collision::BodyNodeCollisionFilter::ignoresCollision(object1, object2))\n                    return true;\n\n                auto shape1_iter = _bitmask_map.find(shape_node1);\n                auto shape2_iter = _bitmask_map.find(shape_node2);\n                if (shape1_iter != _bitmask_map.end() && shape2_iter != _bitmask_map.end()) {\n                    auto col_mask1 = shape1_iter->second.collision_mask;\n                    auto cat_mask1 = shape1_iter->second.category_mask;\n\n                    auto col_mask2 = shape2_iter->second.collision_mask;\n                    auto cat_mask2 = shape2_iter->second.category_mask;\n\n                    if ((col_mask1 & cat_mask2) == 0 && (col_mask2 & cat_mask1) == 0)\n                        return true;\n                }\n\n                return false;\n            }\n\n            void add_to_map(DartShapeConstPtr shape, uint32_t col_mask, uint32_t cat_mask)\n            {\n                _bitmask_map[shape] = {col_mask, cat_mask};\n            }\n\n            void add_to_map(dart::dynamics::SkeletonPtr skel, uint32_t col_mask, uint32_t cat_mask)\n            {\n                for (std::size_t i = 0; i < skel->getNumShapeNodes(); ++i) {\n                    auto shape = skel->getShapeNode(i);\n                    this->add_to_map(shape, col_mask, cat_mask);\n                }\n            }\n\n            void remove_from_map(DartShapeConstPtr shape)\n            {\n                auto shape_iter = _bitmask_map.find(shape);\n                if (shape_iter != _bitmask_map.end())\n                    _bitmask_map.erase(shape_iter);\n            }\n\n            void remove_from_map(dart::dynamics::SkeletonPtr skel)\n            {\n                for (std::size_t i = 0; i < skel->getNumShapeNodes(); ++i) {\n                    auto shape = skel->getShapeNode(i);\n                    this->remove_from_map(shape);\n                }\n            }\n\n            void clear_all() { _bitmask_map.clear(); }\n\n            Masks mask(DartShapeConstPtr shape) const\n            {\n                auto shape_iter = _bitmask_map.find(shape);\n                if (shape_iter != _bitmask_map.end())\n                    return shape_iter->second;\n                return {0xffffffff, 0xffffffff};\n            }\n\n        private:\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\n            std::unordered_map<DartShapeConstPtr, Masks> _bitmask_map;\n        };\n    } // namespace collision_filter\n\n    RobotDARTSimu::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\n        _gui_data.reset(new simu::GUIData());\n    }\n\n    RobotDARTSimu::~RobotDARTSimu()\n    {\n        _robots.clear();\n        _sensors.clear();\n    }\n\n    void RobotDARTSimu::run(double max_duration, bool reset_commands, bool force_position_bounds)\n    {\n        _break = false;\n        double old_time = _world->getTime();\n        double factor = _world->getTimeStep() / 2.;\n\n        while ((_world->getTime() - old_time - max_duration) < -factor) {\n            if (step(reset_commands, force_position_bounds))\n                break;\n        }\n    }\n\n    bool RobotDARTSimu::step_world(bool reset_commands, bool force_position_bounds)\n    {\n        if (_scheduler(_physics_freq)) {\n            _world->step(reset_commands);\n            if (force_position_bounds)\n                for (auto& r : _robots)\n                    r->force_position_bounds();\n        }\n\n        // Update graphics\n        if (_scheduler(_graphics_freq)) {\n            // Update default texts\n            if (_text_panel) { // Need to re-transform as the size of the window might have changed\n                Eigen::Affine2d tf = Eigen::Affine2d::Identity();\n                tf.translate(Eigen::Vector2d(-static_cast<double>(_graphics->width()) / 2., _graphics->height() / 2.));\n                // tf.translate(Eigen::Vector2d(-static_cast<double>(_graphics->width()) / 2., 0.));\n                _text_panel->transformation = tf;\n            }\n            if (_status_bar) {\n                _status_bar->text = status_bar_text(); // this is dynamic text (timings)\n                Eigen::Affine2d tf = Eigen::Affine2d::Identity();\n                tf.translate(Eigen::Vector2d(-static_cast<double>(_graphics->width()) / 2., -static_cast<double>(_graphics->height() / 2.)));\n                // tf.translate(Eigen::Vector2d(-static_cast<double>(_graphics->width()) / 2., 0.));\n                _status_bar->transformation = tf;\n            }\n\n            // Update robot-specific GUI data\n            for (auto& robot : _robots) {\n                _gui_data->update_robot(robot);\n            }\n\n            _graphics->refresh();\n        }\n\n        // update sensors\n        for (auto& sensor : _sensors) {\n            if (sensor->active() && _scheduler(sensor->frequency())) {\n                sensor->refresh(_world->getTime());\n            }\n        }\n\n        _old_index++;\n        _scheduler.step();\n\n        return _break || _graphics->done();\n    }\n\n    bool RobotDARTSimu::step(bool reset_commands, bool force_position_bounds)\n    {\n        if (_scheduler(_control_freq)) {\n            for (auto& robot : _robots) {\n                robot->update(_world->getTime());\n            }\n        }\n\n        return step_world(reset_commands, force_position_bounds);\n    }\n\n    std::shared_ptr<gui::Base> RobotDARTSimu::graphics() const\n    {\n        return _graphics;\n    }\n\n    void 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    }\n\n    dart::simulation::WorldPtr RobotDARTSimu::world()\n    {\n        return _world;\n    }\n\n    void RobotDARTSimu::add_sensor(const std::shared_ptr<sensor::Sensor>& sensor)\n    {\n        _sensors.push_back(sensor);\n        sensor->set_simu(this);\n        sensor->init();\n    }\n\n    std::vector<std::shared_ptr<sensor::Sensor>> RobotDARTSimu::sensors() const\n    {\n        return _sensors;\n    }\n\n    std::shared_ptr<sensor::Sensor> RobotDARTSimu::sensor(size_t index) const\n    {\n        ROBOT_DART_ASSERT(index < _sensors.size(), \"Sensor index out of bounds\", nullptr);\n        return _sensors[index];\n    }\n\n    void RobotDARTSimu::remove_sensor(const std::shared_ptr<sensor::Sensor>& sensor)\n    {\n        auto it = std::find(_sensors.begin(), _sensors.end(), sensor);\n        if (it != _sensors.end()) {\n            _sensors.erase(it);\n        }\n    }\n\n    void RobotDARTSimu::remove_sensor(size_t index)\n    {\n        ROBOT_DART_ASSERT(index < _sensors.size(), \"Sensor index out of bounds\", );\n        _sensors.erase(_sensors.begin() + index);\n    }\n\n    void RobotDARTSimu::remove_sensors(const std::string& type)\n    {\n        for (int i = 0; i < static_cast<int>(_sensors.size()); i++) {\n            auto& sensor = _sensors[i];\n            if (sensor->type() == type) {\n                _sensors.erase(_sensors.begin() + i);\n                i--;\n            }\n        }\n    }\n\n    void RobotDARTSimu::clear_sensors()\n    {\n        _sensors.clear();\n    }\n\n    double RobotDARTSimu::timestep() const\n    {\n        return _world->getTimeStep();\n    }\n\n    void RobotDARTSimu::set_timestep(double timestep, bool update_control_freq)\n    {\n        _world->setTimeStep(timestep);\n        _physics_freq = std::round(1. / timestep);\n        if (update_control_freq)\n            _control_freq = _physics_freq;\n\n        _scheduler.reset(timestep, _scheduler.sync(), _scheduler.current_time(), _scheduler.real_time());\n    }\n\n    Eigen::Vector3d RobotDARTSimu::gravity() const\n    {\n        return _world->getGravity();\n    }\n\n    void RobotDARTSimu::set_gravity(const Eigen::Vector3d& gravity)\n    {\n        _world->setGravity(gravity);\n    }\n\n    void RobotDARTSimu::stop_sim(bool disable)\n    {\n        _break = disable;\n    }\n\n    bool RobotDARTSimu::halted_sim() const\n    {\n        return _break;\n    }\n\n    size_t RobotDARTSimu::num_robots() const\n    {\n        return _robots.size();\n    }\n\n    const std::vector<std::shared_ptr<Robot>>& RobotDARTSimu::robots() const\n    {\n        return _robots;\n    }\n\n    std::shared_ptr<Robot> RobotDARTSimu::robot(size_t index) const\n    {\n        ROBOT_DART_ASSERT(index < _robots.size(), \"Robot index out of bounds\", nullptr);\n        return _robots[index];\n    }\n\n    int RobotDARTSimu::robot_index(const std::shared_ptr<Robot>& robot) const\n    {\n        auto it = std::find(_robots.begin(), _robots.end(), robot);\n        ROBOT_DART_ASSERT(it != _robots.end(), \"Robot index out of bounds\", -1);\n        return std::distance(_robots.begin(), it);\n    }\n\n    void RobotDARTSimu::add_robot(const std::shared_ptr<Robot>& robot)\n    {\n        if (robot->skeleton()) {\n            _robots.push_back(robot);\n            _world->addSkeleton(robot->skeleton());\n\n            robot->_post_addition(this);\n\n            _gui_data->update_robot(robot);\n        }\n    }\n\n    void RobotDARTSimu::add_visual_robot(const std::shared_ptr<Robot>& robot)\n    {\n        if (robot->skeleton()) {\n            // make robot a pure visual one -- assuming that the color is already set\n            // visual robots do not do physics updates\n            robot->skeleton()->setMobile(false);\n            for (auto& bd : robot->skeleton()->getBodyNodes()) {\n#if DART_VERSION_AT_LEAST(6, 13, 0)\n                // visual robots do not have collisions\n                bd->eachShapeNodeWith<dart::dynamics::CollisionAspect>([](dart::dynamics::ShapeNode* shape) {\n                    shape->removeAspect<dart::dynamics::CollisionAspect>();\n                });\n#else\n                auto& collision_shapes = bd->getShapeNodesWith<dart::dynamics::CollisionAspect>();\n                for (auto& shape : collision_shapes) {\n                    shape->removeAspect<dart::dynamics::CollisionAspect>();\n                }\n#endif\n            }\n\n            // visual robots, by default, use the color from the VisualAspect\n            robot->set_color_mode(\"aspect\");\n\n            // visual robots do not cast shadows\n            robot->set_cast_shadows(false);\n            // set the ghost/visual flag\n            robot->set_ghost(true);\n            robot->_post_addition(this);\n\n            _robots.push_back(robot);\n            _world->addSkeleton(robot->skeleton());\n\n            _gui_data->update_robot(robot);\n        }\n    }\n\n    void RobotDARTSimu::remove_robot(const std::shared_ptr<Robot>& robot)\n    {\n        auto it = std::find(_robots.begin(), _robots.end(), robot);\n        if (it != _robots.end()) {\n            robot->_post_removal(this);\n            _gui_data->remove_robot(robot);\n            _world->removeSkeleton(robot->skeleton());\n            _robots.erase(it);\n        }\n    }\n\n    void RobotDARTSimu::remove_robot(size_t index)\n    {\n        ROBOT_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    }\n\n    void RobotDARTSimu::clear_robots()\n    {\n        for (auto& robot : _robots) {\n            robot->_post_removal(this);\n            _gui_data->remove_robot(robot);\n            _world->removeSkeleton(robot->skeleton());\n        }\n        _robots.clear();\n    }\n\n    simu::GUIData* RobotDARTSimu::gui_data() { return &(*_gui_data); }\n\n    void RobotDARTSimu::enable_text_panel(bool enable, double font_size)\n    {\n        _enable(_text_panel, enable, font_size);\n        if (enable) {\n            _text_panel->alignment = 3 << 2; // alignment of status bar should be LineTop; TO-DO: Check how to get types automatically from Magnum?\n            // _text_panel->draw_background = true; // we want to draw a background\n            // _text_panel->background_color = Eigen::Vector4d(0, 0, 0, 0.75); // black-transparent bar\n        }\n    }\n\n    void RobotDARTSimu::enable_status_bar(bool enable, double font_size)\n    {\n        _enable(_status_bar, enable, font_size);\n        if (enable) {\n            _status_bar->alignment = 1 << 2; // alignment of status bar should be LineBottom; TO-DO: Check how to get types automatically from Magnum?\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    }\n\n    void RobotDARTSimu::_enable(std::shared_ptr<simu::TextData>& text, bool enable, double font_size)\n    {\n        if (!text && enable) {\n            text = add_text(\"\");\n        }\n        else if (!enable) {\n            if (text)\n                _gui_data->remove_text(text);\n            text = nullptr;\n        }\n        if (text && font_size > 0)\n            text->font_size = font_size;\n    }\n\n    void RobotDARTSimu::set_text_panel(const std::string& str)\n    {\n        ROBOT_DART_ASSERT(_text_panel, \"Panel text object not created. Use enable_text_panel() to create it.\", );\n        _text_panel->text = str;\n    }\n\n    std::string RobotDARTSimu::text_panel_text() const\n    {\n        ROBOT_DART_ASSERT(_text_panel, \"Panel text object not created. Returning empty string.\", \"\");\n        return _text_panel->text;\n    }\n\n    std::string RobotDARTSimu::status_bar_text() const\n    {\n        std::ostringstream out;\n        out.precision(3);\n        double rt = _scheduler.real_time();\n\n        out << std::fixed << \"[simulation time: \" << _world->getTime()\n            << \"s ] [\"\n            << \"wall time: \" << rt << \"s] [\";\n        out.precision(1);\n        out << _scheduler.real_time_factor() << \"x]\";\n        out << \" [it: \" << _scheduler.it_duration() * 1e3 << \" ms]\";\n        out << (_scheduler.sync() ? \" [sync]\" : \" [no-sync]\");\n\n        return out.str();\n    }\n\n    std::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    {\n        return _gui_data->add_text(text, tf, color, alignment, draw_bg, bg_color, font_size);\n    }\n\n    std::shared_ptr<Robot> RobotDARTSimu::add_floor(double floor_width, double floor_height, const Eigen::Isometry3d& tf, const std::string& floor_name)\n    {\n        ROBOT_DART_ASSERT((_world->getSkeleton(floor_name) == nullptr), \"We cannot have 2 floors with the name '\" + floor_name + \"'\", nullptr);\n        ROBOT_DART_ASSERT((floor_width > 0. && floor_height > 0.), \"Floor dimensions should be bigger than zero!\", nullptr);\n\n        dart::dynamics::SkeletonPtr floor_skel = dart::dynamics::Skeleton::create(floor_name);\n\n        // Give the floor a body\n        dart::dynamics::BodyNodePtr body = floor_skel->createJointAndBodyNodePair<dart::dynamics::WeldJoint>(nullptr).second;\n\n        // Give the body a shape\n        auto box = std::make_shared<dart::dynamics::BoxShape>(Eigen::Vector3d(floor_width, floor_width, floor_height));\n        auto box_node = body->createShapeNodeWith<dart::dynamics::VisualAspect, dart::dynamics::CollisionAspect, dart::dynamics::DynamicsAspect>(box);\n        box_node->getVisualAspect()->setColor(dart::Color::Gray());\n\n        // Put the body into position\n        Eigen::Isometry3d new_tf = tf;\n        new_tf.translate(Eigen::Vector3d(0., 0., -floor_height / 2.0));\n        body->getParentJoint()->setTransformFromParentBodyNode(new_tf);\n\n        auto floor_robot = std::make_shared<Robot>(floor_skel, floor_name);\n        add_robot(floor_robot);\n        return floor_robot;\n    }\n\n    std::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    {\n        ROBOT_DART_ASSERT((_world->getSkeleton(floor_name) == nullptr), \"We cannot have 2 floors with the name '\" + floor_name + \"'\", nullptr);\n        ROBOT_DART_ASSERT((floor_width > 0. && floor_height > 0. && size > 0.), \"Floor dimensions should be bigger than zero!\", nullptr);\n\n        // Add main floor skeleton\n        dart::dynamics::SkeletonPtr main_floor_skel = dart::dynamics::Skeleton::create(floor_name + \"_main\");\n\n        // Give the floor a body\n        dart::dynamics::BodyNodePtr main_body = main_floor_skel->createJointAndBodyNodePair<dart::dynamics::WeldJoint>(nullptr).second;\n\n        // Give the body a shape\n        auto 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\n        main_body->createShapeNodeWith<dart::dynamics::CollisionAspect, dart::dynamics::DynamicsAspect>(box);\n\n        // Put the body into position\n        Eigen::Isometry3d new_tf = tf;\n        new_tf.translate(Eigen::Vector3d(0., 0., -floor_height / 2.0));\n        main_body->getParentJoint()->setTransformFromParentBodyNode(new_tf);\n\n        // Add visual bodies just for visualization\n        int step = std::ceil(floor_width / size);\n        int c = 0;\n        for (int i = 0; i < step; i++) {\n            c = i;\n            for (int j = 0; j < step; j++) {\n                Eigen::Vector3d init_pose;\n                init_pose << -floor_width / 2. + size / 2 + i * size, -floor_width / 2. + size / 2 + j * size, 0.;\n                int id = i * step + j;\n\n                dart::dynamics::WeldJoint::Properties properties;\n                properties.mName = \"joint_\" + std::to_string(id);\n                dart::dynamics::BodyNode::Properties bd_properties;\n                bd_properties.mName = \"body_\" + std::to_string(id);\n                dart::dynamics::BodyNodePtr body = main_body->createChildJointAndBodyNodePair<dart::dynamics::WeldJoint>(properties, bd_properties).second;\n\n                auto box = std::make_shared<dart::dynamics::BoxShape>(Eigen::Vector3d(size, size, floor_height));\n                // no collision/dynamics for these ones; only visual shape\n                auto box_node = body->createShapeNodeWith<dart::dynamics::VisualAspect>(box);\n                if (c % 2 == 0)\n                    box_node->getVisualAspect()->setColor(second_color);\n                else\n                    box_node->getVisualAspect()->setColor(first_color);\n\n                // Put the body into position\n                Eigen::Isometry3d tf(Eigen::Isometry3d::Identity());\n                tf.translation() = init_pose;\n                body->getParentJoint()->setTransformFromParentBodyNode(tf);\n\n                c++;\n            }\n        }\n\n        auto floor_robot = std::make_shared<Robot>(main_floor_skel, floor_name);\n        add_robot(floor_robot);\n        return floor_robot;\n    }\n\n    void RobotDARTSimu::set_collision_detector(const std::string& collision_detector)\n    {\n        std::string coll = collision_detector;\n        for (auto& c : coll)\n            c = tolower(c);\n\n        if (coll == \"dart\")\n            _world->getConstraintSolver()->setCollisionDetector(dart::collision::DARTCollisionDetector::create());\n        else if (coll == \"fcl\")\n            _world->getConstraintSolver()->setCollisionDetector(dart::collision::FCLCollisionDetector::create());\n        else if (coll == \"bullet\") {\n#if (HAVE_BULLET == 1)\n            _world->getConstraintSolver()->setCollisionDetector(dart::collision::BulletCollisionDetector::create());\n#else\n            ROBOT_DART_WARNING(true, \"DART is not installed with Bullet! Cannot set BulletCollisionDetector!\");\n#endif\n        }\n        else if (coll == \"ode\") {\n#if (HAVE_ODE == 1)\n            _world->getConstraintSolver()->setCollisionDetector(dart::collision::OdeCollisionDetector::create());\n#else\n            ROBOT_DART_WARNING(true, \"DART is not installed with ODE! Cannot set OdeCollisionDetector!\");\n#endif\n        }\n    }\n\n    const std::string& RobotDARTSimu::collision_detector() const { return _world->getConstraintSolver()->getCollisionDetector()->getType(); }\n\n    void RobotDARTSimu::set_collision_masks(size_t robot_index, uint32_t category_mask, uint32_t collision_mask)\n    {\n        ROBOT_DART_ASSERT(robot_index < _robots.size(), \"Robot index out of bounds\", );\n        auto coll_filter = std::static_pointer_cast<collision_filter::BitmaskContactFilter>(_world->getConstraintSolver()->getCollisionOption().collisionFilter);\n        coll_filter->add_to_map(_robots[robot_index]->skeleton(), collision_mask, category_mask);\n    }\n\n    void RobotDARTSimu::set_collision_masks(size_t robot_index, const std::string& body_name, uint32_t category_mask, uint32_t collision_mask)\n    {\n        ROBOT_DART_ASSERT(robot_index < _robots.size(), \"Robot index out of bounds\", );\n        auto bd = _robots[robot_index]->skeleton()->getBodyNode(body_name);\n        ROBOT_DART_ASSERT(bd != nullptr, \"BodyNode does not exist in skeleton!\", );\n        auto coll_filter = std::static_pointer_cast<collision_filter::BitmaskContactFilter>(_world->getConstraintSolver()->getCollisionOption().collisionFilter);\n#if DART_VERSION_AT_LEAST(6, 13, 0)\n        bd->eachShapeNode([coll_filter, collision_mask, category_mask](dart::dynamics::ShapeNode* shape) { coll_filter->add_to_map(shape, collision_mask, category_mask); });\n#else\n        for (auto& shape : bd->getShapeNodes())\n            coll_filter->add_to_map(shape, collision_mask, category_mask);\n#endif\n    }\n\n    void RobotDARTSimu::set_collision_masks(size_t robot_index, size_t body_index, uint32_t category_mask, uint32_t collision_mask)\n    {\n        ROBOT_DART_ASSERT(robot_index < _robots.size(), \"Robot index out of bounds\", );\n        auto skel = _robots[robot_index]->skeleton();\n        ROBOT_DART_ASSERT(body_index < skel->getNumBodyNodes(), \"BodyNode index out of bounds\", );\n        auto bd = skel->getBodyNode(body_index);\n        auto coll_filter = std::static_pointer_cast<collision_filter::BitmaskContactFilter>(_world->getConstraintSolver()->getCollisionOption().collisionFilter);\n#if DART_VERSION_AT_LEAST(6, 13, 0)\n        bd->eachShapeNode([coll_filter, collision_mask, category_mask](dart::dynamics::ShapeNode* shape) { coll_filter->add_to_map(shape, collision_mask, category_mask); });\n#else\n        for (auto& shape : bd->getShapeNodes())\n            coll_filter->add_to_map(shape, collision_mask, category_mask);\n#endif\n    }\n\n    uint32_t RobotDARTSimu::collision_mask(size_t robot_index, const std::string& body_name)\n    {\n        ROBOT_DART_ASSERT(robot_index < _robots.size(), \"Robot index out of bounds\", 0xffffffff);\n        auto bd = _robots[robot_index]->skeleton()->getBodyNode(body_name);\n        ROBOT_DART_ASSERT(bd != nullptr, \"BodyNode does not exist in skeleton!\", 0xffffffff);\n        auto coll_filter = std::static_pointer_cast<collision_filter::BitmaskContactFilter>(_world->getConstraintSolver()->getCollisionOption().collisionFilter);\n\n        uint32_t mask = 0xffffffff;\n#if DART_VERSION_AT_LEAST(6, 13, 0)\n        bd->eachShapeNode([coll_filter, &mask](dart::dynamics::ShapeNode* shape) { mask &= coll_filter->mask(shape).collision_mask; });\n#else\n        for (auto& shape : bd->getShapeNodes())\n            mask &= coll_filter->mask(shape).collision_mask;\n#endif\n\n        return mask;\n    }\n\n    uint32_t RobotDARTSimu::collision_mask(size_t robot_index, size_t body_index)\n    {\n        ROBOT_DART_ASSERT(robot_index < _robots.size(), \"Robot index out of bounds\", 0xffffffff);\n        auto skel = _robots[robot_index]->skeleton();\n        ROBOT_DART_ASSERT(body_index < skel->getNumBodyNodes(), \"BodyNode index out of bounds\", 0xffffffff);\n        auto bd = skel->getBodyNode(body_index);\n        auto coll_filter = std::static_pointer_cast<collision_filter::BitmaskContactFilter>(_world->getConstraintSolver()->getCollisionOption().collisionFilter);\n\n        uint32_t mask = 0xffffffff;\n#if DART_VERSION_AT_LEAST(6, 13, 0)\n        bd->eachShapeNode([coll_filter, &mask](dart::dynamics::ShapeNode* shape) { mask &= coll_filter->mask(shape).collision_mask; });\n#else\n        for (auto& shape : bd->getShapeNodes())\n            mask &= coll_filter->mask(shape).collision_mask;\n#endif\n\n        return mask;\n    }\n\n    uint32_t RobotDARTSimu::collision_category(size_t robot_index, const std::string& body_name)\n    {\n        ROBOT_DART_ASSERT(robot_index < _robots.size(), \"Robot index out of bounds\", 0xffffffff);\n        auto bd = _robots[robot_index]->skeleton()->getBodyNode(body_name);\n        ROBOT_DART_ASSERT(bd != nullptr, \"BodyNode does not exist in skeleton!\", 0xffffffff);\n        auto coll_filter = std::static_pointer_cast<collision_filter::BitmaskContactFilter>(_world->getConstraintSolver()->getCollisionOption().collisionFilter);\n\n        uint32_t mask = 0xffffffff;\n#if DART_VERSION_AT_LEAST(6, 13, 0)\n        bd->eachShapeNode([coll_filter, &mask](dart::dynamics::ShapeNode* shape) { mask &= coll_filter->mask(shape).category_mask; });\n#else\n        for (auto& shape : bd->getShapeNodes())\n            mask &= coll_filter->mask(shape).category_mask;\n#endif\n\n        return mask;\n    }\n\n    uint32_t RobotDARTSimu::collision_category(size_t robot_index, size_t body_index)\n    {\n        ROBOT_DART_ASSERT(robot_index < _robots.size(), \"Robot index out of bounds\", 0xffffffff);\n        auto skel = _robots[robot_index]->skeleton();\n        ROBOT_DART_ASSERT(body_index < skel->getNumBodyNodes(), \"BodyNode index out of bounds\", 0xffffffff);\n        auto bd = skel->getBodyNode(body_index);\n        auto coll_filter = std::static_pointer_cast<collision_filter::BitmaskContactFilter>(_world->getConstraintSolver()->getCollisionOption().collisionFilter);\n\n        uint32_t mask = 0xffffffff;\n#if DART_VERSION_AT_LEAST(6, 13, 0)\n        bd->eachShapeNode([coll_filter, &mask](dart::dynamics::ShapeNode* shape) { mask &= coll_filter->mask(shape).category_mask; });\n#else\n        for (auto& shape : bd->getShapeNodes())\n            mask &= coll_filter->mask(shape).category_mask;\n#endif\n\n        return mask;\n    }\n\n    std::pair<uint32_t, uint32_t> RobotDARTSimu::collision_masks(size_t robot_index, const std::string& body_name)\n    {\n        std::pair<uint32_t, uint32_t> mask = {0xffffffff, 0xffffffff};\n        ROBOT_DART_ASSERT(robot_index < _robots.size(), \"Robot index out of bounds\", mask);\n        auto bd = _robots[robot_index]->skeleton()->getBodyNode(body_name);\n        ROBOT_DART_ASSERT(bd != nullptr, \"BodyNode does not exist in skeleton!\", mask);\n        auto coll_filter = std::static_pointer_cast<collision_filter::BitmaskContactFilter>(_world->getConstraintSolver()->getCollisionOption().collisionFilter);\n\n#if DART_VERSION_AT_LEAST(6, 13, 0)\n        bd->eachShapeNode([coll_filter, &mask](dart::dynamics::ShapeNode* shape) {\n            mask.first &= coll_filter->mask(shape).collision_mask;\n            mask.second &= coll_filter->mask(shape).category_mask;\n        });\n#else\n        for (auto& shape : bd->getShapeNodes()) {\n            mask.first &= coll_filter->mask(shape).collision_mask;\n            mask.second &= coll_filter->mask(shape).category_mask;\n        }\n#endif\n\n        return mask;\n    }\n\n    std::pair<uint32_t, uint32_t> RobotDARTSimu::collision_masks(size_t robot_index, size_t body_index)\n    {\n        std::pair<uint32_t, uint32_t> mask = {0xffffffff, 0xffffffff};\n        ROBOT_DART_ASSERT(robot_index < _robots.size(), \"Robot index out of bounds\", mask);\n        auto skel = _robots[robot_index]->skeleton();\n        ROBOT_DART_ASSERT(body_index < skel->getNumBodyNodes(), \"BodyNode index out of bounds\", mask);\n        auto bd = skel->getBodyNode(body_index);\n        auto coll_filter = std::static_pointer_cast<collision_filter::BitmaskContactFilter>(_world->getConstraintSolver()->getCollisionOption().collisionFilter);\n\n#if DART_VERSION_AT_LEAST(6, 13, 0)\n        bd->eachShapeNode([coll_filter, &mask](dart::dynamics::ShapeNode* shape) {\n            mask.first &= coll_filter->mask(shape).collision_mask;\n            mask.second &= coll_filter->mask(shape).category_mask;\n        });\n#else\n        for (auto& shape : bd->getShapeNodes()) {\n            mask.first &= coll_filter->mask(shape).collision_mask;\n            mask.second &= coll_filter->mask(shape).category_mask;\n        }\n#endif\n\n        return mask;\n    }\n\n    void RobotDARTSimu::remove_collision_masks(size_t robot_index)\n    {\n        ROBOT_DART_ASSERT(robot_index < _robots.size(), \"Robot index out of bounds\", );\n        auto coll_filter = std::static_pointer_cast<collision_filter::BitmaskContactFilter>(_world->getConstraintSolver()->getCollisionOption().collisionFilter);\n        coll_filter->remove_from_map(_robots[robot_index]->skeleton());\n    }\n\n    void RobotDARTSimu::remove_collision_masks(size_t robot_index, const std::string& body_name)\n    {\n        ROBOT_DART_ASSERT(robot_index < _robots.size(), \"Robot index out of bounds\", );\n        auto bd = _robots[robot_index]->skeleton()->getBodyNode(body_name);\n        ROBOT_DART_ASSERT(bd != nullptr, \"BodyNode does not exist in skeleton!\", );\n        auto coll_filter = std::static_pointer_cast<collision_filter::BitmaskContactFilter>(_world->getConstraintSolver()->getCollisionOption().collisionFilter);\n#if DART_VERSION_AT_LEAST(6, 13, 0)\n        bd->eachShapeNode([coll_filter](dart::dynamics::ShapeNode* shape) { coll_filter->remove_from_map(shape); });\n#else\n        for (auto& shape : bd->getShapeNodes())\n            coll_filter->remove_from_map(shape);\n#endif\n    }\n\n    void RobotDARTSimu::remove_collision_masks(size_t robot_index, size_t body_index)\n    {\n        ROBOT_DART_ASSERT(robot_index < _robots.size(), \"Robot index out of bounds\", );\n        auto skel = _robots[robot_index]->skeleton();\n        ROBOT_DART_ASSERT(body_index < skel->getNumBodyNodes(), \"BodyNode index out of bounds\", );\n        auto bd = skel->getBodyNode(body_index);\n        auto coll_filter = std::static_pointer_cast<collision_filter::BitmaskContactFilter>(_world->getConstraintSolver()->getCollisionOption().collisionFilter);\n#if DART_VERSION_AT_LEAST(6, 13, 0)\n        bd->eachShapeNode([coll_filter](dart::dynamics::ShapeNode* shape) { coll_filter->remove_from_map(shape); });\n#else\n        for (auto& shape : bd->getShapeNodes())\n            coll_filter->remove_from_map(shape);\n#endif\n    }\n\n    void RobotDARTSimu::remove_all_collision_masks()\n    {\n        auto coll_filter = std::static_pointer_cast<collision_filter::BitmaskContactFilter>(_world->getConstraintSolver()->getCollisionOption().collisionFilter);\n        coll_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

  • #include <robot_dart/gui/base.hpp>
  • #include <robot_dart/robot.hpp>
  • #include <robot_dart/scheduler.hpp>
  • #include <robot_dart/sensor/sensor.hpp>
"},{"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\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>\n\nnamespace robot_dart {\n    namespace simu {\n        struct GUIData;\n\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\n        struct TextData {\n            std::string text;\n            Eigen::Affine2d transformation;\n            Eigen::Vector4d color;\n            std::uint8_t alignment;\n            bool draw_background;\n            Eigen::Vector4d background_color;\n            double font_size = 28.;\n        };\n    } // namespace simu\n\n    class RobotDARTSimu {\n    public:\n        using robot_t = std::shared_ptr<Robot>;\n\n        RobotDARTSimu(double timestep = 0.015);\n\n        ~RobotDARTSimu();\n\n        void run(double max_duration = 5.0, bool reset_commands = false, bool force_position_bounds = true);\n        bool step_world(bool reset_commands = false, bool force_position_bounds = true);\n        bool step(bool reset_commands = false, bool force_position_bounds = true);\n\n        Scheduler& scheduler() { return _scheduler; }\n        const Scheduler& scheduler() const { return _scheduler; }\n        bool schedule(int freq) { return _scheduler(freq); }\n\n        int physics_freq() const { return _physics_freq; }\n        int control_freq() const { return _control_freq; }\n\n        void set_control_freq(int frequency)\n        {\n            ROBOT_DART_EXCEPTION_INTERNAL_ASSERT(\n                frequency <= _physics_freq && \"Control frequency needs to be less than physics frequency\");\n            _control_freq = frequency;\n        }\n\n        int graphics_freq() const { return _graphics_freq; }\n\n        void set_graphics_freq(int frequency)\n        {\n            ROBOT_DART_EXCEPTION_INTERNAL_ASSERT(\n                frequency <= _physics_freq && \"Graphics frequency needs to be less than physics frequency\");\n            _graphics_freq = frequency;\n            _graphics->set_fps(_graphics_freq);\n        }\n\n        std::shared_ptr<gui::Base> graphics() const;\n        void set_graphics(const std::shared_ptr<gui::Base>& graphics);\n\n        dart::simulation::WorldPtr world();\n\n        template <typename T, typename... Args>\n        std::shared_ptr<T> add_sensor(Args&&... args)\n        {\n            add_sensor(std::make_shared<T>(std::forward<Args>(args)...));\n            return std::static_pointer_cast<T>(_sensors.back());\n        }\n\n        void add_sensor(const std::shared_ptr<sensor::Sensor>& sensor);\n        std::vector<std::shared_ptr<sensor::Sensor>> sensors() const;\n        std::shared_ptr<sensor::Sensor> sensor(size_t index) const;\n\n        void remove_sensor(const std::shared_ptr<sensor::Sensor>& sensor);\n        void remove_sensor(size_t index);\n        void remove_sensors(const std::string& type);\n        void clear_sensors();\n\n        double timestep() const;\n        void set_timestep(double timestep, bool update_control_freq = true);\n\n        Eigen::Vector3d gravity() const;\n        void set_gravity(const Eigen::Vector3d& gravity);\n\n        void stop_sim(bool disable = true);\n        bool halted_sim() const;\n\n        size_t num_robots() const;\n        const std::vector<robot_t>& robots() const;\n        robot_t robot(size_t index) const;\n        int robot_index(const robot_t& robot) const;\n\n        void add_robot(const robot_t& robot);\n        void add_visual_robot(const robot_t& robot);\n        void remove_robot(const robot_t& robot);\n        void remove_robot(size_t index);\n        void clear_robots();\n\n        simu::GUIData* gui_data();\n\n        void enable_text_panel(bool enable = true, double font_size = -1);\n        std::string text_panel_text() const;\n        void set_text_panel(const std::string& str);\n\n        void enable_status_bar(bool enable = true, double font_size = -1);\n        std::string status_bar_text() const;\n\n        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 = 2 << 2, bool draw_bg = false, Eigen::Vector4d bg_color = Eigen::Vector4d(0, 0, 0, 0.75), double font_size = 28);\n\n        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\");\n        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.));\n\n        void set_collision_detector(const std::string& collision_detector); // collision_detector can be \"DART\", \"FCL\", \"Ode\" or \"Bullet\" (case does not matter)\n        const std::string& collision_detector() const;\n\n        // Bitmask collision filtering\n        void set_collision_masks(size_t robot_index, uint32_t category_mask, uint32_t collision_mask);\n        void set_collision_masks(size_t robot_index, const std::string& body_name, uint32_t category_mask, uint32_t collision_mask);\n        void set_collision_masks(size_t robot_index, size_t body_index, uint32_t category_mask, uint32_t collision_mask);\n\n        uint32_t collision_mask(size_t robot_index, const std::string& body_name);\n        uint32_t collision_mask(size_t robot_index, size_t body_index);\n\n        uint32_t collision_category(size_t robot_index, const std::string& body_name);\n        uint32_t collision_category(size_t robot_index, size_t body_index);\n\n        std::pair<uint32_t, uint32_t> collision_masks(size_t robot_index, const std::string& body_name);\n        std::pair<uint32_t, uint32_t> collision_masks(size_t robot_index, size_t body_index);\n\n        void remove_collision_masks(size_t robot_index);\n        void remove_collision_masks(size_t robot_index, const std::string& body_name);\n        void remove_collision_masks(size_t robot_index, size_t body_index);\n\n        void remove_all_collision_masks();\n\n    protected:\n        void _enable(std::shared_ptr<simu::TextData>& text, bool enable, double font_size);\n\n        dart::simulation::WorldPtr _world;\n        size_t _old_index;\n        bool _break;\n\n        std::vector<std::shared_ptr<sensor::Sensor>> _sensors;\n        std::vector<robot_t> _robots;\n        std::shared_ptr<gui::Base> _graphics;\n        std::unique_ptr<simu::GUIData> _gui_data;\n        std::shared_ptr<simu::TextData> _text_panel = nullptr;\n        std::shared_ptr<simu::TextData> _status_bar = nullptr;\n\n        Scheduler _scheduler;\n        int _physics_freq = -1, _control_freq = -1, _graphics_freq = 40;\n    };\n} // namespace robot_dart\n\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

  • #include <robot_dart/robot_pool.hpp>
"},{"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>\n\nnamespace robot_dart {\n    RobotPool::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    {\n        if (_verbose) {\n            std::cout << \"Creating a pool of \" << pool_size << \" robots: \";\n            std::cout.flush();\n        }\n\n        for (size_t i = 0; i < _pool_size; ++i) {\n            if (_verbose) {\n                std::cout << \"[\" << i << \"]\";\n                std::cout.flush();\n            }\n            auto robot = robot_creator();\n            _model_filename = robot->model_filename();\n            _reset_robot(robot);\n            _skeletons.push_back(robot->skeleton());\n        }\n        for (size_t i = 0; i < _pool_size; i++)\n            _free.push_back(true);\n\n        if (_verbose)\n            std::cout << std::endl;\n    }\n\n    std::shared_ptr<Robot> RobotPool::get_robot(const std::string& name)\n    {\n        while (true) {\n            std::lock_guard<std::mutex> lock(_skeleton_mutex);\n            for (size_t i = 0; i < _pool_size; i++)\n                if (_free[i]) {\n                    _free[i] = false;\n                    return std::make_shared<Robot>(_skeletons[i], name);\n                }\n        }\n    }\n\n    void RobotPool::free_robot(const std::shared_ptr<Robot>& robot)\n    {\n        std::lock_guard<std::mutex> lock(_skeleton_mutex);\n        for (size_t i = 0; i < _pool_size; i++) {\n            if (_skeletons[i] == robot->skeleton()) {\n                _reset_robot(robot);\n                _free[i] = true;\n                break;\n            }\n        }\n    }\n\n    void RobotPool::_reset_robot(const std::shared_ptr<Robot>& robot)\n    {\n        robot->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

  • #include <functional>
  • #include <memory>
  • #include <mutex>
  • #include <vector>
  • #include <robot_dart/robot.hpp>
"},{"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\n#include <functional>\n#include <memory>\n#include <mutex>\n#include <vector>\n\n#include <robot_dart/robot.hpp>\n\nnamespace robot_dart {\n    class RobotPool {\n    public:\n        using robot_creator_t = std::function<std::shared_ptr<Robot>()>;\n\n        RobotPool(const robot_creator_t& robot_creator, size_t pool_size = 32, bool verbose = true);\n        virtual ~RobotPool() {}\n\n        RobotPool(const RobotPool&) = delete;\n        void operator=(const RobotPool&) = delete;\n\n        virtual std::shared_ptr<Robot> get_robot(const std::string& name = \"robot\");\n        virtual void free_robot(const std::shared_ptr<Robot>& robot);\n\n        const std::string& model_filename() const { return _model_filename; }\n\n    protected:\n        robot_creator_t _robot_creator;\n        size_t _pool_size;\n        bool _verbose;\n        std::vector<dart::dynamics::SkeletonPtr> _skeletons;\n        std::vector<bool> _free;\n        std::mutex _skeleton_mutex;\n        std::string _model_filename;\n\n        virtual void _reset_robot(const std::shared_ptr<Robot>& robot);\n    };\n} // namespace robot_dart\n\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

  • #include <robot_dart/scheduler.hpp>
"},{"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>\n\nnamespace robot_dart {\n    bool Scheduler::schedule(int frequency)\n    {\n        if (_max_frequency == -1) {\n            _start_time = clock_t::now();\n            _last_iteration_time = _start_time;\n        }\n\n        _max_frequency = std::max(_max_frequency, frequency);\n        double period = std::round((1. / frequency) / _dt);\n\n        ROBOT_DART_EXCEPTION_INTERNAL_ASSERT(\n            period >= 1. && \"Time-step is too big for required frequency.\");\n\n        if (_current_step % int(period) == 0)\n            return true;\n\n        return false;\n    }\n\n    void Scheduler::reset(double dt, bool sync, double current_time, double real_time)\n    {\n        ROBOT_DART_EXCEPTION_INTERNAL_ASSERT(dt > 0. && \"Time-step needs to be bigger than zero.\");\n\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\n        _dt = dt;\n        _sync = sync;\n    }\n\n    double Scheduler::step()\n    {\n        _current_time += _dt;\n        _current_step += 1;\n\n        auto 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;\n        std::chrono::duration<double, std::micro> real = end - _start_time;\n        if (_sync) {\n            auto expected = std::chrono::microseconds(int(_current_time * 1e6));\n            std::chrono::duration<double, std::micro> adjust = expected - real;\n            if (adjust.count() > 0)\n                std::this_thread::sleep_for(adjust);\n        }\n\n        _real_time = real.count() * 1e-6;\n        return _real_start_time + _real_time;\n    }\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

  • #include <robot_dart/utils.hpp>
  • #include <chrono>
  • #include <thread>
"},{"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\n#include <robot_dart/utils.hpp>\n\n#include <chrono>\n#include <thread>\n\nnamespace robot_dart {\n    class Scheduler {\n    protected:\n        using clock_t = std::chrono::high_resolution_clock;\n\n    public:\n        Scheduler(double dt, bool sync = false) : _dt(dt), _sync(sync)\n        {\n            ROBOT_DART_EXCEPTION_INTERNAL_ASSERT(_dt > 0. && \"Time-step needs to be bigger than zero.\");\n        }\n\n        bool operator()(int frequency) { return schedule(frequency); };\n        bool schedule(int frequency);\n\n        double step();\n\n        void reset(double dt, bool sync = false, double current_time = 0., double real_time = 0.);\n\n        void set_sync(bool enable) { _sync = enable; }\n        bool sync() const { return _sync; }\n\n        double current_time() const { return _simu_start_time + _current_time; }\n        double next_time() const { return _simu_start_time + _current_time + _dt; }\n        double real_time() const { return _real_start_time + _real_time; }\n        double dt() const { return _dt; }\n        // 0.8x => we are simulating at 80% of real time\n        double real_time_factor() const { return _dt / it_duration(); }\n        // time for a single iteration (wall-clock)\n        double it_duration() const { return _average_it_duration * 1e-6; }\n        // time of the last iteration (wall-clock)\n        double last_it_duration() const { return _it_duration * 1e-6; }\n\n    protected:\n        double _current_time = 0., _simu_start_time = 0., _real_time = 0., _real_start_time = 0., _it_duration = 0.;\n        double _average_it_duration = 0.;\n        double _dt;\n        int _current_step = 0;\n        bool _sync;\n        int _max_frequency = -1;\n        clock_t::time_point _start_time;\n        clock_t::time_point _last_iteration_time;\n    };\n} // namespace robot_dart\n\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

  • #include <exception>
  • #include <iostream>
  • #include <robot_dart/utils_headers_external.hpp>
"},{"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 (\n    condition,\n    message,\n    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
"},{"location":"api/utils_8hpp/#define-robot_dart_exception_assert","title":"define ROBOT_DART_EXCEPTION_ASSERT","text":"
#define ROBOT_DART_EXCEPTION_ASSERT (\n    condition,\n    message\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 (\n    condition\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 (\n    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
"},{"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 (\n    var\n) (void)(var)\n
"},{"location":"api/utils_8hpp/#define-robot_dart_warning","title":"define ROBOT_DART_WARNING","text":"
#define ROBOT_DART_WARNING (\n    condition,\n    message\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\n#include <exception>\n#include <iostream>\n\n#include <robot_dart/utils_headers_external.hpp>\n\n#ifndef ROBOT_DART_SHOW_WARNINGS\n#define ROBOT_DART_SHOW_WARNINGS true\n#endif\n\n#ifndef M_PIf\n#define M_PIf static_cast<float>(M_PI)\n#endif\n\nnamespace robot_dart {\n\n    inline Eigen::VectorXd make_vector(std::initializer_list<double> args)\n    {\n        return Eigen::VectorXd::Map(args.begin(), args.size());\n    }\n\n    inline Eigen::Isometry3d make_tf(const Eigen::Matrix3d& R, const Eigen::Vector3d& t)\n    {\n        Eigen::Isometry3d tf = Eigen::Isometry3d::Identity();\n        tf.linear().matrix() = R;\n        tf.translation() = t;\n\n        return tf;\n    }\n\n    inline Eigen::Isometry3d make_tf(const Eigen::Matrix3d& R)\n    {\n        Eigen::Isometry3d tf = Eigen::Isometry3d::Identity();\n        tf.linear().matrix() = R;\n\n        return tf;\n    }\n\n    inline Eigen::Isometry3d make_tf(const Eigen::Vector3d& t)\n    {\n        Eigen::Isometry3d tf = Eigen::Isometry3d::Identity();\n        tf.translation() = t;\n\n        return tf;\n    }\n\n    inline Eigen::Isometry3d make_tf(std::initializer_list<double> args)\n    {\n        Eigen::Isometry3d tf = Eigen::Isometry3d::Identity();\n        tf.translation() = make_vector(args);\n\n        return tf;\n    }\n\n    class Assertion : public std::exception {\n    public:\n        Assertion(const std::string& msg = \"\") : _msg(_make_message(msg)) {}\n\n        const char* what() const throw()\n        {\n            return _msg.c_str();\n        }\n\n    private:\n        std::string _msg;\n\n        std::string _make_message(const std::string& msg) const\n        {\n            std::string message = \"robot_dart assertion failed\";\n            if (msg != \"\")\n                message += \": '\" + msg + \"'\";\n            return message;\n        }\n    };\n} // namespace robot_dart\n\n#define ROBOT_DART_UNUSED_VARIABLE(var) (void)(var)\n\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\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\n#define ROBOT_DART_EXCEPTION_ASSERT(condition, message) \\\n    do {                                                \\\n        if (!(condition)) {                             \\\n            throw robot_dart::Assertion(message);       \\\n        }                                               \\\n    } while (false)\n\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\n#define ROBOT_DART_EXCEPTION_INTERNAL_ASSERT(condition) \\\n    do {                                                \\\n        if (!(condition)) {                             \\\n            throw robot_dart::Assertion(#condition);    \\\n        }                                               \\\n    } while (false)\n\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

  • #include <dart/config.hpp>
  • #include <dart/collision/CollisionFilter.hpp>
  • #include <dart/collision/CollisionObject.hpp>
  • #include <dart/collision/dart/DARTCollisionDetector.hpp>
  • #include <dart/collision/fcl/FCLCollisionDetector.hpp>
  • #include <dart/constraint/ConstraintSolver.hpp>

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\n#pragma GCC system_header\n\n#include <dart/config.hpp>\n\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\n#if (HAVE_BULLET == 1)\n#include <dart/collision/bullet/BulletCollisionDetector.hpp>\n#endif\n\n#if (HAVE_ODE == 1)\n#include <dart/collision/ode/OdeCollisionDetector.hpp>\n#endif\n\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

  • #include <dart/dynamics/BallJoint.hpp>
  • #include <dart/dynamics/BodyNode.hpp>
  • #include <dart/dynamics/BoxShape.hpp>
  • #include <dart/dynamics/DegreeOfFreedom.hpp>
  • #include <dart/dynamics/EllipsoidShape.hpp>
  • #include <dart/dynamics/EulerJoint.hpp>
  • #include <dart/dynamics/FreeJoint.hpp>
  • #include <dart/dynamics/MeshShape.hpp>
  • #include <dart/dynamics/RevoluteJoint.hpp>
  • #include <dart/dynamics/ShapeNode.hpp>
  • #include <dart/dynamics/SoftBodyNode.hpp>
  • #include <dart/dynamics/SoftMeshShape.hpp>
  • #include <dart/dynamics/WeldJoint.hpp>

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\n#pragma GCC system_header\n\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\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

  • #include <dart/config.hpp>
  • #include <dart/utils/SkelParser.hpp>
  • #include <dart/utils/sdf/SdfParser.hpp>
  • #include <dart/utils/urdf/urdf.hpp>
"},{"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\n#pragma GCC system_header\n\n#include <dart/config.hpp>\n\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\n// namespace alias for compatibility\nnamespace dart {\n    namespace io = utils;\n}\n#endif\n\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

  • #include <Eigen/Core>
  • #include <Eigen/Geometry>
  • #include <dart/config.hpp>
  • #include <dart/dynamics/MeshShape.hpp>
  • #include <dart/dynamics/Skeleton.hpp>
  • #include <dart/simulation/World.hpp>

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\n#pragma GCC system_header\n\n#include <Eigen/Core>\n#include <Eigen/Geometry>\n\n#include <dart/config.hpp>\n#include <dart/dynamics/MeshShape.hpp>\n#include <dart/dynamics/Skeleton.hpp>\n#include <dart/simulation/World.hpp>\n\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

  • #include <robot_dart/utils_headers_external.hpp>
  • #include <Magnum/DartIntegration/World.h>

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\n#pragma GCC system_header\n\n#include <robot_dart/utils_headers_external.hpp>\n\n#include <Magnum/DartIntegration/World.h>\n\n#endif\n
"},{"location":"api/namespaces/","title":"Namespace List","text":"

Here is a list of all namespaces with brief descriptions:

  • namespace Magnum
    • namespace GL
    • namespace Platform
    • namespace SceneGraph
    • namespace Shaders
      • namespace Implementation
  • namespace TinyProcessLib
  • namespace dart
    • namespace collision
    • namespace dynamics
  • namespace robot_dart
    • namespace collision_filter
    • namespace control
    • namespace detail
    • namespace gui
      • namespace magnum
        • namespace gs
        • namespace sensor
    • namespace robots
    • namespace sensor
    • namespace simu
  • namespace gs
  • namespace std
"},{"location":"api/classes/","title":"Class Index","text":""},{"location":"api/classes/#a","title":"a","text":"
  • A1 (robot_dart::robots)
  • Arm (robot_dart::robots)
  • Assertion (robot_dart)
"},{"location":"api/classes/#b","title":"b","text":"
  • Base (robot_dart::gui)
  • BaseApplication (robot_dart::gui::magnum)
  • BaseGraphics (robot_dart::gui::magnum)
  • BitmaskContactFilter (robot_dart::collision_filter)
"},{"location":"api/classes/#c","title":"c","text":"
  • Camera (robot_dart::gui::magnum::gs)
  • Camera (robot_dart::gui::magnum::sensor)
  • CubeMap (robot_dart::gui::magnum::gs)
  • CubeMapColor (robot_dart::gui::magnum::gs)
  • CubeMapShadowedColorObject (robot_dart::gui::magnum)
  • CubeMapShadowedObject (robot_dart::gui::magnum)
"},{"location":"api/classes/#d","title":"d","text":"
  • DebugDrawData (robot_dart::gui::magnum)
  • DepthImage (robot_dart::gui)
  • DrawableObject (robot_dart::gui::magnum)
"},{"location":"api/classes/#f","title":"f","text":"
  • ForceTorque (robot_dart::sensor)
  • Franka (robot_dart::robots)
"},{"location":"api/classes/#g","title":"g","text":"
  • GlfwApplication (robot_dart::gui::magnum)
  • GlobalData (robot_dart::gui::magnum)
  • Graphics (robot_dart::gui::magnum)
  • GraphicsConfiguration (robot_dart::gui::magnum)
  • GrayscaleImage (robot_dart::gui)
  • GUIData (robot_dart::simu)
"},{"location":"api/classes/#h","title":"h","text":"
  • Hexapod (robot_dart::robots)
"},{"location":"api/classes/#i","title":"i","text":"
  • ICub (robot_dart::robots)
  • Iiwa (robot_dart::robots)
  • Image (robot_dart::gui)
  • IMU (robot_dart::sensor)
  • IMUConfig (robot_dart::sensor)
"},{"location":"api/classes/#l","title":"l","text":"
  • Light (robot_dart::gui::magnum::gs)
"},{"location":"api/classes/#m","title":"m","text":"
  • Masks (robot_dart::collision_filter::BitmaskContactFilter)
  • Material (robot_dart::gui::magnum::gs)
"},{"location":"api/classes/#o","title":"o","text":"
  • ObjectStruct (robot_dart::gui::magnum)
"},{"location":"api/classes/#p","title":"p","text":"
  • PDControl (robot_dart::control)
  • Pendulum (robot_dart::robots)
  • PhongMultiLight (robot_dart::gui::magnum::gs)
  • PolicyControl (robot_dart::control)
"},{"location":"api/classes/#r","title":"r","text":"
  • Robot (robot_dart)
  • RobotControl (robot_dart::control)
  • RobotDARTSimu (robot_dart)
  • RobotData
  • RobotPool (robot_dart)
"},{"location":"api/classes/#s","title":"s","text":"
  • Scheduler (robot_dart)
  • Sensor (robot_dart::sensor)
  • ShadowData (robot_dart::gui::magnum)
  • ShadowedColorObject (robot_dart::gui::magnum)
  • ShadowedObject (robot_dart::gui::magnum)
  • ShadowMap (robot_dart::gui::magnum::gs)
  • ShadowMapColor (robot_dart::gui::magnum::gs)
  • SimpleControl (robot_dart::control)
"},{"location":"api/classes/#t","title":"t","text":"
  • Talos (robot_dart::robots)
  • TalosFastCollision (robot_dart::robots)
  • TalosLight (robot_dart::robots)
  • TextData (robot_dart::simu)
  • Tiago (robot_dart::robots)
  • Torque (robot_dart::sensor)
"},{"location":"api/classes/#u","title":"u","text":"
  • Ur3e (robot_dart::robots)
  • Ur3eHand (robot_dart::robots)
"},{"location":"api/classes/#v","title":"v","text":"
  • Vx300 (robot_dart::robots)
"},{"location":"api/classes/#w","title":"w","text":"
  • WindowlessGLApplication (robot_dart::gui::magnum)
  • WindowlessGraphics (robot_dart::gui::magnum)
"},{"location":"api/hierarchy/","title":"Class Hierarchy","text":"

This inheritance list is sorted roughly, but not completely, alphabetically:

  • class robot_dart::RobotDARTSimu
  • class robot_dart::RobotPool
  • class robot_dart::Scheduler
  • class robot_dart::control::RobotControl
    • class robot_dart::control::PDControl
    • class robot_dart::control::PolicyControl
    • class robot_dart::control::SimpleControl
  • class robot_dart::gui::Base
    • class robot_dart::gui::magnum::BaseGraphics
    • class robot_dart::gui::magnum::BaseGraphics
    • class robot_dart::gui::magnum::BaseGraphics
  • class robot_dart::gui::magnum::BaseApplication
    • class robot_dart::gui::magnum::GlfwApplication
    • class robot_dart::gui::magnum::WindowlessGLApplication
  • class robot_dart::gui::magnum::Light
  • class robot_dart::gui::magnum::Material
  • class robot_dart::sensor::Sensor
    • class robot_dart::gui::magnum::sensor::Camera
    • class robot_dart::sensor::ForceTorque
    • class robot_dart::sensor::IMU
    • class robot_dart::sensor::Torque
  • struct robot_dart::collision_filter::BitmaskContactFilter::Masks
  • struct robot_dart::gui::DepthImage
  • struct robot_dart::gui::GrayscaleImage
  • struct robot_dart::gui::Image
  • struct robot_dart::gui::magnum::DebugDrawData
  • struct robot_dart::gui::magnum::GlobalData
  • struct robot_dart::gui::magnum::GraphicsConfiguration
  • struct robot_dart::gui::magnum::ObjectStruct
  • struct robot_dart::gui::magnum::ShadowData
  • struct robot_dart::sensor::IMUConfig
  • struct robot_dart::simu::GUIData
  • struct robot_dart::simu::TextData
  • struct robot_dart::simu::GUIData::RobotData
  • class std::exception
    • class robot_dart::Assertion
  • class std::enable_shared_from_this< Robot >
    • class robot_dart::Robot
      • class robot_dart::robots::A1
      • class robot_dart::robots::Arm
      • class robot_dart::robots::Franka
      • class robot_dart::robots::Hexapod
      • class robot_dart::robots::ICub
      • class robot_dart::robots::Iiwa
      • class robot_dart::robots::Pendulum
      • class robot_dart::robots::Talos datasheet: https://pal-robotics.com/wp-content/uploads/2019/07/Datasheet_TALOS.pdf __
        • class robot_dart::robots::TalosFastCollision
        • class robot_dart::robots::TalosLight
      • class robot_dart::robots::Tiago datasheet: https://pal-robotics.com/wp-content/uploads/2021/07/Datasheet-complete_TIAGo-2021.pdf __
      • class robot_dart::robots::Ur3e
        • class robot_dart::robots::Ur3eHand
      • class robot_dart::robots::Vx300
    • class robot_dart::Robot
      • class robot_dart::robots::A1
      • class robot_dart::robots::Arm
      • class robot_dart::robots::Franka
      • class robot_dart::robots::Hexapod
      • class robot_dart::robots::ICub
      • class robot_dart::robots::Iiwa
      • class robot_dart::robots::Pendulum
      • class robot_dart::robots::Talos datasheet: https://pal-robotics.com/wp-content/uploads/2019/07/Datasheet_TALOS.pdf __
        • class robot_dart::robots::TalosFastCollision
        • class robot_dart::robots::TalosLight
      • class robot_dart::robots::Tiago datasheet: https://pal-robotics.com/wp-content/uploads/2021/07/Datasheet-complete_TIAGo-2021.pdf __
      • class robot_dart::robots::Ur3e
        • class robot_dart::robots::Ur3eHand
      • class robot_dart::robots::Vx300
    • class robot_dart::Robot
      • class robot_dart::robots::A1
      • class robot_dart::robots::Arm
      • class robot_dart::robots::Franka
      • class robot_dart::robots::Hexapod
      • class robot_dart::robots::ICub
      • class robot_dart::robots::Iiwa
      • class robot_dart::robots::Pendulum
      • class robot_dart::robots::Talos datasheet: https://pal-robotics.com/wp-content/uploads/2019/07/Datasheet_TALOS.pdf __
        • class robot_dart::robots::TalosFastCollision
        • class robot_dart::robots::TalosLight
      • class robot_dart::robots::Tiago datasheet: https://pal-robotics.com/wp-content/uploads/2021/07/Datasheet-complete_TIAGo-2021.pdf __
      • class robot_dart::robots::Ur3e
        • class robot_dart::robots::Ur3eHand
      • class robot_dart::robots::Vx300
    • class robot_dart::Robot
      • class robot_dart::robots::A1
      • class robot_dart::robots::Arm
      • class robot_dart::robots::Franka
      • class robot_dart::robots::Hexapod
      • class robot_dart::robots::ICub
      • class robot_dart::robots::Iiwa
      • class robot_dart::robots::Pendulum
      • class robot_dart::robots::Talos datasheet: https://pal-robotics.com/wp-content/uploads/2019/07/Datasheet_TALOS.pdf __
        • class robot_dart::robots::TalosFastCollision
        • class robot_dart::robots::TalosLight
      • class robot_dart::robots::Tiago datasheet: https://pal-robotics.com/wp-content/uploads/2021/07/Datasheet-complete_TIAGo-2021.pdf __
      • class robot_dart::robots::Ur3e
        • class robot_dart::robots::Ur3eHand
      • class robot_dart::robots::Vx300
    • class robot_dart::Robot
      • class robot_dart::robots::A1
      • class robot_dart::robots::Arm
      • class robot_dart::robots::Franka
      • class robot_dart::robots::Hexapod
      • class robot_dart::robots::ICub
      • class robot_dart::robots::Iiwa
      • class robot_dart::robots::Pendulum
      • class robot_dart::robots::Talos datasheet: https://pal-robotics.com/wp-content/uploads/2019/07/Datasheet_TALOS.pdf __
        • class robot_dart::robots::TalosFastCollision
        • class robot_dart::robots::TalosLight
      • class robot_dart::robots::Tiago datasheet: https://pal-robotics.com/wp-content/uploads/2021/07/Datasheet-complete_TIAGo-2021.pdf __
      • class robot_dart::robots::Ur3e
        • class robot_dart::robots::Ur3eHand
      • class robot_dart::robots::Vx300
    • class robot_dart::Robot
      • class robot_dart::robots::A1
      • class robot_dart::robots::Arm
      • class robot_dart::robots::Franka
      • class robot_dart::robots::Hexapod
      • class robot_dart::robots::ICub
      • class robot_dart::robots::Iiwa
      • class robot_dart::robots::Pendulum
      • class robot_dart::robots::Talos datasheet: https://pal-robotics.com/wp-content/uploads/2019/07/Datasheet_TALOS.pdf __
        • class robot_dart::robots::TalosFastCollision
        • class robot_dart::robots::TalosLight
      • class robot_dart::robots::Tiago datasheet: https://pal-robotics.com/wp-content/uploads/2021/07/Datasheet-complete_TIAGo-2021.pdf __
      • class robot_dart::robots::Ur3e
        • class robot_dart::robots::Ur3eHand
      • class robot_dart::robots::Vx300
    • class robot_dart::Robot
      • class robot_dart::robots::A1
      • class robot_dart::robots::Arm
      • class robot_dart::robots::Franka
      • class robot_dart::robots::Hexapod
      • class robot_dart::robots::ICub
      • class robot_dart::robots::Iiwa
      • class robot_dart::robots::Pendulum
      • class robot_dart::robots::Talos datasheet: https://pal-robotics.com/wp-content/uploads/2019/07/Datasheet_TALOS.pdf __
        • class robot_dart::robots::TalosFastCollision
        • class robot_dart::robots::TalosLight
      • class robot_dart::robots::Tiago datasheet: https://pal-robotics.com/wp-content/uploads/2021/07/Datasheet-complete_TIAGo-2021.pdf __
      • class robot_dart::robots::Ur3e
        • class robot_dart::robots::Ur3eHand
      • class robot_dart::robots::Vx300
    • class robot_dart::Robot
      • class robot_dart::robots::A1
      • class robot_dart::robots::Arm
      • class robot_dart::robots::Franka
      • class robot_dart::robots::Hexapod
      • class robot_dart::robots::ICub
      • class robot_dart::robots::Iiwa
      • class robot_dart::robots::Pendulum
      • class robot_dart::robots::Talos datasheet: https://pal-robotics.com/wp-content/uploads/2019/07/Datasheet_TALOS.pdf __
        • class robot_dart::robots::TalosFastCollision
        • class robot_dart::robots::TalosLight
      • class robot_dart::robots::Tiago datasheet: https://pal-robotics.com/wp-content/uploads/2021/07/Datasheet-complete_TIAGo-2021.pdf __
      • class robot_dart::robots::Ur3e
        • class robot_dart::robots::Ur3eHand
      • class robot_dart::robots::Vx300
    • class robot_dart::Robot
      • class robot_dart::robots::A1
      • class robot_dart::robots::Arm
      • class robot_dart::robots::Franka
      • class robot_dart::robots::Hexapod
      • class robot_dart::robots::ICub
      • class robot_dart::robots::Iiwa
      • class robot_dart::robots::Pendulum
      • class robot_dart::robots::Talos datasheet: https://pal-robotics.com/wp-content/uploads/2019/07/Datasheet_TALOS.pdf __
        • class robot_dart::robots::TalosFastCollision
        • class robot_dart::robots::TalosLight
      • class robot_dart::robots::Tiago datasheet: https://pal-robotics.com/wp-content/uploads/2021/07/Datasheet-complete_TIAGo-2021.pdf __
      • class robot_dart::robots::Ur3e
        • class robot_dart::robots::Ur3eHand
      • class robot_dart::robots::Vx300
    • class robot_dart::Robot
      • class robot_dart::robots::A1
      • class robot_dart::robots::Arm
      • class robot_dart::robots::Franka
      • class robot_dart::robots::Hexapod
      • class robot_dart::robots::ICub
      • class robot_dart::robots::Iiwa
      • class robot_dart::robots::Pendulum
      • class robot_dart::robots::Talos datasheet: https://pal-robotics.com/wp-content/uploads/2019/07/Datasheet_TALOS.pdf __
        • class robot_dart::robots::TalosFastCollision
        • class robot_dart::robots::TalosLight
      • class robot_dart::robots::Tiago datasheet: https://pal-robotics.com/wp-content/uploads/2021/07/Datasheet-complete_TIAGo-2021.pdf __
      • class robot_dart::robots::Ur3e
        • class robot_dart::robots::Ur3eHand
      • class robot_dart::robots::Vx300
    • class robot_dart::Robot
      • class robot_dart::robots::A1
      • class robot_dart::robots::Arm
      • class robot_dart::robots::Franka
      • class robot_dart::robots::Hexapod
      • class robot_dart::robots::ICub
      • class robot_dart::robots::Iiwa
      • class robot_dart::robots::Pendulum
      • class robot_dart::robots::Talos datasheet: https://pal-robotics.com/wp-content/uploads/2019/07/Datasheet_TALOS.pdf __
        • class robot_dart::robots::TalosFastCollision
        • class robot_dart::robots::TalosLight
      • class robot_dart::robots::Tiago datasheet: https://pal-robotics.com/wp-content/uploads/2021/07/Datasheet-complete_TIAGo-2021.pdf __
      • class robot_dart::robots::Ur3e
        • class robot_dart::robots::Ur3eHand
      • class robot_dart::robots::Vx300
    • class robot_dart::Robot
      • class robot_dart::robots::A1
      • class robot_dart::robots::Arm
      • class robot_dart::robots::Franka
      • class robot_dart::robots::Hexapod
      • class robot_dart::robots::ICub
      • class robot_dart::robots::Iiwa
      • class robot_dart::robots::Pendulum
      • class robot_dart::robots::Talos datasheet: https://pal-robotics.com/wp-content/uploads/2019/07/Datasheet_TALOS.pdf __
        • class robot_dart::robots::TalosFastCollision
        • class robot_dart::robots::TalosLight
      • class robot_dart::robots::Tiago datasheet: https://pal-robotics.com/wp-content/uploads/2021/07/Datasheet-complete_TIAGo-2021.pdf __
      • class robot_dart::robots::Ur3e
        • class robot_dart::robots::Ur3eHand
      • class robot_dart::robots::Vx300
    • class robot_dart::Robot
      • class robot_dart::robots::A1
      • class robot_dart::robots::Arm
      • class robot_dart::robots::Franka
      • class robot_dart::robots::Hexapod
      • class robot_dart::robots::ICub
      • class robot_dart::robots::Iiwa
      • class robot_dart::robots::Pendulum
      • class robot_dart::robots::Talos datasheet: https://pal-robotics.com/wp-content/uploads/2019/07/Datasheet_TALOS.pdf __
        • class robot_dart::robots::TalosFastCollision
        • class robot_dart::robots::TalosLight
      • class robot_dart::robots::Tiago datasheet: https://pal-robotics.com/wp-content/uploads/2021/07/Datasheet-complete_TIAGo-2021.pdf __
      • class robot_dart::robots::Ur3e
        • class robot_dart::robots::Ur3eHand
      • class robot_dart::robots::Vx300
    • class robot_dart::Robot
      • class robot_dart::robots::A1
      • class robot_dart::robots::Arm
      • class robot_dart::robots::Franka
      • class robot_dart::robots::Hexapod
      • class robot_dart::robots::ICub
      • class robot_dart::robots::Iiwa
      • class robot_dart::robots::Pendulum
      • class robot_dart::robots::Talos datasheet: https://pal-robotics.com/wp-content/uploads/2019/07/Datasheet_TALOS.pdf __
        • class robot_dart::robots::TalosFastCollision
        • class robot_dart::robots::TalosLight
      • class robot_dart::robots::Tiago datasheet: https://pal-robotics.com/wp-content/uploads/2021/07/Datasheet-complete_TIAGo-2021.pdf __
      • class robot_dart::robots::Ur3e
        • class robot_dart::robots::Ur3eHand
      • class robot_dart::robots::Vx300
    • class robot_dart::Robot
      • class robot_dart::robots::A1
      • class robot_dart::robots::Arm
      • class robot_dart::robots::Franka
      • class robot_dart::robots::Hexapod
      • class robot_dart::robots::ICub
      • class robot_dart::robots::Iiwa
      • class robot_dart::robots::Pendulum
      • class robot_dart::robots::Talos datasheet: https://pal-robotics.com/wp-content/uploads/2019/07/Datasheet_TALOS.pdf __
        • class robot_dart::robots::TalosFastCollision
        • class robot_dart::robots::TalosLight
      • class robot_dart::robots::Tiago datasheet: https://pal-robotics.com/wp-content/uploads/2021/07/Datasheet-complete_TIAGo-2021.pdf __
      • class robot_dart::robots::Ur3e
        • class robot_dart::robots::Ur3eHand
      • class robot_dart::robots::Vx300
  • class dart::BodyNodeCollisionFilter
    • class robot_dart::collision_filter::BitmaskContactFilter
  • class Object3D
    • class robot_dart::gui::magnum::CubeMapShadowedColorObject
    • class robot_dart::gui::magnum::CubeMapShadowedObject
    • class robot_dart::gui::magnum::DrawableObject
    • class robot_dart::gui::magnum::ShadowedColorObject
    • class robot_dart::gui::magnum::ShadowedObject
    • class robot_dart::gui::magnum::Camera
  • class Magnum::SceneGraph::Drawable3D
    • class robot_dart::gui::magnum::CubeMapShadowedColorObject
    • class robot_dart::gui::magnum::CubeMapShadowedObject
    • class robot_dart::gui::magnum::DrawableObject
    • class robot_dart::gui::magnum::ShadowedColorObject
    • class robot_dart::gui::magnum::ShadowedObject
  • class Magnum::Platform::Application
    • class robot_dart::gui::magnum::GlfwApplication
  • class Magnum::Platform::WindowlessApplication
    • class robot_dart::gui::magnum::WindowlessGLApplication
  • class Magnum::GL::AbstractShaderProgram
    • class robot_dart::gui::magnum::CubeMap
    • class robot_dart::gui::magnum::CubeMapColor
    • class robot_dart::gui::magnum::PhongMultiLight
    • class robot_dart::gui::magnum::ShadowMap
    • class robot_dart::gui::magnum::ShadowMapColor
"},{"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":"
  • Assertion (robot_dart::Assertion)
  • acceleration_lower_limits (robot_dart::Robot)
  • acceleration_upper_limits (robot_dart::Robot)
  • accelerations (robot_dart::Robot)
  • active_controllers (robot_dart::Robot)
  • actuator_type (robot_dart::Robot)
  • actuator_types (robot_dart::Robot)
  • add_body_mass (robot_dart::Robot)
  • add_controller (robot_dart::Robot)
  • add_external_force (robot_dart::Robot)
  • add_external_torque (robot_dart::Robot)
  • adjacent_colliding (robot_dart::Robot)
  • aug_mass_matrix (robot_dart::Robot)
  • add_checkerboard_floor (robot_dart::RobotDARTSimu)
  • add_floor (robot_dart::RobotDARTSimu)
  • add_robot (robot_dart::RobotDARTSimu)
  • add_sensor (robot_dart::RobotDARTSimu)
  • add_text (robot_dart::RobotDARTSimu, robot_dart::simu::GUIData)
  • add_visual_robot (robot_dart::RobotDARTSimu)
  • add_to_map (robot_dart::collision_filter::BitmaskContactFilter)
  • activate (robot_dart::control::RobotControl, robot_dart::sensor::Sensor)
  • active (robot_dart::control::RobotControl, robot_dart::sensor::Sensor)
  • add_light (robot_dart::gui::magnum::BaseApplication, robot_dart::gui::magnum::BaseGraphics)
  • attach_camera (robot_dart::gui::magnum::BaseApplication)
  • axes_mesh (robot_dart::gui::magnum::DebugDrawData)
  • axes_shader (robot_dart::gui::magnum::DebugDrawData)
  • attenuation (robot_dart::gui::magnum::Light)
  • ambient_color (robot_dart::gui::magnum::Material)
  • ambient_texture (robot_dart::gui::magnum::Material)
  • attach_to_body (robot_dart::gui::magnum::sensor::Camera, robot_dart::sensor::ForceTorque, robot_dart::sensor::Sensor, robot_dart::sensor::Torque)
  • attach_to_joint (robot_dart::gui::magnum::sensor::Camera, robot_dart::sensor::IMU, robot_dart::sensor::Sensor)
  • A1 (robot_dart::robots::A1)
  • Arm (robot_dart::robots::Arm)
  • angular_position (robot_dart::sensor::IMU)
  • angular_position_vec (robot_dart::sensor::IMU)
  • angular_velocity (robot_dart::sensor::IMU)
  • accel_bias (robot_dart::sensor::IMUConfig)
  • attached_to (robot_dart::sensor::Sensor)
  • alignment (robot_dart::simu::TextData)
"},{"location":"api/class_members/#b","title":"b","text":"
  • base_pose (robot_dart::Robot)
  • base_pose_vec (robot_dart::Robot)
  • body_acceleration (robot_dart::Robot)
  • body_index (robot_dart::Robot)
  • body_mass (robot_dart::Robot)
  • body_name (robot_dart::Robot)
  • body_names (robot_dart::Robot)
  • body_node (robot_dart::Robot)
  • body_pose (robot_dart::Robot)
  • body_pose_vec (robot_dart::Robot)
  • body_velocity (robot_dart::Robot)
  • Base (robot_dart::gui::Base)
  • BaseApplication (robot_dart::gui::magnum::BaseApplication)
  • BaseGraphics (robot_dart::gui::magnum::BaseGraphics)
  • background_mesh (robot_dart::gui::magnum::DebugDrawData)
  • background_shader (robot_dart::gui::magnum::DebugDrawData)
  • bg_color (robot_dart::gui::magnum::GraphicsConfiguration)
  • bind_cube_map_texture (robot_dart::gui::magnum::CubeMapColor, robot_dart::gui::magnum::PhongMultiLight)
  • bind_cube_map_color_texture (robot_dart::gui::magnum::PhongMultiLight)
  • bind_shadow_color_texture (robot_dart::gui::magnum::PhongMultiLight)
  • bind_shadow_texture (robot_dart::gui::magnum::PhongMultiLight)
  • body (robot_dart::sensor::IMUConfig)
  • background_color (robot_dart::simu::TextData)
"},{"location":"api/class_members/#c","title":"c","text":"
  • cast_shadows (robot_dart::Robot, robot_dart::simu::GUIData)
  • clear_controllers (robot_dart::Robot)
  • clear_external_forces (robot_dart::Robot)
  • clear_internal_forces (robot_dart::Robot)
  • clone (robot_dart::Robot, robot_dart::control::PDControl, robot_dart::control::PolicyControl, robot_dart::control::RobotControl, robot_dart::control::SimpleControl)
  • clone_ghost (robot_dart::Robot)
  • com (robot_dart::Robot)
  • com_acceleration (robot_dart::Robot)
  • com_jacobian (robot_dart::Robot)
  • com_jacobian_deriv (robot_dart::Robot)
  • com_velocity (robot_dart::Robot)
  • commands (robot_dart::Robot)
  • constraint_forces (robot_dart::Robot)
  • controller (robot_dart::Robot)
  • controllers (robot_dart::Robot)
  • coriolis_forces (robot_dart::Robot)
  • coriolis_gravity_forces (robot_dart::Robot)
  • coulomb_coeffs (robot_dart::Robot)
  • create_box (robot_dart::Robot)
  • create_ellipsoid (robot_dart::Robot)
  • clear_robots (robot_dart::RobotDARTSimu)
  • clear_sensors (robot_dart::RobotDARTSimu)
  • collision_category (robot_dart::RobotDARTSimu)
  • collision_detector (robot_dart::RobotDARTSimu)
  • collision_mask (robot_dart::RobotDARTSimu, robot_dart::collision_filter::BitmaskContactFilter::Masks)
  • collision_masks (robot_dart::RobotDARTSimu)
  • control_freq (robot_dart::RobotDARTSimu)
  • clock_t (robot_dart::Scheduler)
  • current_time (robot_dart::Scheduler)
  • clear_all (robot_dart::collision_filter::BitmaskContactFilter)
  • category_mask (robot_dart::collision_filter::BitmaskContactFilter::Masks)
  • calculate (robot_dart::control::PDControl, robot_dart::control::PolicyControl, robot_dart::control::RobotControl, robot_dart::control::SimpleControl, robot_dart::gui::magnum::sensor::Camera, robot_dart::sensor::ForceTorque, robot_dart::sensor::IMU, robot_dart::sensor::Sensor, robot_dart::sensor::Torque)
  • configure (robot_dart::control::PDControl, robot_dart::control::PolicyControl, robot_dart::control::RobotControl, robot_dart::control::SimpleControl)
  • controllable_dofs (robot_dart::control::RobotControl)
  • channels (robot_dart::gui::Image)
  • camera (robot_dart::gui::magnum::BaseApplication, robot_dart::gui::magnum::BaseGraphics, robot_dart::gui::magnum::Camera, robot_dart::gui::magnum::sensor::Camera)
  • clear_lights (robot_dart::gui::magnum::BaseApplication, robot_dart::gui::magnum::BaseGraphics)
  • camera_extrinsic_matrix (robot_dart::gui::magnum::BaseGraphics, robot_dart::gui::magnum::sensor::Camera)
  • camera_intrinsic_matrix (robot_dart::gui::magnum::BaseGraphics, robot_dart::gui::magnum::sensor::Camera)
  • CubeMapShadowedColorObject (robot_dart::gui::magnum::CubeMapShadowedColorObject)
  • CubeMapShadowedObject (robot_dart::gui::magnum::CubeMapShadowedObject)
  • cache (robot_dart::gui::magnum::DebugDrawData)
  • cubemapped (robot_dart::gui::magnum::ObjectStruct)
  • cubemapped_color (robot_dart::gui::magnum::ObjectStruct)
  • Camera (robot_dart::gui::magnum::Camera, robot_dart::gui::magnum::sensor::Camera)
  • camera_object (robot_dart::gui::magnum::Camera)
  • CubeMap (robot_dart::gui::magnum::CubeMap)
  • CubeMapColor (robot_dart::gui::magnum::CubeMapColor)
  • casts_shadows (robot_dart::gui::magnum::Light)
  • collision_vec (robot_dart::robots::TalosFastCollision)
  • caster_joints (robot_dart::robots::Tiago)
  • color (robot_dart::simu::TextData)
  • casting_shadows (robot_dart::simu::GUIData::RobotData)
"},{"location":"api/class_members/#d","title":"d","text":"
  • damping_coeffs (robot_dart::Robot)
  • dof (robot_dart::Robot)
  • dof_index (robot_dart::Robot)
  • dof_map (robot_dart::Robot)
  • dof_name (robot_dart::Robot)
  • dof_names (robot_dart::Robot)
  • drawing_axes (robot_dart::Robot, robot_dart::simu::GUIData)
  • dt (robot_dart::Scheduler)
  • DartCollisionConstPtr (robot_dart::collision_filter::BitmaskContactFilter)
  • DartShapeConstPtr (robot_dart::collision_filter::BitmaskContactFilter)
  • depth_array (robot_dart::gui::Base, robot_dart::gui::magnum::BaseApplication, robot_dart::gui::magnum::BaseGraphics, robot_dart::gui::magnum::sensor::Camera)
  • depth_image (robot_dart::gui::Base, robot_dart::gui::magnum::BaseApplication, robot_dart::gui::magnum::BaseGraphics, robot_dart::gui::magnum::Camera, robot_dart::gui::magnum::sensor::Camera)
  • done (robot_dart::gui::Base, robot_dart::gui::magnum::BaseApplication, robot_dart::gui::magnum::BaseGraphics)
  • data (robot_dart::gui::DepthImage, robot_dart::gui::GrayscaleImage, robot_dart::gui::Image)
  • debug_draw_data (robot_dart::gui::magnum::BaseApplication)
  • drawables (robot_dart::gui::magnum::BaseApplication)
  • draw (robot_dart::gui::magnum::CubeMapShadowedColorObject, robot_dart::gui::magnum::CubeMapShadowedObject, robot_dart::gui::magnum::DrawableObject, robot_dart::gui::magnum::ShadowedColorObject, robot_dart::gui::magnum::ShadowedObject, robot_dart::gui::magnum::Camera)
  • DrawableObject (robot_dart::gui::magnum::DrawableObject)
  • drawEvent (robot_dart::gui::magnum::GlfwApplication)
  • default_configuration (robot_dart::gui::magnum::Graphics, robot_dart::gui::magnum::WindowlessGraphics)
  • draw_debug (robot_dart::gui::magnum::GraphicsConfiguration, robot_dart::gui::magnum::sensor::Camera)
  • draw_main_camera (robot_dart::gui::magnum::GraphicsConfiguration)
  • draw_text (robot_dart::gui::magnum::GraphicsConfiguration)
  • drawable (robot_dart::gui::magnum::ObjectStruct)
  • diffuse_color (robot_dart::gui::magnum::Material)
  • diffuse_texture (robot_dart::gui::magnum::Material)
  • drawing_debug (robot_dart::gui::magnum::sensor::Camera)
  • detach (robot_dart::sensor::Sensor)
  • drawing_texts (robot_dart::simu::GUIData)
  • draw_background (robot_dart::simu::TextData)
"},{"location":"api/class_members/#e","title":"e","text":"
  • external_forces (robot_dart::Robot)
  • enable_status_bar (robot_dart::RobotDARTSimu)
  • enable_text_panel (robot_dart::RobotDARTSimu)
  • enable_shadows (robot_dart::gui::magnum::BaseApplication, robot_dart::gui::magnum::BaseGraphics)
  • exitEvent (robot_dart::gui::magnum::GlfwApplication)
  • exec (robot_dart::gui::magnum::WindowlessGLApplication)
  • extrinsic_matrix (robot_dart::gui::magnum::Camera)
"},{"location":"api/class_members/#f","title":"f","text":"
  • fix_to_world (robot_dart::Robot)
  • fixed (robot_dart::Robot)
  • force_lower_limits (robot_dart::Robot)
  • force_position_bounds (robot_dart::Robot)
  • force_torque (robot_dart::Robot)
  • force_upper_limits (robot_dart::Robot)
  • forces (robot_dart::Robot)
  • free (robot_dart::Robot)
  • free_from_world (robot_dart::Robot)
  • friction_coeff (robot_dart::Robot)
  • friction_dir (robot_dart::Robot)
  • free_robot (robot_dart::RobotPool)
  • font (robot_dart::gui::magnum::DebugDrawData)
  • free_gl_context (robot_dart::gui::magnum::GlobalData)
  • far_plane (robot_dart::gui::magnum::Camera)
  • forward (robot_dart::gui::magnum::Camera)
  • fov (robot_dart::gui::magnum::Camera)
  • Flag (robot_dart::gui::magnum::CubeMap, robot_dart::gui::magnum::CubeMapColor, robot_dart::gui::magnum::PhongMultiLight, robot_dart::gui::magnum::ShadowMap, robot_dart::gui::magnum::ShadowMapColor)
  • Flags (robot_dart::gui::magnum::CubeMap, robot_dart::gui::magnum::CubeMapColor, robot_dart::gui::magnum::PhongMultiLight, robot_dart::gui::magnum::ShadowMap, robot_dart::gui::magnum::ShadowMapColor)
  • flags (robot_dart::gui::magnum::CubeMap, robot_dart::gui::magnum::CubeMapColor, robot_dart::gui::magnum::PhongMultiLight, robot_dart::gui::magnum::ShadowMap, robot_dart::gui::magnum::ShadowMapColor)
  • Franka (robot_dart::robots::Franka)
  • ft_wrist (robot_dart::robots::Franka, robot_dart::robots::Iiwa, robot_dart::robots::Tiago, robot_dart::robots::Ur3e)
  • ft_foot_left (robot_dart::robots::ICub, robot_dart::robots::Talos)
  • ft_foot_right (robot_dart::robots::ICub, robot_dart::robots::Talos)
  • ft_wrist_left (robot_dart::robots::Talos)
  • ft_wrist_right (robot_dart::robots::Talos)
  • ForceTorque (robot_dart::sensor::ForceTorque)
  • force (robot_dart::sensor::ForceTorque)
  • frequency (robot_dart::sensor::IMUConfig, robot_dart::sensor::Sensor)
  • font_size (robot_dart::simu::TextData)
"},{"location":"api/class_members/#g","title":"g","text":"
  • ghost (robot_dart::Robot, robot_dart::simu::GUIData)
  • gravity_forces (robot_dart::Robot)
  • graphics (robot_dart::RobotDARTSimu)
  • graphics_freq (robot_dart::RobotDARTSimu)
  • gravity (robot_dart::RobotDARTSimu)
  • gui_data (robot_dart::RobotDARTSimu)
  • get_robot (robot_dart::RobotPool)
  • GlfwApplication (robot_dart::gui::magnum::GlfwApplication)
  • GlobalData (robot_dart::gui::magnum::GlobalData)
  • gl_context (robot_dart::gui::magnum::GlobalData)
  • Graphics (robot_dart::gui::magnum::Graphics)
  • gyro_bias (robot_dart::sensor::IMUConfig)
"},{"location":"api/class_members/#h","title":"h","text":"
  • halted_sim (robot_dart::RobotDARTSimu)
  • h_params (robot_dart::control::PolicyControl)
  • height (robot_dart::gui::Base, robot_dart::gui::DepthImage, robot_dart::gui::GrayscaleImage, robot_dart::gui::Image, robot_dart::gui::magnum::BaseGraphics, robot_dart::gui::magnum::GraphicsConfiguration, robot_dart::gui::magnum::Camera)
  • has_ambient_texture (robot_dart::gui::magnum::Material)
  • has_diffuse_texture (robot_dart::gui::magnum::Material)
  • has_specular_texture (robot_dart::gui::magnum::Material)
  • Hexapod (robot_dart::robots::Hexapod)
"},{"location":"api/class_members/#i","title":"i","text":"
  • inv_aug_mass_matrix (robot_dart::Robot)
  • inv_mass_matrix (robot_dart::Robot)
  • it_duration (robot_dart::Scheduler)
  • ignoresCollision (robot_dart::collision_filter::BitmaskContactFilter)
  • init (robot_dart::control::RobotControl, robot_dart::gui::magnum::BaseApplication, robot_dart::gui::magnum::sensor::Camera, robot_dart::sensor::ForceTorque, robot_dart::sensor::IMU, robot_dart::sensor::Sensor, robot_dart::sensor::Torque)
  • image (robot_dart::gui::Base, robot_dart::gui::magnum::BaseApplication, robot_dart::gui::magnum::BaseGraphics, robot_dart::gui::magnum::Camera, robot_dart::gui::magnum::sensor::Camera)
  • instance (robot_dart::gui::magnum::GlobalData)
  • intrinsic_matrix (robot_dart::gui::magnum::Camera)
  • imu (robot_dart::robots::A1, robot_dart::robots::ICub, robot_dart::robots::Talos)
  • ICub (robot_dart::robots::ICub)
  • Iiwa (robot_dart::robots::Iiwa)
  • IMU (robot_dart::sensor::IMU)
  • IMUConfig (robot_dart::sensor::IMUConfig)
  • is_ghost (robot_dart::simu::GUIData::RobotData)
"},{"location":"api/class_members/#j","title":"j","text":"
  • jacobian (robot_dart::Robot)
  • jacobian_deriv (robot_dart::Robot)
  • joint (robot_dart::Robot)
  • joint_index (robot_dart::Robot)
  • joint_map (robot_dart::Robot)
  • joint_name (robot_dart::Robot)
  • joint_names (robot_dart::Robot)
"},{"location":"api/class_members/#k","title":"k","text":"
  • keyPressEvent (robot_dart::gui::magnum::GlfwApplication)
  • keyReleaseEvent (robot_dart::gui::magnum::GlfwApplication)
"},{"location":"api/class_members/#l","title":"l","text":"
  • locked_dof_names (robot_dart::Robot)
  • last_it_duration (robot_dart::Scheduler)
  • light (robot_dart::gui::magnum::BaseApplication, robot_dart::gui::magnum::BaseGraphics)
  • lights (robot_dart::gui::magnum::BaseApplication, robot_dart::gui::magnum::BaseGraphics)
  • look_at (robot_dart::gui::magnum::BaseApplication, robot_dart::gui::magnum::BaseGraphics, robot_dart::gui::magnum::Camera, robot_dart::gui::magnum::sensor::Camera)
  • Light (robot_dart::gui::magnum::Light)
  • linear_acceleration (robot_dart::sensor::IMU)
"},{"location":"api/class_members/#m","title":"m","text":"
  • mass_matrix (robot_dart::Robot)
  • mimic_dof_names (robot_dart::Robot)
  • model_filename (robot_dart::Robot, robot_dart::RobotPool)
  • model_packages (robot_dart::Robot)
  • mask (robot_dart::collision_filter::BitmaskContactFilter)
  • magnum_app (robot_dart::gui::magnum::BaseGraphics)
  • magnum_image (robot_dart::gui::magnum::BaseGraphics, robot_dart::gui::magnum::sensor::Camera)
  • materials (robot_dart::gui::magnum::DrawableObject)
  • mouseMoveEvent (robot_dart::gui::magnum::GlfwApplication)
  • mouseScrollEvent (robot_dart::gui::magnum::GlfwApplication)
  • max_lights (robot_dart::gui::magnum::GraphicsConfiguration, robot_dart::gui::magnum::PhongMultiLight)
  • move (robot_dart::gui::magnum::Camera)
  • material (robot_dart::gui::magnum::Light)
  • Material (robot_dart::gui::magnum::Material)
  • magnum_depth_image (robot_dart::gui::magnum::sensor::Camera)
"},{"location":"api/class_members/#n","title":"n","text":"
  • name (robot_dart::Robot)
  • num_bodies (robot_dart::Robot)
  • num_controllers (robot_dart::Robot)
  • num_dofs (robot_dart::Robot)
  • num_joints (robot_dart::Robot)
  • num_robots (robot_dart::RobotDARTSimu)
  • next_time (robot_dart::Scheduler)
  • num_lights (robot_dart::gui::magnum::BaseApplication, robot_dart::gui::magnum::BaseGraphics)
  • near_plane (robot_dart::gui::magnum::Camera)
  • Normal (robot_dart::gui::magnum::PhongMultiLight)
"},{"location":"api/class_members/#o","title":"o","text":"
  • operator= (robot_dart::RobotPool, robot_dart::gui::magnum::GlobalData)
  • operator() (robot_dart::Scheduler)
"},{"location":"api/class_members/#p","title":"p","text":"
  • passive_dof_names (robot_dart::Robot)
  • position_enforced (robot_dart::Robot)
  • position_lower_limits (robot_dart::Robot)
  • position_upper_limits (robot_dart::Robot)
  • positions (robot_dart::Robot)
  • physics_freq (robot_dart::RobotDARTSimu)
  • PDControl (robot_dart::control::PDControl)
  • pd (robot_dart::control::PDControl)
  • PolicyControl (robot_dart::control::PolicyControl)
  • parameters (robot_dart::control::RobotControl)
  • Position (robot_dart::gui::magnum::CubeMap, robot_dart::gui::magnum::CubeMapColor, robot_dart::gui::magnum::PhongMultiLight, robot_dart::gui::magnum::ShadowMap, robot_dart::gui::magnum::ShadowMapColor)
  • position (robot_dart::gui::magnum::Light)
  • PhongMultiLight (robot_dart::gui::magnum::PhongMultiLight)
  • Pendulum (robot_dart::robots::Pendulum)
  • pose (robot_dart::sensor::Sensor)
"},{"location":"api/class_members/#r","title":"r","text":"
  • Robot (robot_dart::Robot)
  • reinit_controllers (robot_dart::Robot)
  • remove_all_drawing_axis (robot_dart::Robot)
  • remove_controller (robot_dart::Robot)
  • reset (robot_dart::Robot, robot_dart::Scheduler, robot_dart::robots::A1, robot_dart::robots::Hexapod, robot_dart::robots::ICub, robot_dart::robots::Talos, robot_dart::robots::Tiago)
  • reset_commands (robot_dart::Robot)
  • restitution_coeff (robot_dart::Robot)
  • RobotDARTSimu (robot_dart::RobotDARTSimu)
  • remove_all_collision_masks (robot_dart::RobotDARTSimu)
  • remove_collision_masks (robot_dart::RobotDARTSimu)
  • remove_robot (robot_dart::RobotDARTSimu, robot_dart::simu::GUIData)
  • remove_sensor (robot_dart::RobotDARTSimu)
  • remove_sensors (robot_dart::RobotDARTSimu)
  • robot (robot_dart::RobotDARTSimu, robot_dart::control::RobotControl)
  • robot_index (robot_dart::RobotDARTSimu)
  • robot_t (robot_dart::RobotDARTSimu)
  • robots (robot_dart::RobotDARTSimu)
  • run (robot_dart::RobotDARTSimu)
  • RobotPool (robot_dart::RobotPool)
  • robot_creator_t (robot_dart::RobotPool)
  • real_time (robot_dart::Scheduler)
  • real_time_factor (robot_dart::Scheduler)
  • remove_from_map (robot_dart::collision_filter::BitmaskContactFilter)
  • RobotControl (robot_dart::control::RobotControl)
  • raw_depth_image (robot_dart::gui::Base, robot_dart::gui::magnum::BaseApplication, robot_dart::gui::magnum::BaseGraphics, robot_dart::gui::magnum::sensor::Camera)
  • refresh (robot_dart::gui::Base, robot_dart::gui::magnum::BaseGraphics, robot_dart::sensor::Sensor)
  • record_video (robot_dart::gui::magnum::BaseApplication, robot_dart::gui::magnum::BaseGraphics, robot_dart::gui::magnum::Camera, robot_dart::gui::magnum::sensor::Camera)
  • render (robot_dart::gui::magnum::BaseApplication, robot_dart::gui::magnum::GlfwApplication, robot_dart::gui::magnum::WindowlessGLApplication)
  • render_shadows (robot_dart::gui::magnum::BaseApplication)
  • record (robot_dart::gui::magnum::Camera)
  • recording (robot_dart::gui::magnum::Camera)
  • recording_depth (robot_dart::gui::magnum::Camera)
  • root_object (robot_dart::gui::magnum::Camera)
  • remove_text (robot_dart::simu::GUIData)
  • robot_axes (robot_dart::simu::GUIData)
  • robot_data (robot_dart::simu::GUIData)
"},{"location":"api/class_members/#s","title":"s","text":"
  • secondary_friction_coeff (robot_dart::Robot)
  • self_colliding (robot_dart::Robot)
  • set_acceleration_lower_limits (robot_dart::Robot)
  • set_acceleration_upper_limits (robot_dart::Robot)
  • set_accelerations (robot_dart::Robot)
  • set_actuator_type (robot_dart::Robot, robot_dart::robots::Tiago)
  • set_actuator_types (robot_dart::Robot, robot_dart::robots::Tiago)
  • set_base_pose (robot_dart::Robot)
  • set_body_mass (robot_dart::Robot)
  • set_body_name (robot_dart::Robot)
  • set_cast_shadows (robot_dart::Robot)
  • set_color_mode (robot_dart::Robot)
  • set_commands (robot_dart::Robot)
  • set_coulomb_coeffs (robot_dart::Robot)
  • set_damping_coeffs (robot_dart::Robot)
  • set_draw_axis (robot_dart::Robot)
  • set_external_force (robot_dart::Robot)
  • set_external_torque (robot_dart::Robot)
  • set_force_lower_limits (robot_dart::Robot)
  • set_force_upper_limits (robot_dart::Robot)
  • set_forces (robot_dart::Robot)
  • set_friction_coeff (robot_dart::Robot)
  • set_friction_coeffs (robot_dart::Robot)
  • set_friction_dir (robot_dart::Robot)
  • set_ghost (robot_dart::Robot)
  • set_joint_name (robot_dart::Robot)
  • set_mimic (robot_dart::Robot)
  • set_position_enforced (robot_dart::Robot)
  • set_position_lower_limits (robot_dart::Robot)
  • set_position_upper_limits (robot_dart::Robot)
  • set_positions (robot_dart::Robot)
  • set_restitution_coeff (robot_dart::Robot)
  • set_restitution_coeffs (robot_dart::Robot)
  • set_secondary_friction_coeff (robot_dart::Robot)
  • set_secondary_friction_coeffs (robot_dart::Robot)
  • set_self_collision (robot_dart::Robot)
  • set_spring_stiffnesses (robot_dart::Robot)
  • set_velocities (robot_dart::Robot)
  • set_velocity_lower_limits (robot_dart::Robot)
  • set_velocity_upper_limits (robot_dart::Robot)
  • skeleton (robot_dart::Robot)
  • spring_stiffnesses (robot_dart::Robot)
  • schedule (robot_dart::RobotDARTSimu, robot_dart::Scheduler)
  • scheduler (robot_dart::RobotDARTSimu)
  • sensor (robot_dart::RobotDARTSimu)
  • sensors (robot_dart::RobotDARTSimu)
  • set_collision_detector (robot_dart::RobotDARTSimu)
  • set_collision_masks (robot_dart::RobotDARTSimu)
  • set_control_freq (robot_dart::RobotDARTSimu)
  • set_graphics (robot_dart::RobotDARTSimu)
  • set_graphics_freq (robot_dart::RobotDARTSimu)
  • set_gravity (robot_dart::RobotDARTSimu)
  • set_text_panel (robot_dart::RobotDARTSimu)
  • set_timestep (robot_dart::RobotDARTSimu)
  • status_bar_text (robot_dart::RobotDARTSimu)
  • step (robot_dart::RobotDARTSimu, robot_dart::Scheduler)
  • step_world (robot_dart::RobotDARTSimu)
  • stop_sim (robot_dart::RobotDARTSimu)
  • Scheduler (robot_dart::Scheduler)
  • set_sync (robot_dart::Scheduler)
  • sync (robot_dart::Scheduler)
  • set_pd (robot_dart::control::PDControl)
  • set_use_angular_errors (robot_dart::control::PDControl)
  • set_h_params (robot_dart::control::PolicyControl)
  • set_parameters (robot_dart::control::RobotControl)
  • set_robot (robot_dart::control::RobotControl)
  • set_weight (robot_dart::control::RobotControl)
  • SimpleControl (robot_dart::control::SimpleControl)
  • set_enable (robot_dart::gui::Base, robot_dart::gui::magnum::BaseGraphics)
  • set_fps (robot_dart::gui::Base, robot_dart::gui::magnum::BaseGraphics)
  • set_render_period (robot_dart::gui::Base)
  • set_simu (robot_dart::gui::Base, robot_dart::gui::magnum::BaseGraphics, robot_dart::gui::magnum::Graphics, robot_dart::gui::magnum::WindowlessGraphics, robot_dart::sensor::Sensor)
  • simu (robot_dart::gui::Base, robot_dart::gui::magnum::CubeMapShadowedColorObject, robot_dart::gui::magnum::CubeMapShadowedObject, robot_dart::gui::magnum::DrawableObject, robot_dart::gui::magnum::ShadowedColorObject, robot_dart::gui::magnum::ShadowedObject, robot_dart::sensor::Sensor)
  • scene (robot_dart::gui::magnum::BaseApplication)
  • shadowed (robot_dart::gui::magnum::BaseApplication, robot_dart::gui::magnum::BaseGraphics, robot_dart::gui::magnum::GraphicsConfiguration, robot_dart::gui::magnum::ObjectStruct)
  • set_materials (robot_dart::gui::magnum::CubeMapShadowedColorObject, robot_dart::gui::magnum::CubeMapShadowedObject, robot_dart::gui::magnum::DrawableObject, robot_dart::gui::magnum::ShadowedColorObject, robot_dart::gui::magnum::ShadowedObject)
  • set_meshes (robot_dart::gui::magnum::CubeMapShadowedColorObject, robot_dart::gui::magnum::CubeMapShadowedObject, robot_dart::gui::magnum::DrawableObject, robot_dart::gui::magnum::ShadowedColorObject, robot_dart::gui::magnum::ShadowedObject)
  • set_scalings (robot_dart::gui::magnum::CubeMapShadowedColorObject, robot_dart::gui::magnum::CubeMapShadowedObject, robot_dart::gui::magnum::DrawableObject, robot_dart::gui::magnum::ShadowedColorObject, robot_dart::gui::magnum::ShadowedObject)
  • shape (robot_dart::gui::magnum::CubeMapShadowedColorObject, robot_dart::gui::magnum::CubeMapShadowedObject, robot_dart::gui::magnum::DrawableObject, robot_dart::gui::magnum::ShadowedColorObject, robot_dart::gui::magnum::ShadowedObject)
  • set_color_shader (robot_dart::gui::magnum::DrawableObject)
  • set_soft_bodies (robot_dart::gui::magnum::DrawableObject)
  • set_texture_shader (robot_dart::gui::magnum::DrawableObject)
  • set_transparent (robot_dart::gui::magnum::DrawableObject)
  • set_max_contexts (robot_dart::gui::magnum::GlobalData)
  • shadow_map_size (robot_dart::gui::magnum::GraphicsConfiguration)
  • specular_strength (robot_dart::gui::magnum::GraphicsConfiguration)
  • shadowed_color (robot_dart::gui::magnum::ObjectStruct)
  • shadow_color_framebuffer (robot_dart::gui::magnum::ShadowData)
  • shadow_framebuffer (robot_dart::gui::magnum::ShadowData)
  • ShadowedColorObject (robot_dart::gui::magnum::ShadowedColorObject)
  • ShadowedObject (robot_dart::gui::magnum::ShadowedObject)
  • set_camera_params (robot_dart::gui::magnum::Camera)
  • set_far_plane (robot_dart::gui::magnum::Camera, robot_dart::gui::magnum::CubeMap, robot_dart::gui::magnum::CubeMapColor, robot_dart::gui::magnum::PhongMultiLight)
  • set_fov (robot_dart::gui::magnum::Camera)
  • set_near_plane (robot_dart::gui::magnum::Camera)
  • set_speed (robot_dart::gui::magnum::Camera)
  • set_viewport (robot_dart::gui::magnum::Camera)
  • speed (robot_dart::gui::magnum::Camera)
  • strafe (robot_dart::gui::magnum::Camera)
  • set_light_index (robot_dart::gui::magnum::CubeMap, robot_dart::gui::magnum::CubeMapColor)
  • set_light_position (robot_dart::gui::magnum::CubeMap, robot_dart::gui::magnum::CubeMapColor)
  • set_material (robot_dart::gui::magnum::CubeMap, robot_dart::gui::magnum::CubeMapColor, robot_dart::gui::magnum::Light, robot_dart::gui::magnum::PhongMultiLight, robot_dart::gui::magnum::ShadowMap, robot_dart::gui::magnum::ShadowMapColor)
  • set_shadow_matrices (robot_dart::gui::magnum::CubeMap, robot_dart::gui::magnum::CubeMapColor)
  • set_transformation_matrix (robot_dart::gui::magnum::CubeMap, robot_dart::gui::magnum::CubeMapColor, robot_dart::gui::magnum::PhongMultiLight, robot_dart::gui::magnum::ShadowMap, robot_dart::gui::magnum::ShadowMapColor)
  • set_attenuation (robot_dart::gui::magnum::Light)
  • set_casts_shadows (robot_dart::gui::magnum::Light)
  • set_position (robot_dart::gui::magnum::Light)
  • set_shadow_matrix (robot_dart::gui::magnum::Light)
  • set_spot_cut_off (robot_dart::gui::magnum::Light)
  • set_spot_direction (robot_dart::gui::magnum::Light)
  • set_spot_exponent (robot_dart::gui::magnum::Light)
  • set_transformed_position (robot_dart::gui::magnum::Light)
  • set_transformed_spot_direction (robot_dart::gui::magnum::Light)
  • shadow_matrix (robot_dart::gui::magnum::Light)
  • spot_cut_off (robot_dart::gui::magnum::Light)
  • spot_direction (robot_dart::gui::magnum::Light)
  • spot_exponent (robot_dart::gui::magnum::Light)
  • set_ambient_color (robot_dart::gui::magnum::Material)
  • set_ambient_texture (robot_dart::gui::magnum::Material)
  • set_diffuse_color (robot_dart::gui::magnum::Material)
  • set_diffuse_texture (robot_dart::gui::magnum::Material)
  • set_shininess (robot_dart::gui::magnum::Material)
  • set_specular_color (robot_dart::gui::magnum::Material)
  • set_specular_texture (robot_dart::gui::magnum::Material)
  • shininess (robot_dart::gui::magnum::Material)
  • specular_color (robot_dart::gui::magnum::Material)
  • specular_texture (robot_dart::gui::magnum::Material)
  • set_camera_matrix (robot_dart::gui::magnum::PhongMultiLight)
  • set_is_shadowed (robot_dart::gui::magnum::PhongMultiLight)
  • set_light (robot_dart::gui::magnum::PhongMultiLight)
  • set_normal_matrix (robot_dart::gui::magnum::PhongMultiLight)
  • set_projection_matrix (robot_dart::gui::magnum::PhongMultiLight, robot_dart::gui::magnum::ShadowMap, robot_dart::gui::magnum::ShadowMapColor)
  • set_specular_strength (robot_dart::gui::magnum::PhongMultiLight)
  • set_transparent_shadows (robot_dart::gui::magnum::PhongMultiLight)
  • ShadowMap (robot_dart::gui::magnum::ShadowMap)
  • ShadowMapColor (robot_dart::gui::magnum::ShadowMapColor)
  • Sensor (robot_dart::sensor::Sensor)
  • set_frequency (robot_dart::sensor::Sensor)
  • set_pose (robot_dart::sensor::Sensor)
"},{"location":"api/class_members/#t","title":"t","text":"
  • text_panel_text (robot_dart::RobotDARTSimu)
  • timestep (robot_dart::RobotDARTSimu)
  • transparent_shadows (robot_dart::gui::magnum::BaseApplication, robot_dart::gui::magnum::BaseGraphics, robot_dart::gui::magnum::GraphicsConfiguration)
  • text_indices (robot_dart::gui::magnum::DebugDrawData)
  • text_shader (robot_dart::gui::magnum::DebugDrawData)
  • text_vertices (robot_dart::gui::magnum::DebugDrawData)
  • transparent (robot_dart::gui::magnum::DrawableObject)
  • title (robot_dart::gui::magnum::GraphicsConfiguration)
  • transform_lights (robot_dart::gui::magnum::Camera)
  • TextureCoordinates (robot_dart::gui::magnum::CubeMap, robot_dart::gui::magnum::CubeMapColor, robot_dart::gui::magnum::PhongMultiLight, robot_dart::gui::magnum::ShadowMap, robot_dart::gui::magnum::ShadowMapColor)
  • transformed_position (robot_dart::gui::magnum::Light)
  • transformed_spot_direction (robot_dart::gui::magnum::Light)
  • type (robot_dart::gui::magnum::sensor::Camera, robot_dart::sensor::ForceTorque, robot_dart::sensor::IMU, robot_dart::sensor::Sensor, robot_dart::sensor::Torque)
  • Talos (robot_dart::robots::Talos)
  • torque_map_t (robot_dart::robots::Talos)
  • torques (robot_dart::robots::Talos, robot_dart::sensor::Torque)
  • TalosFastCollision (robot_dart::robots::TalosFastCollision)
  • TalosLight (robot_dart::robots::TalosLight)
  • Tiago (robot_dart::robots::Tiago)
  • torque (robot_dart::sensor::ForceTorque)
  • Torque (robot_dart::sensor::Torque)
  • text_drawings (robot_dart::simu::GUIData)
  • text (robot_dart::simu::TextData)
  • transformation (robot_dart::simu::TextData)
"},{"location":"api/class_members/#u","title":"u","text":"
  • update (robot_dart::Robot)
  • update_joint_dof_maps (robot_dart::Robot)
  • using_angular_errors (robot_dart::control::PDControl)
  • update_graphics (robot_dart::gui::magnum::BaseApplication)
  • update_lights (robot_dart::gui::magnum::BaseApplication)
  • Ur3e (robot_dart::robots::Ur3e)
  • Ur3eHand (robot_dart::robots::Ur3eHand)
  • update_robot (robot_dart::simu::GUIData)
"},{"location":"api/class_members/#v","title":"v","text":"
  • vec_dof (robot_dart::Robot)
  • velocities (robot_dart::Robot)
  • velocity_lower_limits (robot_dart::Robot)
  • velocity_upper_limits (robot_dart::Robot)
  • viewportEvent (robot_dart::gui::magnum::GlfwApplication)
  • Vx300 (robot_dart::robots::Vx300)
"},{"location":"api/class_members/#w","title":"w","text":"
  • what (robot_dart::Assertion)
  • world (robot_dart::RobotDARTSimu)
  • weight (robot_dart::control::RobotControl)
  • width (robot_dart::gui::Base, robot_dart::gui::DepthImage, robot_dart::gui::GrayscaleImage, robot_dart::gui::Image, robot_dart::gui::magnum::BaseGraphics, robot_dart::gui::magnum::GraphicsConfiguration, robot_dart::gui::magnum::Camera)
  • WindowlessGLApplication (robot_dart::gui::magnum::WindowlessGLApplication)
  • WindowlessGraphics (robot_dart::gui::magnum::WindowlessGraphics)
  • wrench (robot_dart::sensor::ForceTorque)
"},{"location":"api/class_members/#_1","title":"~","text":"
  • ~Robot (robot_dart::Robot)
  • ~RobotDARTSimu (robot_dart::RobotDARTSimu)
  • ~RobotPool (robot_dart::RobotPool)
  • ~BitmaskContactFilter (robot_dart::collision_filter::BitmaskContactFilter)
  • ~RobotControl (robot_dart::control::RobotControl)
  • ~Base (robot_dart::gui::Base)
  • ~BaseApplication (robot_dart::gui::magnum::BaseApplication)
  • ~BaseGraphics (robot_dart::gui::magnum::BaseGraphics)
  • ~GlfwApplication (robot_dart::gui::magnum::GlfwApplication)
  • ~GlobalData (robot_dart::gui::magnum::GlobalData)
  • ~Graphics (robot_dart::gui::magnum::Graphics)
  • ~WindowlessGLApplication (robot_dart::gui::magnum::WindowlessGLApplication)
  • ~WindowlessGraphics (robot_dart::gui::magnum::WindowlessGraphics)
  • ~Camera (robot_dart::gui::magnum::Camera, robot_dart::gui::magnum::sensor::Camera)
  • ~Sensor (robot_dart::sensor::Sensor)
"},{"location":"api/class_members/#_","title":"_","text":"
  • _make_message (robot_dart::Assertion)
  • _msg (robot_dart::Assertion)
  • _actuator_type (robot_dart::Robot)
  • _actuator_types (robot_dart::Robot)
  • _axis_shapes (robot_dart::Robot)
  • _cast_shadows (robot_dart::Robot, robot_dart::gui::magnum::Light)
  • _controllers (robot_dart::Robot)
  • _dof_map (robot_dart::Robot)
  • _get_path (robot_dart::Robot)
  • _is_ghost (robot_dart::Robot)
  • _jacobian (robot_dart::Robot)
  • _joint_map (robot_dart::Robot)
  • _load_model (robot_dart::Robot)
  • _mass_matrix (robot_dart::Robot)
  • _model_filename (robot_dart::Robot, robot_dart::RobotPool)
  • _packages (robot_dart::Robot)
  • _post_addition (robot_dart::Robot, robot_dart::robots::Franka, robot_dart::robots::ICub, robot_dart::robots::Iiwa, robot_dart::robots::Talos, robot_dart::robots::TalosFastCollision, robot_dart::robots::Tiago, robot_dart::robots::Ur3e)
  • _post_removal (robot_dart::Robot, robot_dart::robots::Franka, robot_dart::robots::ICub, robot_dart::robots::Iiwa, robot_dart::robots::Talos, robot_dart::robots::Tiago, robot_dart::robots::Ur3e)
  • _robot_name (robot_dart::Robot)
  • _set_actuator_type (robot_dart::Robot)
  • _set_actuator_types (robot_dart::Robot)
  • _set_color_mode (robot_dart::Robot)
  • _skeleton (robot_dart::Robot)
  • _break (robot_dart::RobotDARTSimu)
  • _control_freq (robot_dart::RobotDARTSimu)
  • _enable (robot_dart::RobotDARTSimu)
  • _graphics (robot_dart::RobotDARTSimu)
  • _graphics_freq (robot_dart::RobotDARTSimu)
  • _gui_data (robot_dart::RobotDARTSimu)
  • _old_index (robot_dart::RobotDARTSimu)
  • _physics_freq (robot_dart::RobotDARTSimu)
  • _robots (robot_dart::RobotDARTSimu)
  • _scheduler (robot_dart::RobotDARTSimu)
  • _sensors (robot_dart::RobotDARTSimu)
  • _status_bar (robot_dart::RobotDARTSimu)
  • _text_panel (robot_dart::RobotDARTSimu)
  • _world (robot_dart::RobotDARTSimu)
  • _free (robot_dart::RobotPool)
  • _pool_size (robot_dart::RobotPool)
  • _reset_robot (robot_dart::RobotPool)
  • _robot_creator (robot_dart::RobotPool)
  • _skeleton_mutex (robot_dart::RobotPool)
  • _skeletons (robot_dart::RobotPool)
  • _verbose (robot_dart::RobotPool)
  • _average_it_duration (robot_dart::Scheduler)
  • _current_step (robot_dart::Scheduler)
  • _current_time (robot_dart::Scheduler)
  • _dt (robot_dart::Scheduler, robot_dart::control::PolicyControl)
  • _it_duration (robot_dart::Scheduler)
  • _last_iteration_time (robot_dart::Scheduler)
  • _max_frequency (robot_dart::Scheduler)
  • _real_start_time (robot_dart::Scheduler)
  • _real_time (robot_dart::Scheduler)
  • _simu_start_time (robot_dart::Scheduler)
  • _start_time (robot_dart::Scheduler)
  • _sync (robot_dart::Scheduler)
  • _bitmask_map (robot_dart::collision_filter::BitmaskContactFilter)
  • _Kd (robot_dart::control::PDControl)
  • _Kp (robot_dart::control::PDControl)
  • _angle_dist (robot_dart::control::PDControl)
  • _use_angular_errors (robot_dart::control::PDControl)
  • _first (robot_dart::control::PolicyControl)
  • _full_dt (robot_dart::control::PolicyControl)
  • _i (robot_dart::control::PolicyControl)
  • _policy (robot_dart::control::PolicyControl)
  • _prev_commands (robot_dart::control::PolicyControl)
  • _prev_time (robot_dart::control::PolicyControl)
  • _threshold (robot_dart::control::PolicyControl)
  • _active (robot_dart::control::RobotControl, robot_dart::sensor::Sensor)
  • _check_free (robot_dart::control::RobotControl)
  • _control_dof (robot_dart::control::RobotControl)
  • _controllable_dofs (robot_dart::control::RobotControl)
  • _ctrl (robot_dart::control::RobotControl)
  • _dof (robot_dart::control::RobotControl)
  • _robot (robot_dart::control::RobotControl)
  • _weight (robot_dart::control::RobotControl)
  • _simu (robot_dart::gui::Base, robot_dart::gui::magnum::BaseApplication, robot_dart::gui::magnum::CubeMapShadowedColorObject, robot_dart::gui::magnum::CubeMapShadowedObject, robot_dart::gui::magnum::DrawableObject, robot_dart::gui::magnum::GlfwApplication, robot_dart::gui::magnum::ShadowedColorObject, robot_dart::gui::magnum::ShadowedObject, robot_dart::gui::magnum::WindowlessGLApplication, robot_dart::sensor::Sensor)
  • _3D_axis_mesh (robot_dart::gui::magnum::BaseApplication)
  • _3D_axis_shader (robot_dart::gui::magnum::BaseApplication)
  • _background_mesh (robot_dart::gui::magnum::BaseApplication)
  • _background_shader (robot_dart::gui::magnum::BaseApplication)
  • _camera (robot_dart::gui::magnum::BaseApplication, robot_dart::gui::magnum::Camera, robot_dart::gui::magnum::sensor::Camera)
  • _color_shader (robot_dart::gui::magnum::BaseApplication, robot_dart::gui::magnum::DrawableObject)
  • _configuration (robot_dart::gui::magnum::BaseApplication, robot_dart::gui::magnum::BaseGraphics)
  • _cubemap_color_drawables (robot_dart::gui::magnum::BaseApplication)
  • _cubemap_color_shader (robot_dart::gui::magnum::BaseApplication)
  • _cubemap_drawables (robot_dart::gui::magnum::BaseApplication)
  • _cubemap_shader (robot_dart::gui::magnum::BaseApplication)
  • _cubemap_texture_color_shader (robot_dart::gui::magnum::BaseApplication)
  • _cubemap_texture_shader (robot_dart::gui::magnum::BaseApplication)
  • _dart_world (robot_dart::gui::magnum::BaseApplication)
  • _done (robot_dart::gui::magnum::BaseApplication)
  • _drawable_objects (robot_dart::gui::magnum::BaseApplication)
  • _drawables (robot_dart::gui::magnum::BaseApplication)
  • _font (robot_dart::gui::magnum::BaseApplication)
  • _font_manager (robot_dart::gui::magnum::BaseApplication)
  • _gl_clean_up (robot_dart::gui::magnum::BaseApplication)
  • _glyph_cache (robot_dart::gui::magnum::BaseApplication)
  • _importer_manager (robot_dart::gui::magnum::BaseApplication)
  • _lights (robot_dart::gui::magnum::BaseApplication)
  • _max_lights (robot_dart::gui::magnum::BaseApplication, robot_dart::gui::magnum::PhongMultiLight)
  • _prepare_shadows (robot_dart::gui::magnum::BaseApplication)
  • _scene (robot_dart::gui::magnum::BaseApplication)
  • _shadow_camera (robot_dart::gui::magnum::BaseApplication)
  • _shadow_camera_object (robot_dart::gui::magnum::BaseApplication)
  • _shadow_color_cube_map (robot_dart::gui::magnum::BaseApplication)
  • _shadow_color_shader (robot_dart::gui::magnum::BaseApplication)
  • _shadow_color_texture (robot_dart::gui::magnum::BaseApplication)
  • _shadow_cube_map (robot_dart::gui::magnum::BaseApplication)
  • _shadow_data (robot_dart::gui::magnum::BaseApplication)
  • _shadow_map_size (robot_dart::gui::magnum::BaseApplication)
  • _shadow_shader (robot_dart::gui::magnum::BaseApplication)
  • _shadow_texture (robot_dart::gui::magnum::BaseApplication)
  • _shadow_texture_color_shader (robot_dart::gui::magnum::BaseApplication)
  • _shadow_texture_shader (robot_dart::gui::magnum::BaseApplication)
  • _shadowed (robot_dart::gui::magnum::BaseApplication)
  • _shadowed_color_drawables (robot_dart::gui::magnum::BaseApplication)
  • _shadowed_drawables (robot_dart::gui::magnum::BaseApplication)
  • _text_indices (robot_dart::gui::magnum::BaseApplication)
  • _text_shader (robot_dart::gui::magnum::BaseApplication)
  • _text_vertices (robot_dart::gui::magnum::BaseApplication)
  • _texture_shader (robot_dart::gui::magnum::BaseApplication, robot_dart::gui::magnum::CubeMapShadowedColorObject, robot_dart::gui::magnum::CubeMapShadowedObject, robot_dart::gui::magnum::DrawableObject, robot_dart::gui::magnum::ShadowedColorObject, robot_dart::gui::magnum::ShadowedObject)
  • _transparentSize (robot_dart::gui::magnum::BaseApplication)
  • _transparent_shadows (robot_dart::gui::magnum::BaseApplication)
  • _enabled (robot_dart::gui::magnum::BaseGraphics)
  • _fps (robot_dart::gui::magnum::BaseGraphics)
  • _magnum_app (robot_dart::gui::magnum::BaseGraphics, robot_dart::gui::magnum::sensor::Camera)
  • _magnum_silence_output (robot_dart::gui::magnum::BaseGraphics)
  • _materials (robot_dart::gui::magnum::CubeMapShadowedColorObject, robot_dart::gui::magnum::CubeMapShadowedObject, robot_dart::gui::magnum::DrawableObject, robot_dart::gui::magnum::ShadowedColorObject, robot_dart::gui::magnum::ShadowedObject)
  • _meshes (robot_dart::gui::magnum::CubeMapShadowedColorObject, robot_dart::gui::magnum::CubeMapShadowedObject, robot_dart::gui::magnum::DrawableObject, robot_dart::gui::magnum::ShadowedColorObject, robot_dart::gui::magnum::ShadowedObject)
  • _scalings (robot_dart::gui::magnum::CubeMapShadowedColorObject, robot_dart::gui::magnum::CubeMapShadowedObject, robot_dart::gui::magnum::DrawableObject, robot_dart::gui::magnum::ShadowedColorObject, robot_dart::gui::magnum::ShadowedObject)
  • _shader (robot_dart::gui::magnum::CubeMapShadowedColorObject, robot_dart::gui::magnum::CubeMapShadowedObject, robot_dart::gui::magnum::ShadowedColorObject, robot_dart::gui::magnum::ShadowedObject)
  • _shape (robot_dart::gui::magnum::CubeMapShadowedColorObject, robot_dart::gui::magnum::CubeMapShadowedObject, robot_dart::gui::magnum::DrawableObject, robot_dart::gui::magnum::ShadowedColorObject, robot_dart::gui::magnum::ShadowedObject)
  • _has_negative_scaling (robot_dart::gui::magnum::DrawableObject)
  • _isTransparent (robot_dart::gui::magnum::DrawableObject)
  • _is_soft_body (robot_dart::gui::magnum::DrawableObject)
  • _bg_color (robot_dart::gui::magnum::GlfwApplication, robot_dart::gui::magnum::WindowlessGLApplication)
  • _draw_debug (robot_dart::gui::magnum::GlfwApplication, robot_dart::gui::magnum::WindowlessGLApplication, robot_dart::gui::magnum::sensor::Camera)
  • _draw_main_camera (robot_dart::gui::magnum::GlfwApplication, robot_dart::gui::magnum::WindowlessGLApplication)
  • _speed (robot_dart::gui::magnum::GlfwApplication, robot_dart::gui::magnum::Camera)
  • _speed_move (robot_dart::gui::magnum::GlfwApplication)
  • _speed_strafe (robot_dart::gui::magnum::GlfwApplication)
  • _context_mutex (robot_dart::gui::magnum::GlobalData)
  • _create_contexts (robot_dart::gui::magnum::GlobalData)
  • _gl_contexts (robot_dart::gui::magnum::GlobalData)
  • _max_contexts (robot_dart::gui::magnum::GlobalData)
  • _used (robot_dart::gui::magnum::GlobalData)
  • _color (robot_dart::gui::magnum::WindowlessGLApplication, robot_dart::gui::magnum::sensor::Camera)
  • _depth (robot_dart::gui::magnum::WindowlessGLApplication, robot_dart::gui::magnum::sensor::Camera)
  • _format (robot_dart::gui::magnum::WindowlessGLApplication, robot_dart::gui::magnum::sensor::Camera)
  • _framebuffer (robot_dart::gui::magnum::WindowlessGLApplication, robot_dart::gui::magnum::sensor::Camera)
  • _aspect_ratio (robot_dart::gui::magnum::Camera)
  • _camera_object (robot_dart::gui::magnum::Camera)
  • _clean_up_subprocess (robot_dart::gui::magnum::Camera)
  • _depth_image (robot_dart::gui::magnum::Camera)
  • _far_plane (robot_dart::gui::magnum::Camera)
  • _ffmpeg_process (robot_dart::gui::magnum::Camera)
  • _fov (robot_dart::gui::magnum::Camera)
  • _front (robot_dart::gui::magnum::Camera)
  • _height (robot_dart::gui::magnum::Camera, robot_dart::gui::magnum::sensor::Camera)
  • _image (robot_dart::gui::magnum::Camera)
  • _near_plane (robot_dart::gui::magnum::Camera)
  • _pitch_object (robot_dart::gui::magnum::Camera)
  • _recording (robot_dart::gui::magnum::Camera)
  • _recording_depth (robot_dart::gui::magnum::Camera)
  • _recording_video (robot_dart::gui::magnum::Camera)
  • _right (robot_dart::gui::magnum::Camera)
  • _up (robot_dart::gui::magnum::Camera)
  • _width (robot_dart::gui::magnum::Camera, robot_dart::gui::magnum::sensor::Camera)
  • _yaw_object (robot_dart::gui::magnum::Camera)
  • _diffuse_color_uniform (robot_dart::gui::magnum::CubeMap, robot_dart::gui::magnum::CubeMapColor, robot_dart::gui::magnum::PhongMultiLight, robot_dart::gui::magnum::ShadowMap, robot_dart::gui::magnum::ShadowMapColor)
  • _far_plane_uniform (robot_dart::gui::magnum::CubeMap, robot_dart::gui::magnum::CubeMapColor, robot_dart::gui::magnum::PhongMultiLight)
  • _flags (robot_dart::gui::magnum::CubeMap, robot_dart::gui::magnum::CubeMapColor, robot_dart::gui::magnum::PhongMultiLight, robot_dart::gui::magnum::ShadowMap, robot_dart::gui::magnum::ShadowMapColor)
  • _light_index_uniform (robot_dart::gui::magnum::CubeMap, robot_dart::gui::magnum::CubeMapColor)
  • _light_position_uniform (robot_dart::gui::magnum::CubeMap, robot_dart::gui::magnum::CubeMapColor)
  • _shadow_matrices_uniform (robot_dart::gui::magnum::CubeMap, robot_dart::gui::magnum::CubeMapColor)
  • _transformation_matrix_uniform (robot_dart::gui::magnum::CubeMap, robot_dart::gui::magnum::CubeMapColor, robot_dart::gui::magnum::PhongMultiLight, robot_dart::gui::magnum::ShadowMap, robot_dart::gui::magnum::ShadowMapColor)
  • _cube_map_textures_location (robot_dart::gui::magnum::CubeMapColor, robot_dart::gui::magnum::PhongMultiLight)
  • _attenuation (robot_dart::gui::magnum::Light)
  • _material (robot_dart::gui::magnum::Light)
  • _position (robot_dart::gui::magnum::Light)
  • _shadow_transform (robot_dart::gui::magnum::Light)
  • _spot_cut_off (robot_dart::gui::magnum::Light)
  • _spot_direction (robot_dart::gui::magnum::Light)
  • _spot_exponent (robot_dart::gui::magnum::Light)
  • _transformed_position (robot_dart::gui::magnum::Light)
  • _transformed_spot_direction (robot_dart::gui::magnum::Light)
  • _ambient (robot_dart::gui::magnum::Material)
  • _ambient_texture (robot_dart::gui::magnum::Material)
  • _diffuse (robot_dart::gui::magnum::Material)
  • _diffuse_texture (robot_dart::gui::magnum::Material)
  • _shininess (robot_dart::gui::magnum::Material)
  • _specular (robot_dart::gui::magnum::Material)
  • _specular_texture (robot_dart::gui::magnum::Material)
  • _ambient_color_uniform (robot_dart::gui::magnum::PhongMultiLight)
  • _camera_matrix_uniform (robot_dart::gui::magnum::PhongMultiLight)
  • _cube_map_color_textures_location (robot_dart::gui::magnum::PhongMultiLight)
  • _is_shadowed_uniform (robot_dart::gui::magnum::PhongMultiLight)
  • _light_loc_size (robot_dart::gui::magnum::PhongMultiLight)
  • _lights_matrices_uniform (robot_dart::gui::magnum::PhongMultiLight)
  • _lights_uniform (robot_dart::gui::magnum::PhongMultiLight)
  • _normal_matrix_uniform (robot_dart::gui::magnum::PhongMultiLight)
  • _projection_matrix_uniform (robot_dart::gui::magnum::PhongMultiLight, robot_dart::gui::magnum::ShadowMap, robot_dart::gui::magnum::ShadowMapColor)
  • _shadow_color_textures_location (robot_dart::gui::magnum::PhongMultiLight)
  • _shadow_textures_location (robot_dart::gui::magnum::PhongMultiLight)
  • _shininess_uniform (robot_dart::gui::magnum::PhongMultiLight)
  • _specular_color_uniform (robot_dart::gui::magnum::PhongMultiLight)
  • _specular_strength_uniform (robot_dart::gui::magnum::PhongMultiLight)
  • _transparent_shadows_uniform (robot_dart::gui::magnum::PhongMultiLight)
  • _imu (robot_dart::robots::A1, robot_dart::robots::ICub, robot_dart::robots::Talos)
  • _ft_wrist (robot_dart::robots::Franka, robot_dart::robots::Iiwa, robot_dart::robots::Tiago, robot_dart::robots::Ur3e)
  • _ft_foot_left (robot_dart::robots::ICub, robot_dart::robots::Talos)
  • _ft_foot_right (robot_dart::robots::ICub, robot_dart::robots::Talos)
  • _frequency (robot_dart::robots::Talos, robot_dart::sensor::Sensor)
  • _ft_wrist_left (robot_dart::robots::Talos)
  • _ft_wrist_right (robot_dart::robots::Talos)
  • _torques (robot_dart::robots::Talos, robot_dart::sensor::Torque)
  • _direction (robot_dart::sensor::ForceTorque)
  • _wrench (robot_dart::sensor::ForceTorque)
  • _angular_pos (robot_dart::sensor::IMU)
  • _angular_vel (robot_dart::sensor::IMU)
  • _config (robot_dart::sensor::IMU)
  • _linear_accel (robot_dart::sensor::IMU)
  • _attached_tf (robot_dart::sensor::Sensor)
  • _attached_to_body (robot_dart::sensor::Sensor)
  • _attached_to_joint (robot_dart::sensor::Sensor)
  • _attaching_to_body (robot_dart::sensor::Sensor)
  • _attaching_to_joint (robot_dart::sensor::Sensor)
  • _body_attached (robot_dart::sensor::Sensor)
  • _joint_attached (robot_dart::sensor::Sensor)
  • _world_pose (robot_dart::sensor::Sensor)
"},{"location":"api/class_member_functions/","title":"Class Member Functions","text":""},{"location":"api/class_member_functions/#a","title":"a","text":"
  • Assertion (robot_dart::Assertion)
  • acceleration_lower_limits (robot_dart::Robot)
  • acceleration_upper_limits (robot_dart::Robot)
  • accelerations (robot_dart::Robot)
  • active_controllers (robot_dart::Robot)
  • actuator_type (robot_dart::Robot)
  • actuator_types (robot_dart::Robot)
  • add_body_mass (robot_dart::Robot)
  • add_controller (robot_dart::Robot)
  • add_external_force (robot_dart::Robot)
  • add_external_torque (robot_dart::Robot)
  • adjacent_colliding (robot_dart::Robot)
  • aug_mass_matrix (robot_dart::Robot)
  • add_checkerboard_floor (robot_dart::RobotDARTSimu)
  • add_floor (robot_dart::RobotDARTSimu)
  • add_robot (robot_dart::RobotDARTSimu)
  • add_sensor (robot_dart::RobotDARTSimu)
  • add_text (robot_dart::RobotDARTSimu, robot_dart::simu::GUIData)
  • add_visual_robot (robot_dart::RobotDARTSimu)
  • add_to_map (robot_dart::collision_filter::BitmaskContactFilter)
  • activate (robot_dart::control::RobotControl, robot_dart::sensor::Sensor)
  • active (robot_dart::control::RobotControl, robot_dart::sensor::Sensor)
  • add_light (robot_dart::gui::magnum::BaseApplication, robot_dart::gui::magnum::BaseGraphics)
  • attach_camera (robot_dart::gui::magnum::BaseApplication)
  • attenuation (robot_dart::gui::magnum::Light)
  • ambient_color (robot_dart::gui::magnum::Material)
  • ambient_texture (robot_dart::gui::magnum::Material)
  • attach_to_body (robot_dart::gui::magnum::sensor::Camera, robot_dart::sensor::ForceTorque, robot_dart::sensor::Sensor, robot_dart::sensor::Torque)
  • attach_to_joint (robot_dart::gui::magnum::sensor::Camera, robot_dart::sensor::IMU, robot_dart::sensor::Sensor)
  • A1 (robot_dart::robots::A1)
  • Arm (robot_dart::robots::Arm)
  • angular_position (robot_dart::sensor::IMU)
  • angular_position_vec (robot_dart::sensor::IMU)
  • angular_velocity (robot_dart::sensor::IMU)
  • attached_to (robot_dart::sensor::Sensor)
"},{"location":"api/class_member_functions/#b","title":"b","text":"
  • base_pose (robot_dart::Robot)
  • base_pose_vec (robot_dart::Robot)
  • body_acceleration (robot_dart::Robot)
  • body_index (robot_dart::Robot)
  • body_mass (robot_dart::Robot)
  • body_name (robot_dart::Robot)
  • body_names (robot_dart::Robot)
  • body_node (robot_dart::Robot)
  • body_pose (robot_dart::Robot)
  • body_pose_vec (robot_dart::Robot)
  • body_velocity (robot_dart::Robot)
  • Base (robot_dart::gui::Base)
  • BaseApplication (robot_dart::gui::magnum::BaseApplication)
  • BaseGraphics (robot_dart::gui::magnum::BaseGraphics)
  • bind_cube_map_texture (robot_dart::gui::magnum::CubeMapColor, robot_dart::gui::magnum::PhongMultiLight)
  • bind_cube_map_color_texture (robot_dart::gui::magnum::PhongMultiLight)
  • bind_shadow_color_texture (robot_dart::gui::magnum::PhongMultiLight)
  • bind_shadow_texture (robot_dart::gui::magnum::PhongMultiLight)
"},{"location":"api/class_member_functions/#c","title":"c","text":"
  • cast_shadows (robot_dart::Robot, robot_dart::simu::GUIData)
  • clear_controllers (robot_dart::Robot)
  • clear_external_forces (robot_dart::Robot)
  • clear_internal_forces (robot_dart::Robot)
  • clone (robot_dart::Robot, robot_dart::control::PDControl, robot_dart::control::PolicyControl, robot_dart::control::RobotControl, robot_dart::control::SimpleControl)
  • clone_ghost (robot_dart::Robot)
  • com (robot_dart::Robot)
  • com_acceleration (robot_dart::Robot)
  • com_jacobian (robot_dart::Robot)
  • com_jacobian_deriv (robot_dart::Robot)
  • com_velocity (robot_dart::Robot)
  • commands (robot_dart::Robot)
  • constraint_forces (robot_dart::Robot)
  • controller (robot_dart::Robot)
  • controllers (robot_dart::Robot)
  • coriolis_forces (robot_dart::Robot)
  • coriolis_gravity_forces (robot_dart::Robot)
  • coulomb_coeffs (robot_dart::Robot)
  • create_box (robot_dart::Robot)
  • create_ellipsoid (robot_dart::Robot)
  • clear_robots (robot_dart::RobotDARTSimu)
  • clear_sensors (robot_dart::RobotDARTSimu)
  • collision_category (robot_dart::RobotDARTSimu)
  • collision_detector (robot_dart::RobotDARTSimu)
  • collision_mask (robot_dart::RobotDARTSimu)
  • collision_masks (robot_dart::RobotDARTSimu)
  • control_freq (robot_dart::RobotDARTSimu)
  • current_time (robot_dart::Scheduler)
  • clear_all (robot_dart::collision_filter::BitmaskContactFilter)
  • calculate (robot_dart::control::PDControl, robot_dart::control::PolicyControl, robot_dart::control::RobotControl, robot_dart::control::SimpleControl, robot_dart::gui::magnum::sensor::Camera, robot_dart::sensor::ForceTorque, robot_dart::sensor::IMU, robot_dart::sensor::Sensor, robot_dart::sensor::Torque)
  • configure (robot_dart::control::PDControl, robot_dart::control::PolicyControl, robot_dart::control::RobotControl, robot_dart::control::SimpleControl)
  • controllable_dofs (robot_dart::control::RobotControl)
  • camera (robot_dart::gui::magnum::BaseApplication, robot_dart::gui::magnum::BaseGraphics, robot_dart::gui::magnum::Camera, robot_dart::gui::magnum::sensor::Camera)
  • clear_lights (robot_dart::gui::magnum::BaseApplication, robot_dart::gui::magnum::BaseGraphics)
  • camera_extrinsic_matrix (robot_dart::gui::magnum::BaseGraphics, robot_dart::gui::magnum::sensor::Camera)
  • camera_intrinsic_matrix (robot_dart::gui::magnum::BaseGraphics, robot_dart::gui::magnum::sensor::Camera)
  • CubeMapShadowedColorObject (robot_dart::gui::magnum::CubeMapShadowedColorObject)
  • CubeMapShadowedObject (robot_dart::gui::magnum::CubeMapShadowedObject)
  • Camera (robot_dart::gui::magnum::Camera, robot_dart::gui::magnum::sensor::Camera)
  • camera_object (robot_dart::gui::magnum::Camera)
  • CubeMap (robot_dart::gui::magnum::CubeMap)
  • CubeMapColor (robot_dart::gui::magnum::CubeMapColor)
  • casts_shadows (robot_dart::gui::magnum::Light)
  • collision_vec (robot_dart::robots::TalosFastCollision)
  • caster_joints (robot_dart::robots::Tiago)
"},{"location":"api/class_member_functions/#d","title":"d","text":"
  • damping_coeffs (robot_dart::Robot)
  • dof (robot_dart::Robot)
  • dof_index (robot_dart::Robot)
  • dof_map (robot_dart::Robot)
  • dof_name (robot_dart::Robot)
  • dof_names (robot_dart::Robot)
  • drawing_axes (robot_dart::Robot, robot_dart::simu::GUIData)
  • dt (robot_dart::Scheduler)
  • depth_array (robot_dart::gui::Base, robot_dart::gui::magnum::BaseApplication, robot_dart::gui::magnum::BaseGraphics, robot_dart::gui::magnum::sensor::Camera)
  • depth_image (robot_dart::gui::Base, robot_dart::gui::magnum::BaseApplication, robot_dart::gui::magnum::BaseGraphics, robot_dart::gui::magnum::Camera, robot_dart::gui::magnum::sensor::Camera)
  • done (robot_dart::gui::Base, robot_dart::gui::magnum::BaseApplication, robot_dart::gui::magnum::BaseGraphics)
  • debug_draw_data (robot_dart::gui::magnum::BaseApplication)
  • drawables (robot_dart::gui::magnum::BaseApplication)
  • draw (robot_dart::gui::magnum::CubeMapShadowedColorObject, robot_dart::gui::magnum::CubeMapShadowedObject, robot_dart::gui::magnum::DrawableObject, robot_dart::gui::magnum::ShadowedColorObject, robot_dart::gui::magnum::ShadowedObject, robot_dart::gui::magnum::Camera)
  • DrawableObject (robot_dart::gui::magnum::DrawableObject)
  • drawEvent (robot_dart::gui::magnum::GlfwApplication)
  • default_configuration (robot_dart::gui::magnum::Graphics, robot_dart::gui::magnum::WindowlessGraphics)
  • diffuse_color (robot_dart::gui::magnum::Material)
  • diffuse_texture (robot_dart::gui::magnum::Material)
  • draw_debug (robot_dart::gui::magnum::sensor::Camera)
  • drawing_debug (robot_dart::gui::magnum::sensor::Camera)
  • detach (robot_dart::sensor::Sensor)
  • drawing_texts (robot_dart::simu::GUIData)
"},{"location":"api/class_member_functions/#e","title":"e","text":"
  • external_forces (robot_dart::Robot)
  • enable_status_bar (robot_dart::RobotDARTSimu)
  • enable_text_panel (robot_dart::RobotDARTSimu)
  • enable_shadows (robot_dart::gui::magnum::BaseApplication, robot_dart::gui::magnum::BaseGraphics)
  • exitEvent (robot_dart::gui::magnum::GlfwApplication)
  • exec (robot_dart::gui::magnum::WindowlessGLApplication)
  • extrinsic_matrix (robot_dart::gui::magnum::Camera)
"},{"location":"api/class_member_functions/#f","title":"f","text":"
  • fix_to_world (robot_dart::Robot)
  • fixed (robot_dart::Robot)
  • force_lower_limits (robot_dart::Robot)
  • force_position_bounds (robot_dart::Robot)
  • force_torque (robot_dart::Robot)
  • force_upper_limits (robot_dart::Robot)
  • forces (robot_dart::Robot)
  • free (robot_dart::Robot)
  • free_from_world (robot_dart::Robot)
  • friction_coeff (robot_dart::Robot)
  • friction_dir (robot_dart::Robot)
  • free_robot (robot_dart::RobotPool)
  • free_gl_context (robot_dart::gui::magnum::GlobalData)
  • far_plane (robot_dart::gui::magnum::Camera)
  • forward (robot_dart::gui::magnum::Camera)
  • fov (robot_dart::gui::magnum::Camera)
  • flags (robot_dart::gui::magnum::CubeMap, robot_dart::gui::magnum::CubeMapColor, robot_dart::gui::magnum::PhongMultiLight, robot_dart::gui::magnum::ShadowMap, robot_dart::gui::magnum::ShadowMapColor)
  • Franka (robot_dart::robots::Franka)
  • ft_wrist (robot_dart::robots::Franka, robot_dart::robots::Iiwa, robot_dart::robots::Tiago, robot_dart::robots::Ur3e)
  • ft_foot_left (robot_dart::robots::ICub, robot_dart::robots::Talos)
  • ft_foot_right (robot_dart::robots::ICub, robot_dart::robots::Talos)
  • ft_wrist_left (robot_dart::robots::Talos)
  • ft_wrist_right (robot_dart::robots::Talos)
  • ForceTorque (robot_dart::sensor::ForceTorque)
  • force (robot_dart::sensor::ForceTorque)
  • frequency (robot_dart::sensor::Sensor)
"},{"location":"api/class_member_functions/#g","title":"g","text":"
  • ghost (robot_dart::Robot, robot_dart::simu::GUIData)
  • gravity_forces (robot_dart::Robot)
  • graphics (robot_dart::RobotDARTSimu)
  • graphics_freq (robot_dart::RobotDARTSimu)
  • gravity (robot_dart::RobotDARTSimu)
  • gui_data (robot_dart::RobotDARTSimu)
  • get_robot (robot_dart::RobotPool)
  • GlfwApplication (robot_dart::gui::magnum::GlfwApplication)
  • GlobalData (robot_dart::gui::magnum::GlobalData)
  • gl_context (robot_dart::gui::magnum::GlobalData)
  • Graphics (robot_dart::gui::magnum::Graphics)
"},{"location":"api/class_member_functions/#h","title":"h","text":"
  • halted_sim (robot_dart::RobotDARTSimu)
  • h_params (robot_dart::control::PolicyControl)
  • height (robot_dart::gui::Base, robot_dart::gui::magnum::BaseGraphics, robot_dart::gui::magnum::Camera)
  • has_ambient_texture (robot_dart::gui::magnum::Material)
  • has_diffuse_texture (robot_dart::gui::magnum::Material)
  • has_specular_texture (robot_dart::gui::magnum::Material)
  • Hexapod (robot_dart::robots::Hexapod)
"},{"location":"api/class_member_functions/#i","title":"i","text":"
  • inv_aug_mass_matrix (robot_dart::Robot)
  • inv_mass_matrix (robot_dart::Robot)
  • it_duration (robot_dart::Scheduler)
  • ignoresCollision (robot_dart::collision_filter::BitmaskContactFilter)
  • init (robot_dart::control::RobotControl, robot_dart::gui::magnum::BaseApplication, robot_dart::gui::magnum::sensor::Camera, robot_dart::sensor::ForceTorque, robot_dart::sensor::IMU, robot_dart::sensor::Sensor, robot_dart::sensor::Torque)
  • image (robot_dart::gui::Base, robot_dart::gui::magnum::BaseApplication, robot_dart::gui::magnum::BaseGraphics, robot_dart::gui::magnum::Camera, robot_dart::gui::magnum::sensor::Camera)
  • instance (robot_dart::gui::magnum::GlobalData)
  • intrinsic_matrix (robot_dart::gui::magnum::Camera)
  • imu (robot_dart::robots::A1, robot_dart::robots::ICub, robot_dart::robots::Talos)
  • ICub (robot_dart::robots::ICub)
  • Iiwa (robot_dart::robots::Iiwa)
  • IMU (robot_dart::sensor::IMU)
  • IMUConfig (robot_dart::sensor::IMUConfig)
"},{"location":"api/class_member_functions/#j","title":"j","text":"
  • jacobian (robot_dart::Robot)
  • jacobian_deriv (robot_dart::Robot)
  • joint (robot_dart::Robot)
  • joint_index (robot_dart::Robot)
  • joint_map (robot_dart::Robot)
  • joint_name (robot_dart::Robot)
  • joint_names (robot_dart::Robot)
"},{"location":"api/class_member_functions/#k","title":"k","text":"
  • keyPressEvent (robot_dart::gui::magnum::GlfwApplication)
  • keyReleaseEvent (robot_dart::gui::magnum::GlfwApplication)
"},{"location":"api/class_member_functions/#l","title":"l","text":"
  • locked_dof_names (robot_dart::Robot)
  • last_it_duration (robot_dart::Scheduler)
  • light (robot_dart::gui::magnum::BaseApplication, robot_dart::gui::magnum::BaseGraphics)
  • lights (robot_dart::gui::magnum::BaseApplication, robot_dart::gui::magnum::BaseGraphics)
  • look_at (robot_dart::gui::magnum::BaseApplication, robot_dart::gui::magnum::BaseGraphics, robot_dart::gui::magnum::Camera, robot_dart::gui::magnum::sensor::Camera)
  • Light (robot_dart::gui::magnum::Light)
  • linear_acceleration (robot_dart::sensor::IMU)
"},{"location":"api/class_member_functions/#m","title":"m","text":"
  • mass_matrix (robot_dart::Robot)
  • mimic_dof_names (robot_dart::Robot)
  • model_filename (robot_dart::Robot, robot_dart::RobotPool)
  • model_packages (robot_dart::Robot)
  • mask (robot_dart::collision_filter::BitmaskContactFilter)
  • magnum_app (robot_dart::gui::magnum::BaseGraphics)
  • magnum_image (robot_dart::gui::magnum::BaseGraphics, robot_dart::gui::magnum::sensor::Camera)
  • materials (robot_dart::gui::magnum::DrawableObject)
  • mouseMoveEvent (robot_dart::gui::magnum::GlfwApplication)
  • mouseScrollEvent (robot_dart::gui::magnum::GlfwApplication)
  • move (robot_dart::gui::magnum::Camera)
  • material (robot_dart::gui::magnum::Light)
  • Material (robot_dart::gui::magnum::Material)
  • max_lights (robot_dart::gui::magnum::PhongMultiLight)
  • magnum_depth_image (robot_dart::gui::magnum::sensor::Camera)
"},{"location":"api/class_member_functions/#n","title":"n","text":"
  • name (robot_dart::Robot)
  • num_bodies (robot_dart::Robot)
  • num_controllers (robot_dart::Robot)
  • num_dofs (robot_dart::Robot)
  • num_joints (robot_dart::Robot)
  • num_robots (robot_dart::RobotDARTSimu)
  • next_time (robot_dart::Scheduler)
  • num_lights (robot_dart::gui::magnum::BaseApplication, robot_dart::gui::magnum::BaseGraphics)
  • near_plane (robot_dart::gui::magnum::Camera)
"},{"location":"api/class_member_functions/#o","title":"o","text":"
  • operator= (robot_dart::RobotPool, robot_dart::gui::magnum::GlobalData)
  • operator() (robot_dart::Scheduler)
"},{"location":"api/class_member_functions/#p","title":"p","text":"
  • passive_dof_names (robot_dart::Robot)
  • position_enforced (robot_dart::Robot)
  • position_lower_limits (robot_dart::Robot)
  • position_upper_limits (robot_dart::Robot)
  • positions (robot_dart::Robot)
  • physics_freq (robot_dart::RobotDARTSimu)
  • PDControl (robot_dart::control::PDControl)
  • pd (robot_dart::control::PDControl)
  • PolicyControl (robot_dart::control::PolicyControl)
  • parameters (robot_dart::control::RobotControl)
  • position (robot_dart::gui::magnum::Light)
  • PhongMultiLight (robot_dart::gui::magnum::PhongMultiLight)
  • Pendulum (robot_dart::robots::Pendulum)
  • pose (robot_dart::sensor::Sensor)
"},{"location":"api/class_member_functions/#r","title":"r","text":"
  • Robot (robot_dart::Robot)
  • reinit_controllers (robot_dart::Robot)
  • remove_all_drawing_axis (robot_dart::Robot)
  • remove_controller (robot_dart::Robot)
  • reset (robot_dart::Robot, robot_dart::Scheduler, robot_dart::robots::A1, robot_dart::robots::Hexapod, robot_dart::robots::ICub, robot_dart::robots::Talos, robot_dart::robots::Tiago)
  • reset_commands (robot_dart::Robot)
  • restitution_coeff (robot_dart::Robot)
  • RobotDARTSimu (robot_dart::RobotDARTSimu)
  • remove_all_collision_masks (robot_dart::RobotDARTSimu)
  • remove_collision_masks (robot_dart::RobotDARTSimu)
  • remove_robot (robot_dart::RobotDARTSimu, robot_dart::simu::GUIData)
  • remove_sensor (robot_dart::RobotDARTSimu)
  • remove_sensors (robot_dart::RobotDARTSimu)
  • robot (robot_dart::RobotDARTSimu, robot_dart::control::RobotControl)
  • robot_index (robot_dart::RobotDARTSimu)
  • robots (robot_dart::RobotDARTSimu)
  • run (robot_dart::RobotDARTSimu)
  • RobotPool (robot_dart::RobotPool)
  • real_time (robot_dart::Scheduler)
  • real_time_factor (robot_dart::Scheduler)
  • remove_from_map (robot_dart::collision_filter::BitmaskContactFilter)
  • RobotControl (robot_dart::control::RobotControl)
  • raw_depth_image (robot_dart::gui::Base, robot_dart::gui::magnum::BaseApplication, robot_dart::gui::magnum::BaseGraphics, robot_dart::gui::magnum::sensor::Camera)
  • refresh (robot_dart::gui::Base, robot_dart::gui::magnum::BaseGraphics, robot_dart::sensor::Sensor)
  • record_video (robot_dart::gui::magnum::BaseApplication, robot_dart::gui::magnum::BaseGraphics, robot_dart::gui::magnum::Camera, robot_dart::gui::magnum::sensor::Camera)
  • render (robot_dart::gui::magnum::BaseApplication, robot_dart::gui::magnum::GlfwApplication, robot_dart::gui::magnum::WindowlessGLApplication)
  • render_shadows (robot_dart::gui::magnum::BaseApplication)
  • record (robot_dart::gui::magnum::Camera)
  • recording (robot_dart::gui::magnum::Camera)
  • recording_depth (robot_dart::gui::magnum::Camera)
  • root_object (robot_dart::gui::magnum::Camera)
  • remove_text (robot_dart::simu::GUIData)
"},{"location":"api/class_member_functions/#s","title":"s","text":"
  • secondary_friction_coeff (robot_dart::Robot)
  • self_colliding (robot_dart::Robot)
  • set_acceleration_lower_limits (robot_dart::Robot)
  • set_acceleration_upper_limits (robot_dart::Robot)
  • set_accelerations (robot_dart::Robot)
  • set_actuator_type (robot_dart::Robot, robot_dart::robots::Tiago)
  • set_actuator_types (robot_dart::Robot, robot_dart::robots::Tiago)
  • set_base_pose (robot_dart::Robot)
  • set_body_mass (robot_dart::Robot)
  • set_body_name (robot_dart::Robot)
  • set_cast_shadows (robot_dart::Robot)
  • set_color_mode (robot_dart::Robot)
  • set_commands (robot_dart::Robot)
  • set_coulomb_coeffs (robot_dart::Robot)
  • set_damping_coeffs (robot_dart::Robot)
  • set_draw_axis (robot_dart::Robot)
  • set_external_force (robot_dart::Robot)
  • set_external_torque (robot_dart::Robot)
  • set_force_lower_limits (robot_dart::Robot)
  • set_force_upper_limits (robot_dart::Robot)
  • set_forces (robot_dart::Robot)
  • set_friction_coeff (robot_dart::Robot)
  • set_friction_coeffs (robot_dart::Robot)
  • set_friction_dir (robot_dart::Robot)
  • set_ghost (robot_dart::Robot)
  • set_joint_name (robot_dart::Robot)
  • set_mimic (robot_dart::Robot)
  • set_position_enforced (robot_dart::Robot)
  • set_position_lower_limits (robot_dart::Robot)
  • set_position_upper_limits (robot_dart::Robot)
  • set_positions (robot_dart::Robot)
  • set_restitution_coeff (robot_dart::Robot)
  • set_restitution_coeffs (robot_dart::Robot)
  • set_secondary_friction_coeff (robot_dart::Robot)
  • set_secondary_friction_coeffs (robot_dart::Robot)
  • set_self_collision (robot_dart::Robot)
  • set_spring_stiffnesses (robot_dart::Robot)
  • set_velocities (robot_dart::Robot)
  • set_velocity_lower_limits (robot_dart::Robot)
  • set_velocity_upper_limits (robot_dart::Robot)
  • skeleton (robot_dart::Robot)
  • spring_stiffnesses (robot_dart::Robot)
  • schedule (robot_dart::RobotDARTSimu, robot_dart::Scheduler)
  • scheduler (robot_dart::RobotDARTSimu)
  • sensor (robot_dart::RobotDARTSimu)
  • sensors (robot_dart::RobotDARTSimu)
  • set_collision_detector (robot_dart::RobotDARTSimu)
  • set_collision_masks (robot_dart::RobotDARTSimu)
  • set_control_freq (robot_dart::RobotDARTSimu)
  • set_graphics (robot_dart::RobotDARTSimu)
  • set_graphics_freq (robot_dart::RobotDARTSimu)
  • set_gravity (robot_dart::RobotDARTSimu)
  • set_text_panel (robot_dart::RobotDARTSimu)
  • set_timestep (robot_dart::RobotDARTSimu)
  • status_bar_text (robot_dart::RobotDARTSimu)
  • step (robot_dart::RobotDARTSimu, robot_dart::Scheduler)
  • step_world (robot_dart::RobotDARTSimu)
  • stop_sim (robot_dart::RobotDARTSimu)
  • Scheduler (robot_dart::Scheduler)
  • set_sync (robot_dart::Scheduler)
  • sync (robot_dart::Scheduler)
  • set_pd (robot_dart::control::PDControl)
  • set_use_angular_errors (robot_dart::control::PDControl)
  • set_h_params (robot_dart::control::PolicyControl)
  • set_parameters (robot_dart::control::RobotControl)
  • set_robot (robot_dart::control::RobotControl)
  • set_weight (robot_dart::control::RobotControl)
  • SimpleControl (robot_dart::control::SimpleControl)
  • set_enable (robot_dart::gui::Base, robot_dart::gui::magnum::BaseGraphics)
  • set_fps (robot_dart::gui::Base, robot_dart::gui::magnum::BaseGraphics)
  • set_render_period (robot_dart::gui::Base)
  • set_simu (robot_dart::gui::Base, robot_dart::gui::magnum::BaseGraphics, robot_dart::gui::magnum::Graphics, robot_dart::gui::magnum::WindowlessGraphics, robot_dart::sensor::Sensor)
  • simu (robot_dart::gui::Base, robot_dart::gui::magnum::CubeMapShadowedColorObject, robot_dart::gui::magnum::CubeMapShadowedObject, robot_dart::gui::magnum::DrawableObject, robot_dart::gui::magnum::ShadowedColorObject, robot_dart::gui::magnum::ShadowedObject, robot_dart::sensor::Sensor)
  • scene (robot_dart::gui::magnum::BaseApplication)
  • shadowed (robot_dart::gui::magnum::BaseApplication, robot_dart::gui::magnum::BaseGraphics)
  • set_materials (robot_dart::gui::magnum::CubeMapShadowedColorObject, robot_dart::gui::magnum::CubeMapShadowedObject, robot_dart::gui::magnum::DrawableObject, robot_dart::gui::magnum::ShadowedColorObject, robot_dart::gui::magnum::ShadowedObject)
  • set_meshes (robot_dart::gui::magnum::CubeMapShadowedColorObject, robot_dart::gui::magnum::CubeMapShadowedObject, robot_dart::gui::magnum::DrawableObject, robot_dart::gui::magnum::ShadowedColorObject, robot_dart::gui::magnum::ShadowedObject)
  • set_scalings (robot_dart::gui::magnum::CubeMapShadowedColorObject, robot_dart::gui::magnum::CubeMapShadowedObject, robot_dart::gui::magnum::DrawableObject, robot_dart::gui::magnum::ShadowedColorObject, robot_dart::gui::magnum::ShadowedObject)
  • shape (robot_dart::gui::magnum::CubeMapShadowedColorObject, robot_dart::gui::magnum::CubeMapShadowedObject, robot_dart::gui::magnum::DrawableObject, robot_dart::gui::magnum::ShadowedColorObject, robot_dart::gui::magnum::ShadowedObject)
  • set_color_shader (robot_dart::gui::magnum::DrawableObject)
  • set_soft_bodies (robot_dart::gui::magnum::DrawableObject)
  • set_texture_shader (robot_dart::gui::magnum::DrawableObject)
  • set_transparent (robot_dart::gui::magnum::DrawableObject)
  • set_max_contexts (robot_dart::gui::magnum::GlobalData)
  • ShadowedColorObject (robot_dart::gui::magnum::ShadowedColorObject)
  • ShadowedObject (robot_dart::gui::magnum::ShadowedObject)
  • set_camera_params (robot_dart::gui::magnum::Camera)
  • set_far_plane (robot_dart::gui::magnum::Camera, robot_dart::gui::magnum::CubeMap, robot_dart::gui::magnum::CubeMapColor, robot_dart::gui::magnum::PhongMultiLight)
  • set_fov (robot_dart::gui::magnum::Camera)
  • set_near_plane (robot_dart::gui::magnum::Camera)
  • set_speed (robot_dart::gui::magnum::Camera)
  • set_viewport (robot_dart::gui::magnum::Camera)
  • speed (robot_dart::gui::magnum::Camera)
  • strafe (robot_dart::gui::magnum::Camera)
  • set_light_index (robot_dart::gui::magnum::CubeMap, robot_dart::gui::magnum::CubeMapColor)
  • set_light_position (robot_dart::gui::magnum::CubeMap, robot_dart::gui::magnum::CubeMapColor)
  • set_material (robot_dart::gui::magnum::CubeMap, robot_dart::gui::magnum::CubeMapColor, robot_dart::gui::magnum::Light, robot_dart::gui::magnum::PhongMultiLight, robot_dart::gui::magnum::ShadowMap, robot_dart::gui::magnum::ShadowMapColor)
  • set_shadow_matrices (robot_dart::gui::magnum::CubeMap, robot_dart::gui::magnum::CubeMapColor)
  • set_transformation_matrix (robot_dart::gui::magnum::CubeMap, robot_dart::gui::magnum::CubeMapColor, robot_dart::gui::magnum::PhongMultiLight, robot_dart::gui::magnum::ShadowMap, robot_dart::gui::magnum::ShadowMapColor)
  • set_attenuation (robot_dart::gui::magnum::Light)
  • set_casts_shadows (robot_dart::gui::magnum::Light)
  • set_position (robot_dart::gui::magnum::Light)
  • set_shadow_matrix (robot_dart::gui::magnum::Light)
  • set_spot_cut_off (robot_dart::gui::magnum::Light)
  • set_spot_direction (robot_dart::gui::magnum::Light)
  • set_spot_exponent (robot_dart::gui::magnum::Light)
  • set_transformed_position (robot_dart::gui::magnum::Light)
  • set_transformed_spot_direction (robot_dart::gui::magnum::Light)
  • shadow_matrix (robot_dart::gui::magnum::Light)
  • spot_cut_off (robot_dart::gui::magnum::Light)
  • spot_direction (robot_dart::gui::magnum::Light)
  • spot_exponent (robot_dart::gui::magnum::Light)
  • set_ambient_color (robot_dart::gui::magnum::Material)
  • set_ambient_texture (robot_dart::gui::magnum::Material)
  • set_diffuse_color (robot_dart::gui::magnum::Material)
  • set_diffuse_texture (robot_dart::gui::magnum::Material)
  • set_shininess (robot_dart::gui::magnum::Material)
  • set_specular_color (robot_dart::gui::magnum::Material)
  • set_specular_texture (robot_dart::gui::magnum::Material)
  • shininess (robot_dart::gui::magnum::Material)
  • specular_color (robot_dart::gui::magnum::Material)
  • specular_texture (robot_dart::gui::magnum::Material)
  • set_camera_matrix (robot_dart::gui::magnum::PhongMultiLight)
  • set_is_shadowed (robot_dart::gui::magnum::PhongMultiLight)
  • set_light (robot_dart::gui::magnum::PhongMultiLight)
  • set_normal_matrix (robot_dart::gui::magnum::PhongMultiLight)
  • set_projection_matrix (robot_dart::gui::magnum::PhongMultiLight, robot_dart::gui::magnum::ShadowMap, robot_dart::gui::magnum::ShadowMapColor)
  • set_specular_strength (robot_dart::gui::magnum::PhongMultiLight)
  • set_transparent_shadows (robot_dart::gui::magnum::PhongMultiLight)
  • ShadowMap (robot_dart::gui::magnum::ShadowMap)
  • ShadowMapColor (robot_dart::gui::magnum::ShadowMapColor)
  • Sensor (robot_dart::sensor::Sensor)
  • set_frequency (robot_dart::sensor::Sensor)
  • set_pose (robot_dart::sensor::Sensor)
"},{"location":"api/class_member_functions/#t","title":"t","text":"
  • text_panel_text (robot_dart::RobotDARTSimu)
  • timestep (robot_dart::RobotDARTSimu)
  • transparent_shadows (robot_dart::gui::magnum::BaseApplication, robot_dart::gui::magnum::BaseGraphics)
  • transparent (robot_dart::gui::magnum::DrawableObject)
  • transform_lights (robot_dart::gui::magnum::Camera)
  • transformed_position (robot_dart::gui::magnum::Light)
  • transformed_spot_direction (robot_dart::gui::magnum::Light)
  • type (robot_dart::gui::magnum::sensor::Camera, robot_dart::sensor::ForceTorque, robot_dart::sensor::IMU, robot_dart::sensor::Sensor, robot_dart::sensor::Torque)
  • Talos (robot_dart::robots::Talos)
  • torques (robot_dart::robots::Talos, robot_dart::sensor::Torque)
  • TalosFastCollision (robot_dart::robots::TalosFastCollision)
  • TalosLight (robot_dart::robots::TalosLight)
  • Tiago (robot_dart::robots::Tiago)
  • torque (robot_dart::sensor::ForceTorque)
  • Torque (robot_dart::sensor::Torque)
"},{"location":"api/class_member_functions/#u","title":"u","text":"
  • update (robot_dart::Robot)
  • update_joint_dof_maps (robot_dart::Robot)
  • using_angular_errors (robot_dart::control::PDControl)
  • update_graphics (robot_dart::gui::magnum::BaseApplication)
  • update_lights (robot_dart::gui::magnum::BaseApplication)
  • Ur3e (robot_dart::robots::Ur3e)
  • Ur3eHand (robot_dart::robots::Ur3eHand)
  • update_robot (robot_dart::simu::GUIData)
"},{"location":"api/class_member_functions/#v","title":"v","text":"
  • vec_dof (robot_dart::Robot)
  • velocities (robot_dart::Robot)
  • velocity_lower_limits (robot_dart::Robot)
  • velocity_upper_limits (robot_dart::Robot)
  • viewportEvent (robot_dart::gui::magnum::GlfwApplication)
  • Vx300 (robot_dart::robots::Vx300)
"},{"location":"api/class_member_functions/#w","title":"w","text":"
  • what (robot_dart::Assertion)
  • world (robot_dart::RobotDARTSimu)
  • weight (robot_dart::control::RobotControl)
  • width (robot_dart::gui::Base, robot_dart::gui::magnum::BaseGraphics, robot_dart::gui::magnum::Camera)
  • WindowlessGLApplication (robot_dart::gui::magnum::WindowlessGLApplication)
  • WindowlessGraphics (robot_dart::gui::magnum::WindowlessGraphics)
  • wrench (robot_dart::sensor::ForceTorque)
"},{"location":"api/class_member_functions/#_1","title":"~","text":"
  • ~Robot (robot_dart::Robot)
  • ~RobotDARTSimu (robot_dart::RobotDARTSimu)
  • ~RobotPool (robot_dart::RobotPool)
  • ~BitmaskContactFilter (robot_dart::collision_filter::BitmaskContactFilter)
  • ~RobotControl (robot_dart::control::RobotControl)
  • ~Base (robot_dart::gui::Base)
  • ~BaseApplication (robot_dart::gui::magnum::BaseApplication)
  • ~BaseGraphics (robot_dart::gui::magnum::BaseGraphics)
  • ~GlfwApplication (robot_dart::gui::magnum::GlfwApplication)
  • ~GlobalData (robot_dart::gui::magnum::GlobalData)
  • ~Graphics (robot_dart::gui::magnum::Graphics)
  • ~WindowlessGLApplication (robot_dart::gui::magnum::WindowlessGLApplication)
  • ~WindowlessGraphics (robot_dart::gui::magnum::WindowlessGraphics)
  • ~Camera (robot_dart::gui::magnum::Camera, robot_dart::gui::magnum::sensor::Camera)
  • ~Sensor (robot_dart::sensor::Sensor)
"},{"location":"api/class_member_functions/#_","title":"_","text":"
  • _make_message (robot_dart::Assertion)
  • _actuator_type (robot_dart::Robot)
  • _actuator_types (robot_dart::Robot)
  • _get_path (robot_dart::Robot)
  • _jacobian (robot_dart::Robot)
  • _load_model (robot_dart::Robot)
  • _mass_matrix (robot_dart::Robot)
  • _post_addition (robot_dart::Robot, robot_dart::robots::Franka, robot_dart::robots::ICub, robot_dart::robots::Iiwa, robot_dart::robots::Talos, robot_dart::robots::TalosFastCollision, robot_dart::robots::Tiago, robot_dart::robots::Ur3e)
  • _post_removal (robot_dart::Robot, robot_dart::robots::Franka, robot_dart::robots::ICub, robot_dart::robots::Iiwa, robot_dart::robots::Talos, robot_dart::robots::Tiago, robot_dart::robots::Ur3e)
  • _set_actuator_type (robot_dart::Robot)
  • _set_actuator_types (robot_dart::Robot)
  • _set_color_mode (robot_dart::Robot)
  • _enable (robot_dart::RobotDARTSimu)
  • _reset_robot (robot_dart::RobotPool)
  • _angle_dist (robot_dart::control::PDControl)
  • _gl_clean_up (robot_dart::gui::magnum::BaseApplication)
  • _prepare_shadows (robot_dart::gui::magnum::BaseApplication)
  • _create_contexts (robot_dart::gui::magnum::GlobalData)
  • _clean_up_subprocess (robot_dart::gui::magnum::Camera)
"},{"location":"api/class_member_variables/","title":"Class Member Variables","text":""},{"location":"api/class_member_variables/#a","title":"a","text":"
  • axes_mesh (robot_dart::gui::magnum::DebugDrawData)
  • axes_shader (robot_dart::gui::magnum::DebugDrawData)
  • accel_bias (robot_dart::sensor::IMUConfig)
  • alignment (robot_dart::simu::TextData)
"},{"location":"api/class_member_variables/#b","title":"b","text":"
  • background_mesh (robot_dart::gui::magnum::DebugDrawData)
  • background_shader (robot_dart::gui::magnum::DebugDrawData)
  • bg_color (robot_dart::gui::magnum::GraphicsConfiguration)
  • body (robot_dart::sensor::IMUConfig)
  • background_color (robot_dart::simu::TextData)
"},{"location":"api/class_member_variables/#c","title":"c","text":"
  • category_mask (robot_dart::collision_filter::BitmaskContactFilter::Masks)
  • collision_mask (robot_dart::collision_filter::BitmaskContactFilter::Masks)
  • channels (robot_dart::gui::Image)
  • cache (robot_dart::gui::magnum::DebugDrawData)
  • cubemapped (robot_dart::gui::magnum::ObjectStruct)
  • cubemapped_color (robot_dart::gui::magnum::ObjectStruct)
  • color (robot_dart::simu::TextData)
  • casting_shadows (robot_dart::simu::GUIData::RobotData)
"},{"location":"api/class_member_variables/#d","title":"d","text":"
  • data (robot_dart::gui::DepthImage, robot_dart::gui::GrayscaleImage, robot_dart::gui::Image)
  • draw_debug (robot_dart::gui::magnum::GraphicsConfiguration)
  • draw_main_camera (robot_dart::gui::magnum::GraphicsConfiguration)
  • draw_text (robot_dart::gui::magnum::GraphicsConfiguration)
  • drawable (robot_dart::gui::magnum::ObjectStruct)
  • draw_background (robot_dart::simu::TextData)
"},{"location":"api/class_member_variables/#f","title":"f","text":"
  • font (robot_dart::gui::magnum::DebugDrawData)
  • frequency (robot_dart::sensor::IMUConfig)
  • font_size (robot_dart::simu::TextData)
"},{"location":"api/class_member_variables/#g","title":"g","text":"
  • gyro_bias (robot_dart::sensor::IMUConfig)
"},{"location":"api/class_member_variables/#h","title":"h","text":"
  • height (robot_dart::gui::DepthImage, robot_dart::gui::GrayscaleImage, robot_dart::gui::Image, robot_dart::gui::magnum::GraphicsConfiguration)
"},{"location":"api/class_member_variables/#i","title":"i","text":"
  • is_ghost (robot_dart::simu::GUIData::RobotData)
"},{"location":"api/class_member_variables/#m","title":"m","text":"
  • max_lights (robot_dart::gui::magnum::GraphicsConfiguration)
"},{"location":"api/class_member_variables/#r","title":"r","text":"
  • robot_axes (robot_dart::simu::GUIData)
  • robot_data (robot_dart::simu::GUIData)
"},{"location":"api/class_member_variables/#s","title":"s","text":"
  • shadow_map_size (robot_dart::gui::magnum::GraphicsConfiguration)
  • shadowed (robot_dart::gui::magnum::GraphicsConfiguration, robot_dart::gui::magnum::ObjectStruct)
  • specular_strength (robot_dart::gui::magnum::GraphicsConfiguration)
  • shadowed_color (robot_dart::gui::magnum::ObjectStruct)
  • shadow_color_framebuffer (robot_dart::gui::magnum::ShadowData)
  • shadow_framebuffer (robot_dart::gui::magnum::ShadowData)
"},{"location":"api/class_member_variables/#t","title":"t","text":"
  • text_indices (robot_dart::gui::magnum::DebugDrawData)
  • text_shader (robot_dart::gui::magnum::DebugDrawData)
  • text_vertices (robot_dart::gui::magnum::DebugDrawData)
  • title (robot_dart::gui::magnum::GraphicsConfiguration)
  • transparent_shadows (robot_dart::gui::magnum::GraphicsConfiguration)
  • text_drawings (robot_dart::simu::GUIData)
  • text (robot_dart::simu::TextData)
  • transformation (robot_dart::simu::TextData)
"},{"location":"api/class_member_variables/#w","title":"w","text":"
  • width (robot_dart::gui::DepthImage, robot_dart::gui::GrayscaleImage, robot_dart::gui::Image, robot_dart::gui::magnum::GraphicsConfiguration)
"},{"location":"api/class_member_variables/#_","title":"_","text":"
  • _msg (robot_dart::Assertion)
  • _axis_shapes (robot_dart::Robot)
  • _cast_shadows (robot_dart::Robot, robot_dart::gui::magnum::Light)
  • _controllers (robot_dart::Robot)
  • _dof_map (robot_dart::Robot)
  • _is_ghost (robot_dart::Robot)
  • _joint_map (robot_dart::Robot)
  • _model_filename (robot_dart::Robot, robot_dart::RobotPool)
  • _packages (robot_dart::Robot)
  • _robot_name (robot_dart::Robot)
  • _skeleton (robot_dart::Robot)
  • _break (robot_dart::RobotDARTSimu)
  • _control_freq (robot_dart::RobotDARTSimu)
  • _graphics (robot_dart::RobotDARTSimu)
  • _graphics_freq (robot_dart::RobotDARTSimu)
  • _gui_data (robot_dart::RobotDARTSimu)
  • _old_index (robot_dart::RobotDARTSimu)
  • _physics_freq (robot_dart::RobotDARTSimu)
  • _robots (robot_dart::RobotDARTSimu)
  • _scheduler (robot_dart::RobotDARTSimu)
  • _sensors (robot_dart::RobotDARTSimu)
  • _status_bar (robot_dart::RobotDARTSimu)
  • _text_panel (robot_dart::RobotDARTSimu)
  • _world (robot_dart::RobotDARTSimu)
  • _free (robot_dart::RobotPool)
  • _pool_size (robot_dart::RobotPool)
  • _robot_creator (robot_dart::RobotPool)
  • _skeleton_mutex (robot_dart::RobotPool)
  • _skeletons (robot_dart::RobotPool)
  • _verbose (robot_dart::RobotPool)
  • _average_it_duration (robot_dart::Scheduler)
  • _current_step (robot_dart::Scheduler)
  • _current_time (robot_dart::Scheduler)
  • _dt (robot_dart::Scheduler, robot_dart::control::PolicyControl)
  • _it_duration (robot_dart::Scheduler)
  • _last_iteration_time (robot_dart::Scheduler)
  • _max_frequency (robot_dart::Scheduler)
  • _real_start_time (robot_dart::Scheduler)
  • _real_time (robot_dart::Scheduler)
  • _simu_start_time (robot_dart::Scheduler)
  • _start_time (robot_dart::Scheduler)
  • _sync (robot_dart::Scheduler)
  • _bitmask_map (robot_dart::collision_filter::BitmaskContactFilter)
  • _Kd (robot_dart::control::PDControl)
  • _Kp (robot_dart::control::PDControl)
  • _use_angular_errors (robot_dart::control::PDControl)
  • _first (robot_dart::control::PolicyControl)
  • _full_dt (robot_dart::control::PolicyControl)
  • _i (robot_dart::control::PolicyControl)
  • _policy (robot_dart::control::PolicyControl)
  • _prev_commands (robot_dart::control::PolicyControl)
  • _prev_time (robot_dart::control::PolicyControl)
  • _threshold (robot_dart::control::PolicyControl)
  • _active (robot_dart::control::RobotControl, robot_dart::sensor::Sensor)
  • _check_free (robot_dart::control::RobotControl)
  • _control_dof (robot_dart::control::RobotControl)
  • _controllable_dofs (robot_dart::control::RobotControl)
  • _ctrl (robot_dart::control::RobotControl)
  • _dof (robot_dart::control::RobotControl)
  • _robot (robot_dart::control::RobotControl)
  • _weight (robot_dart::control::RobotControl)
  • _simu (robot_dart::gui::Base, robot_dart::gui::magnum::BaseApplication, robot_dart::gui::magnum::CubeMapShadowedColorObject, robot_dart::gui::magnum::CubeMapShadowedObject, robot_dart::gui::magnum::DrawableObject, robot_dart::gui::magnum::GlfwApplication, robot_dart::gui::magnum::ShadowedColorObject, robot_dart::gui::magnum::ShadowedObject, robot_dart::gui::magnum::WindowlessGLApplication, robot_dart::sensor::Sensor)
  • _3D_axis_mesh (robot_dart::gui::magnum::BaseApplication)
  • _3D_axis_shader (robot_dart::gui::magnum::BaseApplication)
  • _background_mesh (robot_dart::gui::magnum::BaseApplication)
  • _background_shader (robot_dart::gui::magnum::BaseApplication)
  • _camera (robot_dart::gui::magnum::BaseApplication, robot_dart::gui::magnum::Camera, robot_dart::gui::magnum::sensor::Camera)
  • _color_shader (robot_dart::gui::magnum::BaseApplication, robot_dart::gui::magnum::DrawableObject)
  • _configuration (robot_dart::gui::magnum::BaseApplication, robot_dart::gui::magnum::BaseGraphics)
  • _cubemap_color_drawables (robot_dart::gui::magnum::BaseApplication)
  • _cubemap_color_shader (robot_dart::gui::magnum::BaseApplication)
  • _cubemap_drawables (robot_dart::gui::magnum::BaseApplication)
  • _cubemap_shader (robot_dart::gui::magnum::BaseApplication)
  • _cubemap_texture_color_shader (robot_dart::gui::magnum::BaseApplication)
  • _cubemap_texture_shader (robot_dart::gui::magnum::BaseApplication)
  • _dart_world (robot_dart::gui::magnum::BaseApplication)
  • _done (robot_dart::gui::magnum::BaseApplication)
  • _drawable_objects (robot_dart::gui::magnum::BaseApplication)
  • _drawables (robot_dart::gui::magnum::BaseApplication)
  • _font (robot_dart::gui::magnum::BaseApplication)
  • _font_manager (robot_dart::gui::magnum::BaseApplication)
  • _glyph_cache (robot_dart::gui::magnum::BaseApplication)
  • _importer_manager (robot_dart::gui::magnum::BaseApplication)
  • _lights (robot_dart::gui::magnum::BaseApplication)
  • _max_lights (robot_dart::gui::magnum::BaseApplication, robot_dart::gui::magnum::PhongMultiLight)
  • _scene (robot_dart::gui::magnum::BaseApplication)
  • _shadow_camera (robot_dart::gui::magnum::BaseApplication)
  • _shadow_camera_object (robot_dart::gui::magnum::BaseApplication)
  • _shadow_color_cube_map (robot_dart::gui::magnum::BaseApplication)
  • _shadow_color_shader (robot_dart::gui::magnum::BaseApplication)
  • _shadow_color_texture (robot_dart::gui::magnum::BaseApplication)
  • _shadow_cube_map (robot_dart::gui::magnum::BaseApplication)
  • _shadow_data (robot_dart::gui::magnum::BaseApplication)
  • _shadow_map_size (robot_dart::gui::magnum::BaseApplication)
  • _shadow_shader (robot_dart::gui::magnum::BaseApplication)
  • _shadow_texture (robot_dart::gui::magnum::BaseApplication)
  • _shadow_texture_color_shader (robot_dart::gui::magnum::BaseApplication)
  • _shadow_texture_shader (robot_dart::gui::magnum::BaseApplication)
  • _shadowed (robot_dart::gui::magnum::BaseApplication)
  • _shadowed_color_drawables (robot_dart::gui::magnum::BaseApplication)
  • _shadowed_drawables (robot_dart::gui::magnum::BaseApplication)
  • _text_indices (robot_dart::gui::magnum::BaseApplication)
  • _text_shader (robot_dart::gui::magnum::BaseApplication)
  • _text_vertices (robot_dart::gui::magnum::BaseApplication)
  • _texture_shader (robot_dart::gui::magnum::BaseApplication, robot_dart::gui::magnum::CubeMapShadowedColorObject, robot_dart::gui::magnum::CubeMapShadowedObject, robot_dart::gui::magnum::DrawableObject, robot_dart::gui::magnum::ShadowedColorObject, robot_dart::gui::magnum::ShadowedObject)
  • _transparentSize (robot_dart::gui::magnum::BaseApplication)
  • _transparent_shadows (robot_dart::gui::magnum::BaseApplication)
  • _enabled (robot_dart::gui::magnum::BaseGraphics)
  • _fps (robot_dart::gui::magnum::BaseGraphics)
  • _magnum_app (robot_dart::gui::magnum::BaseGraphics, robot_dart::gui::magnum::sensor::Camera)
  • _magnum_silence_output (robot_dart::gui::magnum::BaseGraphics)
  • _materials (robot_dart::gui::magnum::CubeMapShadowedColorObject, robot_dart::gui::magnum::CubeMapShadowedObject, robot_dart::gui::magnum::DrawableObject, robot_dart::gui::magnum::ShadowedColorObject, robot_dart::gui::magnum::ShadowedObject)
  • _meshes (robot_dart::gui::magnum::CubeMapShadowedColorObject, robot_dart::gui::magnum::CubeMapShadowedObject, robot_dart::gui::magnum::DrawableObject, robot_dart::gui::magnum::ShadowedColorObject, robot_dart::gui::magnum::ShadowedObject)
  • _scalings (robot_dart::gui::magnum::CubeMapShadowedColorObject, robot_dart::gui::magnum::CubeMapShadowedObject, robot_dart::gui::magnum::DrawableObject, robot_dart::gui::magnum::ShadowedColorObject, robot_dart::gui::magnum::ShadowedObject)
  • _shader (robot_dart::gui::magnum::CubeMapShadowedColorObject, robot_dart::gui::magnum::CubeMapShadowedObject, robot_dart::gui::magnum::ShadowedColorObject, robot_dart::gui::magnum::ShadowedObject)
  • _shape (robot_dart::gui::magnum::CubeMapShadowedColorObject, robot_dart::gui::magnum::CubeMapShadowedObject, robot_dart::gui::magnum::DrawableObject, robot_dart::gui::magnum::ShadowedColorObject, robot_dart::gui::magnum::ShadowedObject)
  • _has_negative_scaling (robot_dart::gui::magnum::DrawableObject)
  • _isTransparent (robot_dart::gui::magnum::DrawableObject)
  • _is_soft_body (robot_dart::gui::magnum::DrawableObject)
  • _bg_color (robot_dart::gui::magnum::GlfwApplication, robot_dart::gui::magnum::WindowlessGLApplication)
  • _draw_debug (robot_dart::gui::magnum::GlfwApplication, robot_dart::gui::magnum::WindowlessGLApplication, robot_dart::gui::magnum::sensor::Camera)
  • _draw_main_camera (robot_dart::gui::magnum::GlfwApplication, robot_dart::gui::magnum::WindowlessGLApplication)
  • _speed (robot_dart::gui::magnum::GlfwApplication, robot_dart::gui::magnum::Camera)
  • _speed_move (robot_dart::gui::magnum::GlfwApplication)
  • _speed_strafe (robot_dart::gui::magnum::GlfwApplication)
  • _context_mutex (robot_dart::gui::magnum::GlobalData)
  • _gl_contexts (robot_dart::gui::magnum::GlobalData)
  • _max_contexts (robot_dart::gui::magnum::GlobalData)
  • _used (robot_dart::gui::magnum::GlobalData)
  • _color (robot_dart::gui::magnum::WindowlessGLApplication, robot_dart::gui::magnum::sensor::Camera)
  • _depth (robot_dart::gui::magnum::WindowlessGLApplication, robot_dart::gui::magnum::sensor::Camera)
  • _format (robot_dart::gui::magnum::WindowlessGLApplication, robot_dart::gui::magnum::sensor::Camera)
  • _framebuffer (robot_dart::gui::magnum::WindowlessGLApplication, robot_dart::gui::magnum::sensor::Camera)
  • _aspect_ratio (robot_dart::gui::magnum::Camera)
  • _camera_object (robot_dart::gui::magnum::Camera)
  • _depth_image (robot_dart::gui::magnum::Camera)
  • _far_plane (robot_dart::gui::magnum::Camera)
  • _ffmpeg_process (robot_dart::gui::magnum::Camera)
  • _fov (robot_dart::gui::magnum::Camera)
  • _front (robot_dart::gui::magnum::Camera)
  • _height (robot_dart::gui::magnum::Camera, robot_dart::gui::magnum::sensor::Camera)
  • _image (robot_dart::gui::magnum::Camera)
  • _near_plane (robot_dart::gui::magnum::Camera)
  • _pitch_object (robot_dart::gui::magnum::Camera)
  • _recording (robot_dart::gui::magnum::Camera)
  • _recording_depth (robot_dart::gui::magnum::Camera)
  • _recording_video (robot_dart::gui::magnum::Camera)
  • _right (robot_dart::gui::magnum::Camera)
  • _up (robot_dart::gui::magnum::Camera)
  • _width (robot_dart::gui::magnum::Camera, robot_dart::gui::magnum::sensor::Camera)
  • _yaw_object (robot_dart::gui::magnum::Camera)
  • _diffuse_color_uniform (robot_dart::gui::magnum::CubeMap, robot_dart::gui::magnum::CubeMapColor, robot_dart::gui::magnum::PhongMultiLight, robot_dart::gui::magnum::ShadowMap, robot_dart::gui::magnum::ShadowMapColor)
  • _far_plane_uniform (robot_dart::gui::magnum::CubeMap, robot_dart::gui::magnum::CubeMapColor, robot_dart::gui::magnum::PhongMultiLight)
  • _flags (robot_dart::gui::magnum::CubeMap, robot_dart::gui::magnum::CubeMapColor, robot_dart::gui::magnum::PhongMultiLight, robot_dart::gui::magnum::ShadowMap, robot_dart::gui::magnum::ShadowMapColor)
  • _light_index_uniform (robot_dart::gui::magnum::CubeMap, robot_dart::gui::magnum::CubeMapColor)
  • _light_position_uniform (robot_dart::gui::magnum::CubeMap, robot_dart::gui::magnum::CubeMapColor)
  • _shadow_matrices_uniform (robot_dart::gui::magnum::CubeMap, robot_dart::gui::magnum::CubeMapColor)
  • _transformation_matrix_uniform (robot_dart::gui::magnum::CubeMap, robot_dart::gui::magnum::CubeMapColor, robot_dart::gui::magnum::PhongMultiLight, robot_dart::gui::magnum::ShadowMap, robot_dart::gui::magnum::ShadowMapColor)
  • _cube_map_textures_location (robot_dart::gui::magnum::CubeMapColor, robot_dart::gui::magnum::PhongMultiLight)
  • _attenuation (robot_dart::gui::magnum::Light)
  • _material (robot_dart::gui::magnum::Light)
  • _position (robot_dart::gui::magnum::Light)
  • _shadow_transform (robot_dart::gui::magnum::Light)
  • _spot_cut_off (robot_dart::gui::magnum::Light)
  • _spot_direction (robot_dart::gui::magnum::Light)
  • _spot_exponent (robot_dart::gui::magnum::Light)
  • _transformed_position (robot_dart::gui::magnum::Light)
  • _transformed_spot_direction (robot_dart::gui::magnum::Light)
  • _ambient (robot_dart::gui::magnum::Material)
  • _ambient_texture (robot_dart::gui::magnum::Material)
  • _diffuse (robot_dart::gui::magnum::Material)
  • _diffuse_texture (robot_dart::gui::magnum::Material)
  • _shininess (robot_dart::gui::magnum::Material)
  • _specular (robot_dart::gui::magnum::Material)
  • _specular_texture (robot_dart::gui::magnum::Material)
  • _ambient_color_uniform (robot_dart::gui::magnum::PhongMultiLight)
  • _camera_matrix_uniform (robot_dart::gui::magnum::PhongMultiLight)
  • _cube_map_color_textures_location (robot_dart::gui::magnum::PhongMultiLight)
  • _is_shadowed_uniform (robot_dart::gui::magnum::PhongMultiLight)
  • _light_loc_size (robot_dart::gui::magnum::PhongMultiLight)
  • _lights_matrices_uniform (robot_dart::gui::magnum::PhongMultiLight)
  • _lights_uniform (robot_dart::gui::magnum::PhongMultiLight)
  • _normal_matrix_uniform (robot_dart::gui::magnum::PhongMultiLight)
  • _projection_matrix_uniform (robot_dart::gui::magnum::PhongMultiLight, robot_dart::gui::magnum::ShadowMap, robot_dart::gui::magnum::ShadowMapColor)
  • _shadow_color_textures_location (robot_dart::gui::magnum::PhongMultiLight)
  • _shadow_textures_location (robot_dart::gui::magnum::PhongMultiLight)
  • _shininess_uniform (robot_dart::gui::magnum::PhongMultiLight)
  • _specular_color_uniform (robot_dart::gui::magnum::PhongMultiLight)
  • _specular_strength_uniform (robot_dart::gui::magnum::PhongMultiLight)
  • _transparent_shadows_uniform (robot_dart::gui::magnum::PhongMultiLight)
  • _imu (robot_dart::robots::A1, robot_dart::robots::ICub, robot_dart::robots::Talos)
  • _ft_wrist (robot_dart::robots::Franka, robot_dart::robots::Iiwa, robot_dart::robots::Tiago, robot_dart::robots::Ur3e)
  • _ft_foot_left (robot_dart::robots::ICub, robot_dart::robots::Talos)
  • _ft_foot_right (robot_dart::robots::ICub, robot_dart::robots::Talos)
  • _frequency (robot_dart::robots::Talos, robot_dart::sensor::Sensor)
  • _ft_wrist_left (robot_dart::robots::Talos)
  • _ft_wrist_right (robot_dart::robots::Talos)
  • _torques (robot_dart::robots::Talos, robot_dart::sensor::Torque)
  • _direction (robot_dart::sensor::ForceTorque)
  • _wrench (robot_dart::sensor::ForceTorque)
  • _angular_pos (robot_dart::sensor::IMU)
  • _angular_vel (robot_dart::sensor::IMU)
  • _config (robot_dart::sensor::IMU)
  • _linear_accel (robot_dart::sensor::IMU)
  • _attached_tf (robot_dart::sensor::Sensor)
  • _attached_to_body (robot_dart::sensor::Sensor)
  • _attached_to_joint (robot_dart::sensor::Sensor)
  • _attaching_to_body (robot_dart::sensor::Sensor)
  • _attaching_to_joint (robot_dart::sensor::Sensor)
  • _body_attached (robot_dart::sensor::Sensor)
  • _joint_attached (robot_dart::sensor::Sensor)
  • _world_pose (robot_dart::sensor::Sensor)
"},{"location":"api/class_member_typedefs/","title":"Class Member Typedefs","text":""},{"location":"api/class_member_typedefs/#c","title":"c","text":"
  • clock_t (robot_dart::Scheduler)
"},{"location":"api/class_member_typedefs/#d","title":"d","text":"
  • DartCollisionConstPtr (robot_dart::collision_filter::BitmaskContactFilter)
  • DartShapeConstPtr (robot_dart::collision_filter::BitmaskContactFilter)
"},{"location":"api/class_member_typedefs/#f","title":"f","text":"
  • Flags (robot_dart::gui::magnum::CubeMap, robot_dart::gui::magnum::CubeMapColor, robot_dart::gui::magnum::PhongMultiLight, robot_dart::gui::magnum::ShadowMap, robot_dart::gui::magnum::ShadowMapColor)
"},{"location":"api/class_member_typedefs/#n","title":"n","text":"
  • Normal (robot_dart::gui::magnum::PhongMultiLight)
"},{"location":"api/class_member_typedefs/#p","title":"p","text":"
  • Position (robot_dart::gui::magnum::CubeMap, robot_dart::gui::magnum::CubeMapColor, robot_dart::gui::magnum::PhongMultiLight, robot_dart::gui::magnum::ShadowMap, robot_dart::gui::magnum::ShadowMapColor)
"},{"location":"api/class_member_typedefs/#r","title":"r","text":"
  • robot_t (robot_dart::RobotDARTSimu)
  • robot_creator_t (robot_dart::RobotPool)
"},{"location":"api/class_member_typedefs/#t","title":"t","text":"
  • TextureCoordinates (robot_dart::gui::magnum::CubeMap, robot_dart::gui::magnum::CubeMapColor, robot_dart::gui::magnum::PhongMultiLight, robot_dart::gui::magnum::ShadowMap, robot_dart::gui::magnum::ShadowMapColor)
  • torque_map_t (robot_dart::robots::Talos)
"},{"location":"api/class_member_enums/","title":"Class Member Enums","text":""},{"location":"api/class_member_enums/#f","title":"f","text":"
  • Flag (robot_dart::gui::magnum::CubeMap, robot_dart::gui::magnum::CubeMapColor, robot_dart::gui::magnum::PhongMultiLight, robot_dart::gui::magnum::ShadowMap, robot_dart::gui::magnum::ShadowMapColor)
"},{"location":"api/namespace_members/","title":"Namespace Members","text":""},{"location":"api/namespace_members/#a","title":"a","text":"
  • add_dof_data (robot_dart::detail)
"},{"location":"api/namespace_members/#b","title":"b","text":"
  • body_node_get_friction_coeff (robot_dart)
  • body_node_get_restitution_coeff (robot_dart)
  • body_node_set_friction_coeff (robot_dart)
  • body_node_set_restitution_coeff (robot_dart)
"},{"location":"api/namespace_members/#c","title":"c","text":"
  • createCompatibilityShader (Magnum::Shaders::Implementation)
  • convert_rgb_to_grayscale (robot_dart::gui)
  • Camera3D (robot_dart::gui::magnum)
  • create_directional_light (robot_dart::gui::magnum::gs)
  • create_point_light (robot_dart::gui::magnum::gs)
  • create_spot_light (robot_dart::gui::magnum::gs)
"},{"location":"api/namespace_members/#d","title":"d","text":"
  • dof_data (robot_dart::detail)
  • depth_array_from_image (robot_dart::gui::magnum::gs)
  • depth_from_image (robot_dart::gui::magnum::gs)
"},{"location":"api/namespace_members/#g","title":"g","text":"
  • gs (robot_dart::gui::magnum::gs)
"},{"location":"api/namespace_members/#m","title":"m","text":"
  • make_tf (robot_dart)
  • make_vector (robot_dart)
  • make_application (robot_dart::gui::magnum)
"},{"location":"api/namespace_members/#o","title":"o","text":"
  • Object3D (robot_dart::gui::magnum)
"},{"location":"api/namespace_members/#p","title":"p","text":"
  • point_cloud_from_depth_array (robot_dart::gui)
"},{"location":"api/namespace_members/#r","title":"r","text":"
  • rgb_from_image (robot_dart::gui::magnum::gs)
"},{"location":"api/namespace_members/#s","title":"s","text":"
  • set_dof_data (robot_dart::detail)
  • Scene3D (robot_dart::gui::magnum)
  • search_path (robot_dart::gui::magnum::gs)
  • save_png_image (robot_dart::gui)
"},{"location":"api/namespace_member_functions/","title":"Namespace Member Functions","text":""},{"location":"api/namespace_member_functions/#a","title":"a","text":"
  • add_dof_data (robot_dart::detail)
"},{"location":"api/namespace_member_functions/#c","title":"c","text":"
  • createCompatibilityShader (Magnum::Shaders::Implementation)
  • convert_rgb_to_grayscale (robot_dart::gui)
  • create_directional_light (robot_dart::gui::magnum::gs)
  • create_point_light (robot_dart::gui::magnum::gs)
  • create_spot_light (robot_dart::gui::magnum::gs)
"},{"location":"api/namespace_member_functions/#d","title":"d","text":"
  • dof_data (robot_dart::detail)
  • depth_array_from_image (robot_dart::gui::magnum::gs)
  • depth_from_image (robot_dart::gui::magnum::gs)
"},{"location":"api/namespace_member_functions/#m","title":"m","text":"
  • make_tf (robot_dart)
  • make_vector (robot_dart)
  • make_application (robot_dart::gui::magnum)
"},{"location":"api/namespace_member_functions/#p","title":"p","text":"
  • point_cloud_from_depth_array (robot_dart::gui)
"},{"location":"api/namespace_member_functions/#r","title":"r","text":"
  • rgb_from_image (robot_dart::gui::magnum::gs)
"},{"location":"api/namespace_member_functions/#s","title":"s","text":"
  • set_dof_data (robot_dart::detail)
  • search_path (robot_dart::gui::magnum::gs)
  • save_png_image (robot_dart::gui)
"},{"location":"api/namespace_member_variables/","title":"Namespace Member Variables","text":""},{"location":"api/namespace_member_variables/#b","title":"b","text":"
  • body_node_get_friction_coeff (robot_dart)
  • body_node_get_restitution_coeff (robot_dart)
  • body_node_set_friction_coeff (robot_dart)
  • body_node_set_restitution_coeff (robot_dart)
"},{"location":"api/namespace_member_typedefs/","title":"Namespace Member Typedefs","text":""},{"location":"api/namespace_member_typedefs/#c","title":"c","text":"
  • Camera3D (robot_dart::gui::magnum)
"},{"location":"api/namespace_member_typedefs/#o","title":"o","text":"
  • Object3D (robot_dart::gui::magnum)
"},{"location":"api/namespace_member_typedefs/#s","title":"s","text":"
  • Scene3D (robot_dart::gui::magnum)
"},{"location":"api/namespace_member_enums/","title":"Namespace Member Enums","text":""},{"location":"api/namespace_member_enums/#g","title":"g","text":"
  • gs (robot_dart::gui::magnum::gs)
"},{"location":"api/functions/","title":"Functions","text":""},{"location":"api/functions/#r","title":"r","text":"
  • robot_dart_initialize_magnum_resources (base_graphics.hpp)
"},{"location":"api/functions/#s","title":"s","text":"
  • stbi_flip_vertically_on_write (stb_image_write.h)
  • stbi_write_bmp (stb_image_write.h)
  • stbi_write_bmp_to_func (stb_image_write.h)
  • stbi_write_hdr (stb_image_write.h)
  • stbi_write_hdr_to_func (stb_image_write.h)
  • stbi_write_jpg (stb_image_write.h)
  • stbi_write_jpg_to_func (stb_image_write.h)
  • stbi_write_png (stb_image_write.h)
  • stbi_write_png_to_func (stb_image_write.h)
  • stbi_write_tga (stb_image_write.h)
  • stbi_write_tga_to_func (stb_image_write.h)
"},{"location":"api/macros/","title":"Macros","text":""},{"location":"api/macros/#g","title":"g","text":"
  • get_gl_context (base_application.hpp)
  • get_gl_context_with_sleep (base_application.hpp)
"},{"location":"api/macros/#m","title":"m","text":"
  • M_PIf (utils.hpp)
"},{"location":"api/macros/#r","title":"r","text":"
  • release_gl_context (base_application.hpp)
  • ROBOT_DART_ASSERT (utils.hpp)
  • ROBOT_DART_EXCEPTION_ASSERT (utils.hpp)
  • ROBOT_DART_EXCEPTION_INTERNAL_ASSERT (utils.hpp)
  • ROBOT_DART_INTERNAL_ASSERT (utils.hpp)
  • ROBOT_DART_SHOW_WARNINGS (utils.hpp)
  • ROBOT_DART_UNUSED_VARIABLE (utils.hpp)
  • ROBOT_DART_WARNING (utils.hpp)
"},{"location":"api/macros/#s","title":"s","text":"
  • STB_IMAGE_WRITE_IMPLEMENTATION (helper.cpp)
  • STBIWDEF (stb_image_write.h)
"},{"location":"api/variables/","title":"Variables","text":""},{"location":"api/variables/#s","title":"s","text":"
  • stbi_write_force_png_filter (stb_image_write.h)
  • stbi_write_func (stb_image_write.h)
  • stbi_write_png_compression_level (stb_image_write.h)
  • stbi_write_tga_with_rle (stb_image_write.h)
"},{"location":"api/links/","title":"Links","text":"
  • Related Pages
  • Modules
  • Class List
  • Namespace ListNamespace List
  • Namespace Members
  • Namespace Member Functions
  • Namespace Member Variables
  • Namespace Member Typedefs
  • Namespace Member Enumerations
  • Class Index
  • Class Hierarchy
  • Class Members
  • Class Member Functions
  • Class Member Variables
  • Class Member Typedefs
  • Class Member Enumerations
  • Files
  • File Variables
  • File Functions
  • File Macros
"}]} \ 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:

  • a physics engine (DART)
  • an optional graphics engine (Magnum)
  • a few sensor classes (IMU, force/torque sensors, cameras, etc.)
  • a curated URDF library
  • ... and a few useful features to make the life of roboticists/researchers easier

"},{"location":"#main-features","title":"Main Features","text":"
  • Modern C++ code that makes it easy to develop environments and applications
  • Fast and reliable simulation of robotic mechanisms and their interactions (through the DART physics engine)
  • A structured Robot class that enables a unified creation and access to all important values: in RobotDART you can load any robot description file (URDF, SDF, SKEL, and MuJoCo files) with the same command, and all robot measurements can be queried without using any DART code
  • A generic RobotControl class that enables fast prototyping of any type of controller
  • A generic Sensor class that allows the creation of any kind of sensor
  • A growing list of already implemented sensors, that includes 6-axis ForceTorque, IMU, RGB, and RGB-D sensors
  • A simulation class (RobotDARTSimu) that handles multiple robots and sensors, and allows for step-by-step simulation
  • A growing list of supported robots along with edited and optimized models to be used with RobotDART (see the robots page for details and examples):
    • PAL Talos humanoid
    • Franka Emika Panda
    • KUKA LBR Iiwa (14kg version)
    • IIT iCub humanoid (without hands)
    • Unitree A1 quadruped robot
    • Dynamixel-based 6-legged robot
    • A simple arm for educational purposes
    • and you can use any URDF
  • A custom graphical interface built on top of Magnum that allows generic customization
  • Support for windowless OpenGL context creation (even in parallel threads!) to allow for camera sensor usage even in parallel jobs running on clusters
  • Support for video recording in simulation time (i.e., not affected by delays of simulator and/or graphics) for visualization or debugging purposes
  • Full-featured Python bindings for fast prototyping
  • RobotDART runs on any Linux distribution and Mac OS
"},{"location":"#what-robotdart-is-not","title":"What RobotDART is not","text":"
  • RobotDART is primarily intended to be non-interactive (run a simulation, record/view the result),
  • Interaction is limited to changing the view and your own code. No GUI for adding objects or interactively build an environment,
  • RobotDART is not optimized for wheeled robots,
  • RobotDART is not optimized for simulating complex (e.g., mountain-like) terrains.
"},{"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.

  • We first include the appropriate files:
C++Python
#include <robot_dart/robot_dart_simu.hpp>\n\n#ifdef GRAPHIC\n#include <robot_dart/gui/magnum/graphics.hpp>\n#endif\n
import RobotDART as rd\n
  • We then load our hexapod robot:
C++Python
auto robot = std::make_shared<robot_dart::Robot>(\"pexod.urdf\");\n
robot = rd.Robot(\"pexod.urdf\");\n
  • We need to place it above the floor to avoid collision (we can use RobotDART's helpers ;)):
C++Python
robot->set_base_pose(robot_dart::make_tf({0., 0., 0.2}));\n
# pose is a 6D vector (first 3D orientation in angle-axis and last 3D translation)\nrobot.set_base_pose([0., 0., 0., 0., 0., 0.2])\n
  • We can now create the simulation object and add the robot and the floor:
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
  • If needed or wanted, we can add a graphics component to visualize the scene:
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
  • Once everything is configured, we can run our simulation for a few seconds:
C++Python
simu.run(10.);\n
simu.run(10.)\n
  • Here's how it looks:

"},{"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:

  • Install Magnum. See the installation page for details.
  • Create and set a graphics object in the simulation object. Here's an example:
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 (1) of what the main or any other camera \"sees\", you need to call the function record_video(path) of the graphics class:

  1. Make sure that you have ffmpeg installed on your system.
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\n    0.01f, // near plane\n    60.0f, // field of view\n    600, // width\n    400 // height\n);\n
camera.camera().set_camera_params(5., #far plane\n                                  0.01, #near plane\n                                  60.0, # field of view\n                                  600, # width\n                                  400) #height\n

You can find a complete example at cameras.cpp and cameras.py.

"},{"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\n// We can change the configuration for shadows\nconfiguration.shadowed = true;\nconfiguration.transparent_shadows = true;\nconfiguration.shadow_map_size = 1024;\n\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\n// Some extra configuration for the main camera\nconfiguration.draw_main_camera = true;\nconfiguration.draw_debug = true;\nconfiguration.draw_text = true;\n\n// We can also change the background color [default=black]\nconfiguration.bg_color = Eigen::Vector4d{1.0, 1.0, 1.0, 1.0};\n\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\n# We can change the configuration for shadows\nconfiguration.shadowed = True\nconfiguration.transparent_shadows = True\nconfiguration.shadow_map_size = 1024\n\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\n#  Some extra configuration for the main camera\nconfiguration.draw_main_camera = True\nconfiguration.draw_debug = True\nconfiguration.draw_text = True\n\n# We can also change the background color [default = black]\nconfiguration.bg_color = [1., 1., 1., 1.]\n\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\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\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\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\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);\n// add the controller to the robot, with a default weight of 1.0\nrobot->add_controller(controller1);\n
controller1 = rd.SimpleControl(ctrl)\n# add the controller to the robot, with a default weight of 1.0\nrobot.add_controller(controller1)\n

Robot control

C++Python
class MyController : public robot_dart::control::RobotControl {\npublic:\n    MyController() : robot_dart::control::RobotControl() {}\n\n    MyController(const Eigen::VectorXd& ctrl, bool full_control) : robot_dart::control::RobotControl(ctrl, full_control) {}\n    MyController(const Eigen::VectorXd& ctrl, const std::vector<std::string>& dof_names) : robot_dart::control::RobotControl(ctrl, dof_names) {}\n\n    void configure() override\n    {\n        _active = true;\n    }\n\n    Eigen::VectorXd calculate(double) override\n    {\n        auto robot = _robot.lock();\n        Eigen::VectorXd cmd = 100. * (_ctrl - robot->positions(_controllable_dofs));\n        return cmd;\n    }\n    std::shared_ptr<robot_dart::control::RobotControl> clone() const override\n    {\n        return std::make_shared<MyController>(*this);\n    }\n};\n
class MyController(rd.RobotControl):\n    def __init__(self, ctrl, full_control):\n        rd.RobotControl.__init__(self, ctrl, full_control)\n\n    def __init__(self, ctrl, controllable_dofs):\n        rd.RobotControl.__init__(self, ctrl, controllable_dofs)\n\n    def configure(self):\n        self._active = True\n\n    def calculate(self, t):\n        target = np.array([self._ctrl])\n        cmd = 100*(target-self.robot().positions(self._controllable_dofs))\n        return cmd[0]\n\n    # TO-DO: This is NOT working at the moment!\n    def clone(self):\n        return 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()) {\n    std::cout << \"Self collision is not enabled\" << std::endl;\n    // set self collisions to true and adjacent collisions to false\n    robot->set_self_collision(true, false);\n}\n
if(not robot.self_colliding()):\n    print(\"Self collision is not enabled\")\n    # set self collisions to true and adjacent collisions to false\n    robot.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\n// Get Joint Velocities\nauto joint_vels = robot->velocities();\n\n// Get Joint Accelerations\nauto joint_accs = robot->accelerations();\n\n// Get link_name(str) Transformation matrix with respect to the world frame.\nauto eef_tf = robot->body_pose(link_name);\n\n// Get translation vector from transformation matrix\nauto eef_pos = eef_tf.translation();\n\n// Get rotation matrix from tranformation matrix\nauto eef_rot = eef_tf.rotation();\n\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\n// Get link_name 6d velocity vector [angular, cartesian]\nauto eef_vel = robot->body_velocity(link_name);\n\n// Get link_name 6d acceleration vector [angular, cartesian]\nauto eef_acc = robot->body_acceleration(link_name);\n\n// Jacobian targeting the origin of link_name(str)\nauto jacobian = robot->jacobian(link_name);\n\n// Jacobian time derivative\nauto jacobian_deriv = robot->jacobian_deriv(link_name);\n\n// Center of Mass Jacobian\nauto com_jacobian = robot->com_jacobian();\n\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\n# Get Joint Velocities\njoint_vels = robot.velocities()\n\n# Get Joint Accelerations\njoint_accs = robot.accelerations()\n\n# Get link_name(str) Transformation matrix with respect to the world frame.\neef_tf = robot.body_pose(link_name)\n\n# Get translation vector from transformation matrix\neef_pos = eef_tf.translation()\n\n# Get rotation matrix from tranformation matrix\neef_rot = eef_tf.rotation()\n\n# Get link_name 6d pose vector [logmap(eef_tf.linear()), eef_tf.translation()]\neef_pose_vec = robot.body_pose_vec(link_name)\n\n# Get link_name 6d velocity vector [angular, cartesian]\neef_vel = robot.body_velocity(link_name)\n\n# Get link_name 6d acceleration vector [angular, cartesian]\neef_acc = robot.body_acceleration(link_name)\n\n# Jacobian targeting the origin of link_name(str)\njacobian = robot.jacobian(link_name)\n\n# Jacobian time derivative\njacobian_deriv = robot.jacobian_deriv(link_name)\n\n# Center of Mass Jacobian\ncom_jacobian = robot.com_jacobian()\n\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\n// Get link's mass\nauto eef_mass = robot->body_mass(link_name);\n\n// Mass Matrix of robot\nauto mass_matrix = robot->mass_matrix();\n\n// Inverse of Mass Matrix\nauto inv_mass_matrix = robot->inv_mass_matrix();\n\n// Augmented Mass matrix\nauto aug_mass_matrix = robot->aug_mass_matrix();\n\n// Inverse of Augmented Mass matrix\nauto inv_aug_mass_matrix = robot->inv_aug_mass_matrix();\n\n// Coriolis Force vector\nauto coriolis = robot->coriolis_forces();\n\n// Gravity Force vector\nauto gravity = robot->gravity_forces();\n\n// Combined vector of Coriolis Force and Gravity Force\nauto coriolis_gravity = robot->coriolis_gravity_forces();\n\n// Constraint Force Vector\nauto constraint_forces = robot->constraint_forces();\n
# Get Joint Forces\njoint_forces = robot.forces()\n\n# Get link's mass\neef_mass = robot.body_mass(link_name)\n\n# Mass Matrix of robot\nmass_matrix = robot.mass_matrix()\n\n# Inverse of Mass Matrix\ninv_mass_matrix = robot.inv_mass_matrix()\n\n# Augmented Mass matrix\naug_mass_matrix = robot.aug_mass_matrix()\n\n# Inverse of Augmented Mass matrix\ninv_aug_mass_matrix = robot.inv_aug_mass_matrix()\n\n# Coriolis Force vector\ncoriolis = robot.coriolis_forces()\n\n# Gravity Force vector\ngravity = robot.gravity_forces()\n\n# Combined vector of Coriolis Force and Gravity Force\ncoriolis_gravity = robot.coriolis_gravity_forces()\n\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\n// Modify Velocity Limits\n\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\n// Modify Force Limits\n\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\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\n# Modify Velocity Limits\nvel_upper_lims = np.array([1.5, 1.5, 1.5, 1.5, 1.5, 1.5, 1.5])\n\nrobot.set_velocity_upper_limits(vel_upper_lims, dof_names)\nrobot.set_velocity_lower_limits(-1*vel_upper_lims, dof_names)\n\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\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\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\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\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\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())\n    tq_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():\n    simu.add_sensor(rd.sensor.Torque(robot, joint, 1000))\n    tq_sensors[ct] = simu.sensors()[-1]\n    ct += 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)\n    torques_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:\n    torques_measure[ct] = tq_sens.torques()\n    ct += 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())\n    f_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():\n    simu.add_sensor(rd.sensor.ForceTorque(\n        robot, joint, 1000, \"parent_to_child\"))\n    f_tq_sensors[ct] = simu.sensors()[-1]\n    print(f_tq_sensors)\n    ct += 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) {\n    ft_torques_measure.block<1, 3>(ct, 0) = f_tq_sens->torque();\n    ft_forces_measure.block<1, 3>(ct, 0) = f_tq_sens->force();\n    ft_wrench_measure.block<1, 6>(ct, 0) = f_tq_sens->wrench();\n    ct++;\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:\n    ft_torques_measure[ct, :] = f_tq_sens.torque()\n    ft_forces_measure[ct, :] = f_tq_sens.force()\n    ft_wrench_measure[ct, :] = f_tq_sens.wrench()\n    ct += 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))),\n    imu_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():\n    simu.add_sensor(rd.sensor.IMU(\n        rd.sensor.IMUConfig(robot.body_node(body_node), 1000)))\n    imu_sensors[ct] = simu.sensors()[-1]\n    ct += 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) {\n    imu_angular_positions_measure.block<1, 3>(ct, 0) = imu_sens->angular_position_vec();\n    imu_angular_velocities_measure.block<1, 3>(ct, 0) = imu_sens->angular_velocity();\n    imu_linear_acceleration_measure.block<1, 3>(ct, 0) = imu_sens->linear_acceleration();\n    ct++;\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:\n    imu_angular_positions_measure[ct,:] = imu_sens.angular_position_vec()\n    imu_angular_velocities_measure[ct, :] = imu_sens.angular_velocity()\n    imu_linear_acceleration_measure[ct,:] = imu_sens.linear_acceleration()\n    ct += 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:

  • Minimize the overhead of loading robots (it happens only once!) or cloning robots (it never happens)
  • Make sure that your robots are \"clean\" once released from each thread
  • Focus on the important stuff rather than handling robots and threads

Let's see a more practical example:

  • First we need to include the proper header:
C++
#include <robot_dart/robot_pool.hpp>\n
  • Then we create a creator function and the pool object:
C++
namespace pool {\n    // This function should load one robot: here we load Talos\n    inline std::shared_ptr<robot_dart::Robot> robot_creator()\n    {\n        return std::make_shared<robot_dart::robots::Talos>();\n    }\n\n    // To create the object we need to pass the robot_creator function and the number of maximum parallel threads\n    robot_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.

  • Next, we create a few threads that utilize the robots (in your code you might be using OpenMP or TBB):
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)\n    threads[i] = std::thread(eval_robot, i); // eval_robot is the function that uses the robot\n
  • An example evaluation function:
C++
inline void eval_robot(int i)\n{\n    // We get one available robot\n    auto robot = pool::robot_pool.get_robot();\n    std::cout << \"Robot \" << i << \" got [\" << robot->skeleton() << \"]\" << std::endl;\n\n    /// --- some robot_dart code ---\n    simulate_robot(robot);\n    // --- do something with the result\n\n    std::cout << \"End of simulation \" << i << std::endl;\n\n    // CRITICAL : free your robot !\n    pool::robot_pool.free_robot(robot);\n\n    std::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>();\n\nstd::vector<std::thread> workers;\n\n// Set maximum number of parallel GL contexts (this is GPU-dependent)\nrobot_dart::gui::magnum::GlobalData::instance()->set_max_contexts(4);\n\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++) {\n    workers.push_back(std::thread([&] {\n        mutex.lock();\n        size_t index = id++;\n        mutex.unlock();\n\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\n        get_gl_context_with_sleep(gl_context, 20); // this call will sleep 20ms between each failed query\n\n        // Do the simulation\n        auto robot = global_robot->clone();\n\n        robot_dart::RobotDARTSimu simu(0.001);\n\n        Eigen::VectorXd ctrl = robot_dart::make_vector({0., M_PI / 3., 0., -M_PI / 4., 0., 0., 0.});\n\n        auto controller = std::make_shared<robot_dart::control::PDControl>(ctrl);\n        robot->add_controller(controller);\n        controller->set_pd(300., 50.);\n\n        // Magnum graphics\n        robot_dart::gui::magnum::GraphicsConfiguration configuration = robot_dart::gui::magnum::WindowlessGraphics::default_configuration();\n\n        configuration.width = 1024;\n        configuration.height = 768;\n        auto graphics = std::make_shared<robot_dart::gui::magnum::WindowlessGraphics>(configuration);\n        simu.set_graphics(graphics);\n        // Position the camera differently for each thread to visualize the difference\n        graphics->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\n\n        simu.add_robot(robot);\n        simu.run(6);\n\n        // Save the image for verification\n        robot_dart::gui::save_png_image(\"camera_\" + std::to_string(index) + \".png\",\n            graphics->image());\n\n        // Release the GL context for another thread to use\n        release_gl_context(gl_context);\n    }));\n}\n\n// Wait for all the workers\nfor (size_t i = 0; i < workers.size(); i++) {\n    workers[i].join();\n}\n
robot = rd.Robot(\"arm.urdf\", \"arm\", False)\nrobot.fix_to_world()\n\ndef test():\n    pid = os.getpid()\n    ii = pid%15\n\n    # create the controller\n    pdcontrol = rd.PDControl([0.0, 1.0, -1.5, 1.0], False)\n\n    # clone the robot\n    grobot = robot.clone()\n\n    # add the controller to the robot\n    grobot.add_controller(pdcontrol, 1.)\n    pdcontrol.set_pd(200., 20.)\n\n    # create the simulation object\n    simu = rd.RobotDARTSimu(0.001)\n\n    # set the graphics\n    graphics = rd.gui.WindowlessGraphics()\n    simu.set_graphics(graphics)\n\n    graphics.look_at([0.4 * ii, 3.5 - ii * 0.1, 2.], [0., 0., 0.25], [0., 0., 1.])\n\n    # add the robot and the floor\n    simu.add_robot(grobot)\n    simu.add_checkerboard_floor()\n\n    # run\n    simu.run(20.)\n\n    # save last frame for visualization purposes\n    img = graphics.image()\n    rd.gui.save_png_image('camera-' + str(ii) + '.png', img)\n\n# helper function to run in parallel\ndef runInParallel(N):\n  proc = []\n  for 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\n    p = Process(target=rd.gui.run_with_gl_context, args=(test, 20))\n    p.start()\n    proc.append(p)\n  for p in proc:\n    p.join()\n\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:

"},{"location":"faq/#prerequisites","title":"Prerequisites:","text":"
  • Ensure RobotDart and Magnum are installed.
  • If RobotDart and Magnum are not installed in standard locations, you can either:
  • Set the CMAKE_PREFIX_PATH environment variable:
    export CMAKE_PREFIX_PATH=/opt/robot_dart:/opt/magnum\n
  • Or, specify the paths directly when running cmake:
    cmake -DRobotDART_DIR=/opt/robot_dart -DMagnum_DIR=/opt/magnum ..\n
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)\n\nadd_executable(robot_dart_example example.cpp)\n\ntarget_link_libraries(robot_dart_example\n   RobotDART::Simu\n)\n\nif(RobotDART_Magnum_FOUND)\n  add_executable(robot_dart_example_graphics example.cpp)\n  target_link_libraries(robot_dart_example_graphics\n    RobotDART::Simu\n    RobotDART::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":"
  • Ubuntu (it should work on versions >= 14.04) or OSX
  • Eigen3
  • DART, http://dartsim.github.io/
"},{"location":"install/#optional","title":"Optional","text":"
  • Boost (for unit tests)
  • Magnum (for graphics), https://github.com/mosra/magnum
  • ffmpeg (for video recording) - please install using your favorite package manager
"},{"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\n# Installation of Magnum Python Bindings (some examples use them but this is optional)\ncd /path/to/tmp/folder\ngit clone https://github.com/mosra/magnum-bindings.git\ncd magnum-bindings\nmkdir build && cd build\ncmake .. -DMAGNUM_WITH_PYTHON=ON\nmake -j\ncd src/python\nsudo python3 setup.py install\n

For OSX you can also install Magnum via brew: brew install --HEAD mosra/magnum/corrade && brew install --HEAD mosra/magnum/magnum && brew install --HEAD mosra/magnum/magnum-plugins && brew install --HEAD mosra/magnum/magnum-integration --with-dartsim

"},{"location":"install/#compilation-and-running-the-examples","title":"Compilation and running the examples","text":"

The compilation of the library is straight-forward:

  • retrieve the code, for instance with git clone https://github.com/resibots/robot_dart.git
  • cd /path/to/repo/root
  • ./waf configure
  • ./waf

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:

  • ./waf install

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:

  • ./waf configure --prefix=/path/to/install/dir --shared
  • ./waf install

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:

  • retrieve the code, for instance with git clone https://github.com/resibots/robot_dart.git
  • cd /path/to/repo/root
  • ./waf configure --python (--python enables the python bindings)
  • ./waf
  • Install the library (including the python bindings) as before (no change is needed)
  • Depending on your installation directory you might need to update your PYTHONPATH, e.g. export PYTHONPATH=$PYTHONPATH:/usr/local/lib/python3.10/site-packages/

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

  • cd /path/to/repo/root
  • python src/python/example.py or python src/python/example_parallel.py
"},{"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":"pubs/","title":"Publications using RobotDART","text":""},{"location":"pubs/#scientific-publications-indicative-list-ordered-by-date","title":"Scientific Publications (indicative list, ordered by date)","text":""},{"location":"pubs/#scientific-publications-indicative-list-ordered-by-date_1","title":"Scientific Publications (indicative list, ordered by date)","text":"
  1. Anne, T. and Mouret, J.B., 2024. Parametric-Task MAP-Elites. Proceedings of the Genetic and Evolutionary Computation Conference (GECCO). (pdf)

  2. Ivaldi, S. and Ghini, E., 2023, June. Teleoperating a robot for removing asbestos tiles on roofs: insights from a pilot study. In 2023 IEEE International Conference on Advanced Robotics and Its Social Impacts (ARSO) (pp. 128-133). IEEE. (pdf)

  3. Khadivar, F., Chatzilygeroudis, K. and Billard, A., 2023. Self-correcting quadratic programming-based robot control. IEEE Transactions on Systems, Man, and Cybernetics: Systems. (pdf)

  4. Souza, A.O., Grenier, J., Charpillet, F., Maurice, P. and Ivaldi, S., 2023, June. Towards data-driven predictive control of active upper-body exoskeletons for load carrying. In 2023 IEEE International Conference on Advanced Robotics and Its Social Impacts (ARSO) (pp. 59-64). IEEE. (pdf)

  5. Chatzilygeroudis, K.I., Tsakonas, C.G. and Vrahatis, M.N., 2023, July. Evolving Dynamic Locomotion Policies in Minutes. In 2023 14th International Conference on Information, Intelligence, Systems & Applications (IISA) (pp. 1-8). IEEE. (pdf)

  6. Tsakonas, C.G. and Chatzilygeroudis, K.I., 2023, July. Effective Skill Learning via Autonomous Goal Representation Learning. In 2023 14th International Conference on Information, Intelligence, Systems & Applications (IISA) (pp. 1-8). IEEE. (pdf)

  7. Totsila, D., Chatzilygeroudis, K., Hadjivelichkov, D., Modugno, V., Hatzilygeroudis, I. and Kanoulas, D., 2023. End-to-End Stable Imitation Learning via Autonomous Neural Dynamic Policies. Life-Long Learning with Human Help (L3H2) Workshop, ICRA. (pdf)

  8. Allard, M., Smith, S.C., Chatzilygeroudis, K., Lim, B. and Cully, A., 2023. Online damage recovery for physical robots with hierarchical quality-diversity. ACM Transactions on Evolutionary Learning, 3(2), pp.1-23. (pdf)

  9. Anne, T., Dalin, E., Bergonzani, I., Ivaldi, S. and Mouret, J.B., 2022. First do not fall: learning to exploit a wall with a damaged humanoid robot. IEEE Robotics and Automation Letters, 7(4), pp.9028-9035. (pdf)

  10. Mayr, M., Ahmad, F., Chatzilygeroudis, K., Nardi, L. and Krueger, V., 2022, December. Skill-based multi-objective reinforcement learning of industrial robot tasks with planning and knowledge integration. In 2022 IEEE International Conference on Robotics and Biomimetics (ROBIO) (pp. 1995-2002). IEEE. (pdf)

  11. Grillotti, L. and Cully, A., 2022. Unsupervised behavior discovery with quality-diversity optimization. IEEE Transactions on Evolutionary Computation, 26(6), pp.1539-1552. (pdf)

  12. Lim, B., Grillotti, L., Bernasconi, L. and Cully, A., 2022, May. Dynamics-aware quality-diversity for efficient learning of skill repertoires. In 2022 International Conference on Robotics and Automation (ICRA) (pp. 5360-5366). IEEE. (pdf)

  13. Tsinganos, K., Chatzilygeroudis, K., Hadjivelichkov, D., Komninos, T., Dermatas, E. and Kanoulas, D., 2022. Behavior policy learning: Learning multi-stage tasks via solution sketches and model-based controllers. Frontiers in Robotics and AI, 9, p.974537. (pdf)

  14. d'Elia, E., Mouret, J.B., Kober, J. and Ivaldi, S., 2022, October. Automatic tuning and selection of whole-body controllers. In 2022 IEEE/RSJ International Conference on Intelligent Robots and Systems (IROS) (pp. 12935-12941). IEEE. (pdf)

  15. Mayr, M., Hvarfner, C., Chatzilygeroudis, K., Nardi, L. and Krueger, V., 2022, August. Learning skill-based industrial robot tasks with user priors. In 2022 IEEE 18th International Conference on Automation Science and Engineering (CASE) (pp. 1485-1492). IEEE. (pdf)

  16. Allard, M., Smith, S.C., Chatzilygeroudis, K. and Cully, A., 2022, July. Hierarchical quality-diversity for online damage recovery. In Proceedings of the Genetic and Evolutionary Computation Conference (pp. 58-67). (pdf)

  17. Mayr, M., Ahmad, F., Chatzilygeroudis, K., Nardi, L. and Krueger, V., 2022. Combining planning, reasoning and reinforcement learning to solve industrial robot tasks. 2nd Workshop on Trends and Advances in Machine Learning and Automated Reasoning for Intelligent Robots and Systems, IROS. (pdf)

  18. Cully, A., 2021, June. Multi-emitter map-elites: improving quality, diversity and data efficiency with heterogeneous sets of emitters. In Proceedings of the Genetic and Evolutionary Computation Conference (pp. 84-92). (pdf)

  19. Mayr, M., Chatzilygeroudis, K., Ahmad, F., Nardi, L. and Krueger, V., 2021, September. Learning of parameters in behavior trees for movement skills. In 2021 IEEE/RSJ International Conference on Intelligent Robots and Systems (IROS) (pp. 7572-7579). IEEE. (pdf)

  20. Penco, L., Hoffman, E.M., Modugno, V., Gomes, W., Mouret, J.B. and Ivaldi, S., 2020. Learning robust task priorities and gains for control of redundant robots. IEEE Robotics and Automation Letters, 5(2), pp.2626-2633. (pdf)

  21. Flageat, M. and Cully, A., 2020, July. Fast and stable MAP-Elites in noisy domains using deep grids. In Artificial Life Conference Proceedings 32 (pp. 273-282). One Rogers Street, Cambridge, MA 02142-1209, USA journals-info@ mit. edu: MIT Press. (pdf)

  22. Paul, S., Chatzilygeroudis, K., Ciosek, K., Mouret, J.B., Osborne, M.A. and Whiteson, S., 2020. Robust reinforcement learning with Bayesian optimisation and quadrature. Journal of Machine Learning Research, 21(151), pp.1-31. (pdf)

  23. Chatzilygeroudis, K., Vassiliades, V. and Mouret, J.B., 2018. Reset-free trial-and-error learning for robot damage recovery. Robotics and Autonomous Systems, 100, pp.236-250. (pdf)

  24. Pautrat, R., Chatzilygeroudis, K. and Mouret, J.B., 2018, May. Bayesian optimization with automatic prior selection for data-efficient direct policy search. In 2018 IEEE International Conference on Robotics and Automation (ICRA) (pp. 7571-7578). IEEE. (pdf)

  25. Chatzilygeroudis, K. and Mouret, J.B., 2018, May. Using parameterized black-box priors to scale up model-based policy search for robotics. In 2018 IEEE international conference on robotics and automation (ICRA) (pp. 5121-5128). IEEE. (pdf)

  26. Paul, S., Chatzilygeroudis, K., Ciosek, K., Mouret, J.B., Osborne, M. and Whiteson, S., 2018, April. Alternating optimisation and quadrature for robust control. In Proceedings of the AAAI Conference on Artificial Intelligence (Vol. 32, No. 1). (pdf)

  27. Kaushik, R., Chatzilygeroudis, K. and Mouret, J.B., 2018, October. Multi-objective model-based policy search for data-efficient learning with sparse rewards. In Conference on Robot Learning (pp. 839-855). PMLR. (pdf)

  28. Vassiliades, V., Chatzilygeroudis, K. and Mouret, J.B., 2017. Using centroidal voronoi tessellations to scale up the multidimensional archive of phenotypic elites algorithm. IEEE Transactions on Evolutionary Computation, 22(4), pp.623-630. (pdf)

  29. Mouret, J.B. and Chatzilygeroudis, K., 2017, July. 20 years of reality gap: a few thoughts about simulators in evolutionary robotics. In Proceedings of the genetic and evolutionary computation conference companion (pp. 1121-1124). (pdf)

  30. Papaspyros, V., Chatzilygeroudis, K., Vassiliades, V. and Mouret, J.B., 2016. Safety-aware robot damage recovery using constrained bayesian optimization and simulated priors. BayesOpt '16: Proceedings of the International Workshop \"Bayesian Optimization: Black-box Optimization and Beyond\", NeurIPS. (pdf)

  31. Chatzilygeroudis, K., Cully, A. and Mouret, J.B., 2016. Towards semi-episodic learning for robot damage recovery. AILTA '16: Proceedings of the International Workshop \"AI for Long-term Autonomy\", ICRA. (pdf)

"},{"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/#video-recording-to-file","title":"Video recording to file","text":"

ffmpeg is needed for enabling the video recording capabilities. You can install this at any time using your favorite package manager (e.g. apt for Ubuntu or brew for Mac OSX).

"},{"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:

  • git clone https://github.com/resibots/robot_dart.git
  • cd robot_dart
  • ./scripts/install_ubuntu.sh

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 CMAKE_PREFIX_PATH=/opt/robot_dart:/opt/magnum\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":"

To quickly install RobotDART on Mac OSX, we just need to run ./scripts/install_osx.sh from the root of the repo. In more detail:

  • git clone https://github.com/resibots/robot_dart.git
  • cd robot_dart
  • ./scripts/install_osx.sh

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 CMAKE_PREFIX_PATH=/opt/robot_dart:/opt/magnum\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
  1. You can run python --version to see your version. We only keep the major.minor (ignoring the patch version)\u00a0\u21a9\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()):

  • First check in the current directory
  • If not found, check in current_directory/utheque
  • If not found, check in $ROBOT_DART_PATH/utheque
  • If not found, check in the robot dart installation path/robots (e.g., /usr/share/utheque or $HOME/share/utheque)
  • Otherwise, report failure

utheque is a separate header-only library that gets installed together with RobotDART (or even alone), that can be used in libraries that do not want to interfere with RobotDART and use the curated URDF files.

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

Talos is a humanoid robot made by PAL Robotics.

  • Datasheet: [pdf]
  • 32 degrees of freedom (6 for each leg, 7 for each arm, 2 for the waist, 2 for the neck, 1 for each gripper)
  • 175 cm / 95 kg
  • IMU in the torso
  • Torque sensors in all joints except head, wrist and gripper (22 torque sensors total)
  • 1 force/torque sensor in each ankle
  • 1 force/torque sensor in each wrist

We have two URDF files:

  • utheque/talos/talos.urdf :
    • accurate (simplified but made of polygons) collision meshes
    • mimic joints for the gripper
    • Not compatible the DART collision detector (you need to use FCL collision detector - shipped with DART)
    • URDF: [talos.urdf]
    • Example: [talos.cpp] [talos.py]

Load Talos

C++
auto robot = std::make_shared<robot_dart::robots::Talos>();\n
Python
robot = rd.Talos()\n
  • utheque/talos/talos_fast.urdf:
    • no collision except for the feet, which are approximated by boxes
    • grippers are fixed (no movement is allowed)
    • compatible with the DART collision detector
    • URDF: [talos_fast.urdf]
    • Example: [talos_fast.cpp]

talos_fast.urdf is faster because it makes it possible to use the DART collision detector (and has much collision shapes). You should prefer it except if you want to use the grippers (e.g., for manipulation) or are working on self-collisions.

  • utheque/talos/talos_fast_collision.urdf:
    • all bodies are approximated by boxes
    • grippers are fixed (no movement is allowed)
    • compatible with the DART collision detector
    • URDF: [talos_fast_collision.urdf]
    • Example: [talos_fast_collision.cpp] [talos_fast_collision.py]

talos_fast_collision.urdf is faster than talos.urdf but slower than talos_fast.urdf. You should use it when you need more detail collisions but faster simulation times.

Load Talos Fast

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.

  • Datasheet: [pdf]
  • 7 degrees of freedom
  • Can be controlled in torque
  • 18 kg
  • workspace: 855 mm (horizontal), 1190 mm (vertical)
  • URDF: [franka.urdf]
  • Example: [franka.cpp] [franka.py] The URDF includes the gripper.

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.

  • Datasheet: [pdf]
  • We implement the 14 kg version
  • 29.5 kg
  • 7 degrees of freedom
  • URDF: [iiwa.urdf]
  • Example: [iiwa.cpp] [iiwa.py]

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.

  • Datasheet (rev 2.3) [pdf]
  • 6 force/torque sensors (upper arms, upper legs, ankles)
  • IMU in the head
  • We do to simulate the skin
  • We do not simulate the hands
  • Our model is close to the Inria's iCub, but it has not been checked in detail.
  • URDF: [icub.urdf]
  • Example [icub.cpp] [icub.py]

Please note that the mesh files (.glb) require assimp 5.x (and not assimp4.x usually shipped with ROS). If you cannot load the URDF, please check your assimp version.

Load iCub

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

  • IMU in the torso
  • We do not simulate the foot pressure sensors (yet)
  • One can easily add a depth camera on the head
  • URDF: [a1.urdf]
  • Example [a1.cpp] [a1.py]

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

  • 6 legs, 3 degrees of freedom for each leg (18 degrees of freedom)
  • simple URDF (no meshes)
  • URDF: [pexod.urdf]
  • Example: [hexapod.cpp] [hexapod.py]

Load 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":"
  • A simple arm for educational or debugging purposes
  • 5 degrees of freedom
  • simple URDF (no meshes)
  • URDF: [arm.urdf]
  • Example: [arm.cpp] [arm.py]

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');\n    auto 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\")]\n    your_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:

  • namespace Magnum
    • namespace GL
    • namespace Platform
    • namespace SceneGraph
    • namespace Shaders
      • namespace Implementation
  • namespace TinyProcessLib
  • namespace dart
    • namespace collision
    • namespace dynamics
  • namespace robot_dart
    • class Assertion
    • class Robot
    • class RobotDARTSimu
    • class RobotPool
    • class Scheduler
    • namespace collision_filter
      • class BitmaskContactFilter
        • struct Masks
    • namespace control
      • class PDControl
      • class PolicyControl
      • class RobotControl
      • class SimpleControl
    • namespace detail
    • namespace gui
      • class Base
      • struct DepthImage
      • struct GrayscaleImage
      • struct Image
      • namespace magnum
        • class BaseApplication
        • class BaseGraphics
        • 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
        • namespace gs
          • class Camera
          • class CubeMap
          • class CubeMapColor
          • class Light
          • class Material
          • class PhongMultiLight
          • class ShadowMap
          • class ShadowMapColor
        • namespace sensor
          • class Camera
    • namespace robots
      • 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
    • namespace sensor
      • class ForceTorque
      • class IMU
      • struct IMUConfig
      • class Sensor
      • class Torque
    • namespace simu
      • struct GUIData
      • struct TextData
  • namespace gs
  • struct RobotData
  • namespace std
"},{"location":"api/files/","title":"File List","text":"

Here is a list of all files with brief descriptions:

  • dir robot_dart
    • file gui_data.hpp
    • file robot.cpp
    • file robot.hpp
    • dir control
      • 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
    • dir gui
      • file base.hpp
      • file helper.cpp
      • file helper.hpp
      • dir magnum
        • 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
        • dir gs
          • 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
        • dir sensor
          • file camera.cpp
          • file camera.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
      • file stb_image_write.h
    • dir robots
      • 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
    • dir sensor
      • 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
    • 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/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 (\n    const Utility::Resource & rs,\n    GL::Version version,\n    GL::Shader::Type type\n) \n

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

"},{"location":"api/namespaceTinyProcessLib/","title":"Namespace TinyProcessLib","text":"

Namespace List > TinyProcessLib

The documentation for this class was generated from the following file robot_dart/gui/magnum/gs/camera.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 (\n    const Eigen::Matrix3d & R,\n    const Eigen::Vector3d & t\n) \n
"},{"location":"api/namespacerobot__dart/#function-make_tf_1","title":"function make_tf","text":"
inline Eigen::Isometry3d robot_dart::make_tf (\n    const Eigen::Matrix3d & R\n) \n
"},{"location":"api/namespacerobot__dart/#function-make_tf_2","title":"function make_tf","text":"
inline Eigen::Isometry3d robot_dart::make_tf (\n    const Eigen::Vector3d & t\n) \n
"},{"location":"api/namespacerobot__dart/#function-make_tf_3","title":"function make_tf","text":"
inline Eigen::Isometry3d robot_dart::make_tf (\n    std::initializer_list< double > args\n) \n
"},{"location":"api/namespacerobot__dart/#function-make_vector","title":"function make_vector","text":"
inline Eigen::VectorXd robot_dart::make_vector (\n    std::initializer_list< double > args\n) \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 (\n    const std::string & msg=\"\"\n) \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 (\n    const std::string & model_file,\n    const std::vector< std::pair< std::string, std::string > > & packages,\n    const std::string & robot_name=\"robot\",\n    bool is_urdf_string=false,\n    bool cast_shadows=true\n) \n
"},{"location":"api/classrobot__dart_1_1Robot/#function-robot-23","title":"function Robot [\u2154]","text":"
robot_dart::Robot::Robot (\n    const std::string & model_file,\n    const std::string & robot_name=\"robot\",\n    bool is_urdf_string=false,\n    bool cast_shadows=true\n) \n
"},{"location":"api/classrobot__dart_1_1Robot/#function-robot-33","title":"function Robot [3/3]","text":"
robot_dart::Robot::Robot (\n    dart::dynamics::SkeletonPtr skeleton,\n    const std::string & robot_name=\"robot\",\n    bool cast_shadows=true\n) \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 (\n    const 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 (\n    const 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 (\n    const 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 (\n    const 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 (\n    const 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 (\n    const std::string & body_name,\n    double mass\n) \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 (\n    size_t body_index,\n    double mass\n) \n
"},{"location":"api/classrobot__dart_1_1Robot/#function-add_controller","title":"function add_controller","text":"
void robot_dart::Robot::add_controller (\n    const std::shared_ptr< control::RobotControl > & controller,\n    double weight=1.0\n) \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 (\n    const std::string & body_name,\n    const Eigen::Vector3d & force,\n    const Eigen::Vector3d & offset=Eigen::Vector3d::Zero(),\n    bool force_local=false,\n    bool offset_local=true\n) \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 (\n    size_t body_index,\n    const Eigen::Vector3d & force,\n    const Eigen::Vector3d & offset=Eigen::Vector3d::Zero(),\n    bool force_local=false,\n    bool offset_local=true\n) \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 (\n    const std::string & body_name,\n    const Eigen::Vector3d & torque,\n    bool local=false\n) \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 (\n    size_t body_index,\n    const Eigen::Vector3d & torque,\n    bool local=false\n) \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 (\n    const 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 (\n    const 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 (\n    size_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 (\n    const 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 (\n    const 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 (\n    size_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 (\n    size_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 (\n    const std::string & body_name\n) \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 (\n    size_t body_index\n) \n
"},{"location":"api/classrobot__dart_1_1Robot/#function-body_pose-12","title":"function body_pose [\u00bd]","text":"
Eigen::Isometry3d robot_dart::Robot::body_pose (\n    const 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 (\n    size_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 (\n    const 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 (\n    size_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 (\n    const 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 (\n    size_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 () \n
"},{"location":"api/classrobot__dart_1_1Robot/#function-clear_external_forces","title":"function clear_external_forces","text":"
void robot_dart::Robot::clear_external_forces () \n
"},{"location":"api/classrobot__dart_1_1Robot/#function-clear_internal_forces","title":"function clear_internal_forces","text":"
void robot_dart::Robot::clear_internal_forces () \n
"},{"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 (\n    const std::string & ghost_name=\"ghost\",\n    const 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 (\n    const 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 (\n    const 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 (\n    const 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 (\n    const 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 (\n    size_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 (\n    const 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 (\n    const 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 (\n    const 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 (\n    const 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 (\n    const std::string & dof_name\n) \n
"},{"location":"api/classrobot__dart_1_1Robot/#function-dof-22","title":"function dof [2/2]","text":"
dart::dynamics::DegreeOfFreedom * robot_dart::Robot::dof (\n    size_t dof_index\n) \n
"},{"location":"api/classrobot__dart_1_1Robot/#function-dof_index","title":"function dof_index","text":"
size_t robot_dart::Robot::dof_index (\n    const 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 (\n    size_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 (\n    bool filter_mimics=false,\n    bool filter_locked=false,\n    bool 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 (\n    const 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 (\n    size_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 () \n
"},{"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 (\n    const 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 () \n
"},{"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 (\n    size_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 (\n    const 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 (\n    const 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 (\n    const Eigen::Vector6d & pose=Eigen::Vector6d::Zero()\n) \n
"},{"location":"api/classrobot__dart_1_1Robot/#function-friction_coeff-12","title":"function friction_coeff [\u00bd]","text":"
double robot_dart::Robot::friction_coeff (\n    const std::string & body_name\n) \n
"},{"location":"api/classrobot__dart_1_1Robot/#function-friction_coeff-22","title":"function friction_coeff [2/2]","text":"
double robot_dart::Robot::friction_coeff (\n    size_t body_index\n) \n
"},{"location":"api/classrobot__dart_1_1Robot/#function-friction_dir-12","title":"function friction_dir [\u00bd]","text":"
Eigen::Vector3d robot_dart::Robot::friction_dir (\n    const std::string & body_name\n) \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 (\n    size_t body_index\n) \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 (\n    const 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 (\n    const 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 (\n    const 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 (\n    const std::string & body_name,\n    const 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 (\n    const std::string & body_name,\n    const 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 (\n    const std::string & joint_name\n) \n
"},{"location":"api/classrobot__dart_1_1Robot/#function-joint-22","title":"function joint [2/2]","text":"
dart::dynamics::Joint * robot_dart::Robot::joint (\n    size_t joint_index\n) \n
"},{"location":"api/classrobot__dart_1_1Robot/#function-joint_index","title":"function joint_index","text":"
size_t robot_dart::Robot::joint_index (\n    const 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 (\n    size_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 (\n    const 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 (\n    const 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 (\n    const 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 (\n    const 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 (\n    const 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 () \n
"},{"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 () \n
"},{"location":"api/classrobot__dart_1_1Robot/#function-remove_controller-12","title":"function remove_controller [\u00bd]","text":"
void robot_dart::Robot::remove_controller (\n    const std::shared_ptr< control::RobotControl > & controller\n) \n
"},{"location":"api/classrobot__dart_1_1Robot/#function-remove_controller-22","title":"function remove_controller [2/2]","text":"
void robot_dart::Robot::remove_controller (\n    size_t index\n) \n
"},{"location":"api/classrobot__dart_1_1Robot/#function-reset","title":"function reset","text":"
virtual void robot_dart::Robot::reset () \n
"},{"location":"api/classrobot__dart_1_1Robot/#function-reset_commands","title":"function reset_commands","text":"
void robot_dart::Robot::reset_commands () \n
"},{"location":"api/classrobot__dart_1_1Robot/#function-restitution_coeff-12","title":"function restitution_coeff [\u00bd]","text":"
double robot_dart::Robot::restitution_coeff (\n    const std::string & body_name\n) \n
"},{"location":"api/classrobot__dart_1_1Robot/#function-restitution_coeff-22","title":"function restitution_coeff [2/2]","text":"
double robot_dart::Robot::restitution_coeff (\n    size_t body_index\n) \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 (\n    const std::string & body_name\n) \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 (\n    size_t body_index\n) \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 (\n    const Eigen::VectorXd & accelerations,\n    const std::vector< std::string > & dof_names={}\n) \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 (\n    const Eigen::VectorXd & accelerations,\n    const std::vector< std::string > & dof_names={}\n) \n
"},{"location":"api/classrobot__dart_1_1Robot/#function-set_accelerations","title":"function set_accelerations","text":"
void robot_dart::Robot::set_accelerations (\n    const Eigen::VectorXd & accelerations,\n    const std::vector< std::string > & dof_names={}\n) \n
"},{"location":"api/classrobot__dart_1_1Robot/#function-set_actuator_type","title":"function set_actuator_type","text":"
void robot_dart::Robot::set_actuator_type (\n    const std::string & type,\n    const std::string & joint_name,\n    bool override_mimic=false,\n    bool override_base=false\n) \n
"},{"location":"api/classrobot__dart_1_1Robot/#function-set_actuator_types","title":"function set_actuator_types","text":"
void robot_dart::Robot::set_actuator_types (\n    const std::string & type,\n    const std::vector< std::string > & joint_names={},\n    bool override_mimic=false,\n    bool override_base=false\n) \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 (\n    const Eigen::Isometry3d & tf\n) \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 (\n    const Eigen::Vector6d & pose\n) \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 (\n    const std::string & body_name,\n    double mass\n) \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 (\n    size_t body_index,\n    double mass\n) \n
"},{"location":"api/classrobot__dart_1_1Robot/#function-set_body_name","title":"function set_body_name","text":"
void robot_dart::Robot::set_body_name (\n    size_t body_index,\n    const std::string & body_name\n) \n
"},{"location":"api/classrobot__dart_1_1Robot/#function-set_cast_shadows","title":"function set_cast_shadows","text":"
void robot_dart::Robot::set_cast_shadows (\n    bool cast_shadows=true\n) \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 (\n    const std::string & color_mode\n) \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 (\n    const std::string & color_mode,\n    const std::string & body_name\n) \n
"},{"location":"api/classrobot__dart_1_1Robot/#function-set_commands","title":"function set_commands","text":"
void robot_dart::Robot::set_commands (\n    const Eigen::VectorXd & commands,\n    const std::vector< std::string > & dof_names={}\n) \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 (\n    const std::vector< double > & cfrictions,\n    const std::vector< std::string > & dof_names={}\n) \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 (\n    double cfriction,\n    const std::vector< std::string > & dof_names={}\n) \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 (\n    const std::vector< double > & damps,\n    const std::vector< std::string > & dof_names={}\n) \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 (\n    double damp,\n    const std::vector< std::string > & dof_names={}\n) \n
"},{"location":"api/classrobot__dart_1_1Robot/#function-set_draw_axis","title":"function set_draw_axis","text":"
void robot_dart::Robot::set_draw_axis (\n    const std::string & body_name,\n    double size=0.25\n) \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 (\n    const std::string & body_name,\n    const Eigen::Vector3d & force,\n    const Eigen::Vector3d & offset=Eigen::Vector3d::Zero(),\n    bool force_local=false,\n    bool offset_local=true\n) \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 (\n    size_t body_index,\n    const Eigen::Vector3d & force,\n    const Eigen::Vector3d & offset=Eigen::Vector3d::Zero(),\n    bool force_local=false,\n    bool offset_local=true\n) \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 (\n    const std::string & body_name,\n    const Eigen::Vector3d & torque,\n    bool local=false\n) \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 (\n    size_t body_index,\n    const Eigen::Vector3d & torque,\n    bool local=false\n) \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 (\n    const Eigen::VectorXd & forces,\n    const std::vector< std::string > & dof_names={}\n) \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 (\n    const Eigen::VectorXd & forces,\n    const std::vector< std::string > & dof_names={}\n) \n
"},{"location":"api/classrobot__dart_1_1Robot/#function-set_forces","title":"function set_forces","text":"
void robot_dart::Robot::set_forces (\n    const Eigen::VectorXd & forces,\n    const std::vector< std::string > & dof_names={}\n) \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 (\n    const std::string & body_name,\n    double value\n) \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 (\n    size_t body_index,\n    double value\n) \n
"},{"location":"api/classrobot__dart_1_1Robot/#function-set_friction_coeffs","title":"function set_friction_coeffs","text":"
void robot_dart::Robot::set_friction_coeffs (\n    double value\n) \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 (\n    const std::string & body_name,\n    const Eigen::Vector3d & direction\n) \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 (\n    size_t body_index,\n    const Eigen::Vector3d & direction\n) \n
"},{"location":"api/classrobot__dart_1_1Robot/#function-set_ghost","title":"function set_ghost","text":"
void robot_dart::Robot::set_ghost (\n    bool ghost=true\n) \n
"},{"location":"api/classrobot__dart_1_1Robot/#function-set_joint_name","title":"function set_joint_name","text":"
void robot_dart::Robot::set_joint_name (\n    size_t joint_index,\n    const std::string & joint_name\n) \n
"},{"location":"api/classrobot__dart_1_1Robot/#function-set_mimic","title":"function set_mimic","text":"
void robot_dart::Robot::set_mimic (\n    const std::string & joint_name,\n    const std::string & mimic_joint_name,\n    double multiplier=1.,\n    double offset=0.\n) \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 (\n    const std::vector< bool > & enforced,\n    const std::vector< std::string > & dof_names={}\n) \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 (\n    bool enforced,\n    const std::vector< std::string > & dof_names={}\n) \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 (\n    const Eigen::VectorXd & positions,\n    const std::vector< std::string > & dof_names={}\n) \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 (\n    const Eigen::VectorXd & positions,\n    const std::vector< std::string > & dof_names={}\n) \n
"},{"location":"api/classrobot__dart_1_1Robot/#function-set_positions","title":"function set_positions","text":"
void robot_dart::Robot::set_positions (\n    const Eigen::VectorXd & positions,\n    const std::vector< std::string > & dof_names={}\n) \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 (\n    const std::string & body_name,\n    double value\n) \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 (\n    size_t body_index,\n    double value\n) \n
"},{"location":"api/classrobot__dart_1_1Robot/#function-set_restitution_coeffs","title":"function set_restitution_coeffs","text":"
void robot_dart::Robot::set_restitution_coeffs (\n    double value\n) \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 (\n    const std::string & body_name,\n    double value\n) \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 (\n    size_t body_index,\n    double value\n) \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 (\n    double value\n) \n
"},{"location":"api/classrobot__dart_1_1Robot/#function-set_self_collision","title":"function set_self_collision","text":"
void robot_dart::Robot::set_self_collision (\n    bool enable_self_collisions=true,\n    bool enable_adjacent_collisions=false\n) \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 (\n    const std::vector< double > & stiffnesses,\n    const std::vector< std::string > & dof_names={}\n) \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 (\n    double stiffness,\n    const std::vector< std::string > & dof_names={}\n) \n
"},{"location":"api/classrobot__dart_1_1Robot/#function-set_velocities","title":"function set_velocities","text":"
void robot_dart::Robot::set_velocities (\n    const Eigen::VectorXd & velocities,\n    const std::vector< std::string > & dof_names={}\n) \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 (\n    const Eigen::VectorXd & velocities,\n    const std::vector< std::string > & dof_names={}\n) \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 (\n    const Eigen::VectorXd & velocities,\n    const std::vector< std::string > & dof_names={}\n) \n
"},{"location":"api/classrobot__dart_1_1Robot/#function-skeleton","title":"function skeleton","text":"
dart::dynamics::SkeletonPtr robot_dart::Robot::skeleton () \n
"},{"location":"api/classrobot__dart_1_1Robot/#function-spring_stiffnesses","title":"function spring_stiffnesses","text":"
std::vector< double > robot_dart::Robot::spring_stiffnesses (\n    const 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 (\n    double t\n) \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 () \n
"},{"location":"api/classrobot__dart_1_1Robot/#function-vec_dof","title":"function vec_dof","text":"
Eigen::VectorXd robot_dart::Robot::vec_dof (\n    const Eigen::VectorXd & vec,\n    const 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 (\n    const 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 (\n    const 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 (\n    const 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 () \n
"},{"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 (\n    const Eigen::Vector3d & dims,\n    const Eigen::Isometry3d & tf,\n    const std::string & type=\"free\",\n    double mass=1.0,\n    const Eigen::Vector4d & color=dart::Color::Red(1.0),\n    const std::string & box_name=\"box\"\n) \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 (\n    const Eigen::Vector3d & dims,\n    const Eigen::Vector6d & pose=Eigen::Vector6d::Zero(),\n    const std::string & type=\"free\",\n    double mass=1.0,\n    const Eigen::Vector4d & color=dart::Color::Red(1.0),\n    const std::string & box_name=\"box\"\n) \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 (\n    const Eigen::Vector3d & dims,\n    const Eigen::Isometry3d & tf,\n    const std::string & type=\"free\",\n    double mass=1.0,\n    const Eigen::Vector4d & color=dart::Color::Red(1.0),\n    const std::string & ellipsoid_name=\"ellipsoid\"\n) \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 (\n    const Eigen::Vector3d & dims,\n    const Eigen::Vector6d & pose=Eigen::Vector6d::Zero(),\n    const std::string & type=\"free\",\n    double mass=1.0,\n    const Eigen::Vector4d & color=dart::Color::Red(1.0),\n    const std::string & ellipsoid_name=\"ellipsoid\"\n) \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 (\n    size_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 (\n    const std::string & filename\n) const\n
"},{"location":"api/classrobot__dart_1_1Robot/#function-_jacobian","title":"function _jacobian","text":"
Eigen::MatrixXd robot_dart::Robot::_jacobian (\n    const Eigen::MatrixXd & full_jacobian,\n    const 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 (\n    const std::string & filename,\n    const std::vector< std::pair< std::string, std::string > > & packages=std::vector< std::pair< std::string, std::string > >(),\n    bool is_urdf_string=false\n) \n
"},{"location":"api/classrobot__dart_1_1Robot/#function-_mass_matrix","title":"function _mass_matrix","text":"
Eigen::MatrixXd robot_dart::Robot::_mass_matrix (\n    const Eigen::MatrixXd & full_mass_matrix,\n    const 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 (\n    RobotDARTSimu *\n) \n
"},{"location":"api/classrobot__dart_1_1Robot/#function-_post_removal","title":"function _post_removal","text":"
inline virtual void robot_dart::Robot::_post_removal (\n    RobotDARTSimu *\n) \n
"},{"location":"api/classrobot__dart_1_1Robot/#function-_set_actuator_type","title":"function _set_actuator_type","text":"
void robot_dart::Robot::_set_actuator_type (\n    size_t joint_index,\n    dart::dynamics::Joint::ActuatorType type,\n    bool override_mimic=false,\n    bool override_base=false\n) \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 (\n    const std::vector< dart::dynamics::Joint::ActuatorType > & types,\n    bool override_mimic=false,\n    bool override_base=false\n) \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 (\n    dart::dynamics::Joint::ActuatorType type,\n    bool override_mimic=false,\n    bool override_base=false\n) \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 (\n    dart::dynamics::MeshShape::ColorMode color_mode,\n    dart::dynamics::SkeletonPtr skel\n) \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 (\n    dart::dynamics::MeshShape::ColorMode color_mode,\n    dart::dynamics::ShapeNode * sn\n) \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=2<< 2, 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 (\n    double timestep=0.015\n) \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 (\n    double floor_width=10.0,\n    double floor_height=0.1,\n    double size=1.,\n    const Eigen::Isometry3d & tf=Eigen::Isometry3d::Identity(),\n    const std::string & floor_name=\"checkerboard_floor\",\n    const Eigen::Vector4d & first_color=dart::Color::White(1.),\n    const Eigen::Vector4d & second_color=dart::Color::Gray(1.)\n) \n
"},{"location":"api/classrobot__dart_1_1RobotDARTSimu/#function-add_floor","title":"function add_floor","text":"
std::shared_ptr< Robot > robot_dart::RobotDARTSimu::add_floor (\n    double floor_width=10.0,\n    double floor_height=0.1,\n    const Eigen::Isometry3d & tf=Eigen::Isometry3d::Identity(),\n    const std::string & floor_name=\"floor\"\n) \n
"},{"location":"api/classrobot__dart_1_1RobotDARTSimu/#function-add_robot","title":"function add_robot","text":"
void robot_dart::RobotDARTSimu::add_robot (\n    const robot_t & robot\n) \n
"},{"location":"api/classrobot__dart_1_1RobotDARTSimu/#function-add_sensor-12","title":"function add_sensor [\u00bd]","text":"
template<typename T, typename... Args>\ninline std::shared_ptr< T > robot_dart::RobotDARTSimu::add_sensor (\n    Args &&... args\n) \n
"},{"location":"api/classrobot__dart_1_1RobotDARTSimu/#function-add_sensor-22","title":"function add_sensor [2/2]","text":"
void robot_dart::RobotDARTSimu::add_sensor (\n    const std::shared_ptr< sensor::Sensor > & sensor\n) \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 (\n    const std::string & text,\n    const Eigen::Affine2d & tf=Eigen::Affine2d::Identity(),\n    Eigen::Vector4d color=Eigen::Vector4d(1, 1, 1, 1),\n    std::uint8_t alignment=2<< 2,\n    bool draw_bg=false,\n    Eigen::Vector4d bg_color=Eigen::Vector4d(0, 0, 0, 0.75),\n    double font_size=28\n) \n
"},{"location":"api/classrobot__dart_1_1RobotDARTSimu/#function-add_visual_robot","title":"function add_visual_robot","text":"
void robot_dart::RobotDARTSimu::add_visual_robot (\n    const robot_t & robot\n) \n
"},{"location":"api/classrobot__dart_1_1RobotDARTSimu/#function-clear_robots","title":"function clear_robots","text":"
void robot_dart::RobotDARTSimu::clear_robots () \n
"},{"location":"api/classrobot__dart_1_1RobotDARTSimu/#function-clear_sensors","title":"function clear_sensors","text":"
void robot_dart::RobotDARTSimu::clear_sensors () \n
"},{"location":"api/classrobot__dart_1_1RobotDARTSimu/#function-collision_category-12","title":"function collision_category [\u00bd]","text":"
uint32_t robot_dart::RobotDARTSimu::collision_category (\n    size_t robot_index,\n    const std::string & body_name\n) \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 (\n    size_t robot_index,\n    size_t body_index\n) \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 (\n    size_t robot_index,\n    const std::string & body_name\n) \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 (\n    size_t robot_index,\n    size_t body_index\n) \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 (\n    size_t robot_index,\n    const std::string & body_name\n) \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 (\n    size_t robot_index,\n    size_t body_index\n) \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 (\n    bool enable=true,\n    double font_size=-1\n) \n
"},{"location":"api/classrobot__dart_1_1RobotDARTSimu/#function-enable_text_panel","title":"function enable_text_panel","text":"
void robot_dart::RobotDARTSimu::enable_text_panel (\n    bool enable=true,\n    double font_size=-1\n) \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 () \n
"},{"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 () \n
"},{"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 (\n    size_t robot_index\n) \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 (\n    size_t robot_index,\n    const std::string & body_name\n) \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 (\n    size_t robot_index,\n    size_t body_index\n) \n
"},{"location":"api/classrobot__dart_1_1RobotDARTSimu/#function-remove_robot-12","title":"function remove_robot [\u00bd]","text":"
void robot_dart::RobotDARTSimu::remove_robot (\n    const robot_t & robot\n) \n
"},{"location":"api/classrobot__dart_1_1RobotDARTSimu/#function-remove_robot-22","title":"function remove_robot [2/2]","text":"
void robot_dart::RobotDARTSimu::remove_robot (\n    size_t index\n) \n
"},{"location":"api/classrobot__dart_1_1RobotDARTSimu/#function-remove_sensor-12","title":"function remove_sensor [\u00bd]","text":"
void robot_dart::RobotDARTSimu::remove_sensor (\n    const std::shared_ptr< sensor::Sensor > & sensor\n) \n
"},{"location":"api/classrobot__dart_1_1RobotDARTSimu/#function-remove_sensor-22","title":"function remove_sensor [2/2]","text":"
void robot_dart::RobotDARTSimu::remove_sensor (\n    size_t index\n) \n
"},{"location":"api/classrobot__dart_1_1RobotDARTSimu/#function-remove_sensors","title":"function remove_sensors","text":"
void robot_dart::RobotDARTSimu::remove_sensors (\n    const std::string & type\n) \n
"},{"location":"api/classrobot__dart_1_1RobotDARTSimu/#function-robot","title":"function robot","text":"
robot_t robot_dart::RobotDARTSimu::robot (\n    size_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 (\n    const 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 (\n    double max_duration=5.0,\n    bool reset_commands=false,\n    bool force_position_bounds=true\n) \n
"},{"location":"api/classrobot__dart_1_1RobotDARTSimu/#function-schedule","title":"function schedule","text":"
inline bool robot_dart::RobotDARTSimu::schedule (\n    int freq\n) \n
"},{"location":"api/classrobot__dart_1_1RobotDARTSimu/#function-scheduler-12","title":"function scheduler [\u00bd]","text":"
inline Scheduler & robot_dart::RobotDARTSimu::scheduler () \n
"},{"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 (\n    size_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 (\n    const std::string & collision_detector\n) \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 (\n    size_t robot_index,\n    uint32_t category_mask,\n    uint32_t collision_mask\n) \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 (\n    size_t robot_index,\n    const std::string & body_name,\n    uint32_t category_mask,\n    uint32_t collision_mask\n) \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 (\n    size_t robot_index,\n    size_t body_index,\n    uint32_t category_mask,\n    uint32_t collision_mask\n) \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 (\n    int frequency\n) \n
"},{"location":"api/classrobot__dart_1_1RobotDARTSimu/#function-set_graphics","title":"function set_graphics","text":"
void robot_dart::RobotDARTSimu::set_graphics (\n    const std::shared_ptr< gui::Base > & graphics\n) \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 (\n    int frequency\n) \n
"},{"location":"api/classrobot__dart_1_1RobotDARTSimu/#function-set_gravity","title":"function set_gravity","text":"
void robot_dart::RobotDARTSimu::set_gravity (\n    const Eigen::Vector3d & gravity\n) \n
"},{"location":"api/classrobot__dart_1_1RobotDARTSimu/#function-set_text_panel","title":"function set_text_panel","text":"
void robot_dart::RobotDARTSimu::set_text_panel (\n    const std::string & str\n) \n
"},{"location":"api/classrobot__dart_1_1RobotDARTSimu/#function-set_timestep","title":"function set_timestep","text":"
void robot_dart::RobotDARTSimu::set_timestep (\n    double timestep,\n    bool update_control_freq=true\n) \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 (\n    bool reset_commands=false,\n    bool force_position_bounds=true\n) \n
"},{"location":"api/classrobot__dart_1_1RobotDARTSimu/#function-step_world","title":"function step_world","text":"
bool robot_dart::RobotDARTSimu::step_world (\n    bool reset_commands=false,\n    bool force_position_bounds=true\n) \n
"},{"location":"api/classrobot__dart_1_1RobotDARTSimu/#function-stop_sim","title":"function stop_sim","text":"
void robot_dart::RobotDARTSimu::stop_sim (\n    bool disable=true\n) \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 () \n
"},{"location":"api/classrobot__dart_1_1RobotDARTSimu/#function-robotdartsimu_1","title":"function ~RobotDARTSimu","text":"
robot_dart::RobotDARTSimu::~RobotDARTSimu () \n
"},{"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 (\n    std::shared_ptr< simu::TextData > & text,\n    bool enable,\n    double font_size\n) \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 (\n    const robot_creator_t & robot_creator,\n    size_t pool_size=32,\n    bool verbose=true\n) \n
"},{"location":"api/classrobot__dart_1_1RobotPool/#function-robotpool-22","title":"function RobotPool [2/2]","text":"
robot_dart::RobotPool::RobotPool (\n    const 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 (\n    const std::shared_ptr< Robot > & robot\n) \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 (\n    const std::string & name=\"robot\"\n) \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= (\n    const RobotPool &\n) = delete\n
"},{"location":"api/classrobot__dart_1_1RobotPool/#function-robotpool","title":"function ~RobotPool","text":"
inline virtual robot_dart::RobotPool::~RobotPool () \n
"},{"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 (\n    const std::shared_ptr< Robot > & robot\n) \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 (\n    double dt,\n    bool sync=false\n) \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() (\n    int frequency\n) \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 (\n    double dt,\n    bool sync=false,\n    double current_time=0.,\n    double real_time=0.\n) \n
"},{"location":"api/classrobot__dart_1_1Scheduler/#function-schedule","title":"function schedule","text":"
bool robot_dart::Scheduler::schedule (\n    int frequency\n) \n
"},{"location":"api/classrobot__dart_1_1Scheduler/#function-set_sync","title":"function set_sync","text":"
inline void robot_dart::Scheduler::set_sync (\n    bool enable\n) \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 () \n

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::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::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 (\n    DartShapeConstPtr shape,\n    uint32_t col_mask,\n    uint32_t cat_mask\n) \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 (\n    dart::dynamics::SkeletonPtr skel,\n    uint32_t col_mask,\n    uint32_t cat_mask\n) \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 () \n
"},{"location":"api/classrobot__dart_1_1collision__filter_1_1BitmaskContactFilter/#function-ignorescollision","title":"function ignoresCollision","text":"
inline bool robot_dart::collision_filter::BitmaskContactFilter::ignoresCollision (\n    DartCollisionConstPtr object1,\n    DartCollisionConstPtr 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 (\n    DartShapeConstPtr 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 (\n    DartShapeConstPtr shape\n) \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 (\n    dart::dynamics::SkeletonPtr skel\n) \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 () \n
"},{"location":"api/classrobot__dart_1_1control_1_1PDControl/#function-pdcontrol-23","title":"function PDControl [\u2154]","text":"
robot_dart::control::PDControl::PDControl (\n    const Eigen::VectorXd & ctrl,\n    bool full_control=false,\n    bool use_angular_errors=true\n) \n
"},{"location":"api/classrobot__dart_1_1control_1_1PDControl/#function-pdcontrol-33","title":"function PDControl [3/3]","text":"
robot_dart::control::PDControl::PDControl (\n    const Eigen::VectorXd & ctrl,\n    const std::vector< std::string > & controllable_dofs,\n    bool use_angular_errors=true\n) \n
"},{"location":"api/classrobot__dart_1_1control_1_1PDControl/#function-calculate","title":"function calculate","text":"
virtual Eigen::VectorXd robot_dart::control::PDControl::calculate (\n    double\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 (\n    double p,\n    double d\n) \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 (\n    const Eigen::VectorXd & p,\n    const Eigen::VectorXd & d\n) \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 (\n    bool enable=true\n) \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 (\n    double target,\n    double current\n) \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>

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 () \n
"},{"location":"api/classrobot__dart_1_1control_1_1PolicyControl/#function-policycontrol-25","title":"function PolicyControl [\u2156]","text":"
inline robot_dart::control::PolicyControl::PolicyControl (\n    double dt,\n    const Eigen::VectorXd & ctrl,\n    bool full_control=false\n) \n
"},{"location":"api/classrobot__dart_1_1control_1_1PolicyControl/#function-policycontrol-35","title":"function PolicyControl [\u2157]","text":"
inline robot_dart::control::PolicyControl::PolicyControl (\n    const Eigen::VectorXd & ctrl,\n    bool full_control=false\n) \n
"},{"location":"api/classrobot__dart_1_1control_1_1PolicyControl/#function-policycontrol-45","title":"function PolicyControl [\u2158]","text":"
inline robot_dart::control::PolicyControl::PolicyControl (\n    double dt,\n    const Eigen::VectorXd & ctrl,\n    const std::vector< std::string > & controllable_dofs\n) \n
"},{"location":"api/classrobot__dart_1_1control_1_1PolicyControl/#function-policycontrol-55","title":"function PolicyControl [5/5]","text":"
inline robot_dart::control::PolicyControl::PolicyControl (\n    const Eigen::VectorXd & ctrl,\n    const std::vector< std::string > & controllable_dofs\n) \n
"},{"location":"api/classrobot__dart_1_1control_1_1PolicyControl/#function-calculate","title":"function calculate","text":"
inline virtual Eigen::VectorXd robot_dart::control::PolicyControl::calculate (\n    double 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 (\n    const Eigen::VectorXd & h_params\n) \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 () \n
"},{"location":"api/classrobot__dart_1_1control_1_1RobotControl/#function-robotcontrol-23","title":"function RobotControl [\u2154]","text":"
robot_dart::control::RobotControl::RobotControl (\n    const Eigen::VectorXd & ctrl,\n    bool full_control=false\n) \n
"},{"location":"api/classrobot__dart_1_1control_1_1RobotControl/#function-robotcontrol-33","title":"function RobotControl [3/3]","text":"
robot_dart::control::RobotControl::RobotControl (\n    const Eigen::VectorXd & ctrl,\n    const std::vector< std::string > & controllable_dofs\n) \n
"},{"location":"api/classrobot__dart_1_1control_1_1RobotControl/#function-activate","title":"function activate","text":"
void robot_dart::control::RobotControl::activate (\n    bool enable=true\n) \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 (\n    double 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 () \n
"},{"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 (\n    const Eigen::VectorXd & ctrl\n) \n
"},{"location":"api/classrobot__dart_1_1control_1_1RobotControl/#function-set_robot","title":"function set_robot","text":"
void robot_dart::control::RobotControl::set_robot (\n    const std::shared_ptr< Robot > & robot\n) \n
"},{"location":"api/classrobot__dart_1_1control_1_1RobotControl/#function-set_weight","title":"function set_weight","text":"
void robot_dart::control::RobotControl::set_weight (\n    double weight\n) \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 () \n
"},{"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 () \n
"},{"location":"api/classrobot__dart_1_1control_1_1SimpleControl/#function-simplecontrol-23","title":"function SimpleControl [\u2154]","text":"
robot_dart::control::SimpleControl::SimpleControl (\n    const Eigen::VectorXd & ctrl,\n    bool full_control=false\n) \n
"},{"location":"api/classrobot__dart_1_1control_1_1SimpleControl/#function-simplecontrol-33","title":"function SimpleControl [3/3]","text":"
robot_dart::control::SimpleControl::SimpleControl (\n    const Eigen::VectorXd & ctrl,\n    const std::vector< std::string > & controllable_dofs\n) \n
"},{"location":"api/classrobot__dart_1_1control_1_1SimpleControl/#function-calculate","title":"function calculate","text":"
virtual Eigen::VectorXd robot_dart::control::SimpleControl::calculate (\n    double\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 (\n    const Eigen::VectorXd & data,\n    dart::dynamics::SkeletonPtr skeleton,\n    const std::vector< std::string > & dof_names,\n    const std::unordered_map< std::string, size_t > & dof_map\n) \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 (\n    dart::dynamics::SkeletonPtr skeleton,\n    const std::vector< std::string > & dof_names,\n    const std::unordered_map< std::string, size_t > & dof_map\n) \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 (\n    const Eigen::VectorXd & data,\n    dart::dynamics::SkeletonPtr skeleton,\n    const std::vector< std::string > & dof_names,\n    const std::unordered_map< std::string, size_t > & dof_map\n) \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 (\n    const Image & rgb\n) \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 (\n    const DepthImage & depth_image,\n    const Eigen::Matrix3d & intrinsic_matrix,\n    const Eigen::Matrix4d & tf,\n    double far_plane\n) \n
"},{"location":"api/namespacerobot__dart_1_1gui/#function-save_png_image","title":"function save_png_image","text":"
void robot_dart::gui::save_png_image (\n    const std::string & filename,\n    const Image & rgb\n) \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 (\n    const std::string & filename,\n    const GrayscaleImage & gray\n) \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 () \n
"},{"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 () \n
"},{"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 () \n
"},{"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 () \n
"},{"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 () \n
"},{"location":"api/classrobot__dart_1_1gui_1_1Base/#function-refresh","title":"function refresh","text":"
inline virtual void robot_dart::gui::Base::refresh () \n
"},{"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 (\n    bool\n) \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 (\n    int\n) \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 (\n    double\n) \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 (\n    RobotDARTSimu * simu\n) \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 () \n
"},{"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 =  Magnum::SceneGraph::Camera3D;\n
"},{"location":"api/namespacerobot__dart_1_1gui_1_1magnum/#typedef-object3d","title":"typedef Object3D","text":"
using robot_dart::gui::magnum::Object3D =  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 =  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>\ninline BaseApplication * robot_dart::gui::magnum::make_application (\n    RobotDARTSimu * simu,\n    const GraphicsConfiguration & configuration=GraphicsConfiguration ()\n) \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 (\n    const GraphicsConfiguration & configuration=GraphicsConfiguration ()\n) \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 (\n    const gs::Light & light\n) \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 (\n    gs::Camera & camera,\n    dart::dynamics::BodyNode * body\n) \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 () \n
"},{"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 () \n
"},{"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 () \n
"},{"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 () \n
"},{"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 () \n
"},{"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 () \n
"},{"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 (\n    bool enable=true,\n    bool drawTransparentShadows=false\n) \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 () \n
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1BaseApplication/#function-init","title":"function init","text":"
void robot_dart::gui::magnum::BaseApplication::init (\n    RobotDARTSimu * simu,\n    const GraphicsConfiguration & configuration\n) \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 (\n    size_t i\n) \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 () \n
"},{"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 (\n    const Eigen::Vector3d & camera_pos,\n    const Eigen::Vector3d & look_at,\n    const Eigen::Vector3d & up\n) \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 () \n
"},{"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 (\n    const std::string & video_fname,\n    int fps\n) \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 () \n
"},{"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 () \n
"},{"location":"api/classrobot__dart_1_1gui_1_1magnum_1_1BaseApplication/#function-scene","title":"function scene","text":"
inline Scene3D & robot_dart::gui::magnum::BaseApplication::scene () \n
"},{"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 () \n
"},{"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 (\n    const gs::Camera & camera\n) \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 () \n
"},{"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 () \n
"},{"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 () \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_1BaseGraphics/","title":"Class robot_dart::gui::magnum::BaseGraphics","text":"

template <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 (\n    const GraphicsConfiguration & configuration=GraphicsConfiguration ()\n) \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 (\n    const magnum::gs::Light & light\n) \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 () \n
"},{"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 () \n
"},{"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 (\n    bool enable=true,\n    bool transparent=true\n) \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 (\n    size_t i\n) \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 () \n
"},{"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 (\n    const Eigen::Vector3d & camera_pos,\n    const Eigen::Vector3d & look_at=Eigen::Vector3d(0, 0, 0),\n    const Eigen::Vector3d & up=Eigen::Vector3d(0, 0, 1)\n) \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 () \n
"},{"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 () \n
"},{"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 (\n    const std::string & video_fname,\n    int fps=-1\n) \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 (\n    bool 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 (\n    int 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 (\n    RobotDARTSimu * 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 () \n
"},{"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 (\n    RobotDARTSimu * simu,\n    dart::dynamics::ShapeNode * shape,\n    const std::vector< std::reference_wrapper< Magnum::GL::Mesh > > & meshes,\n    gs::CubeMapColor & shader,\n    gs::CubeMapColor & texture_shader,\n    Object3D * parent,\n    Magnum::SceneGraph::DrawableGroup3D * group\n) \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 (\n    const std::vector< gs::Material > & materials\n) \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 (\n    const std::vector< std::reference_wrapper< Magnum::GL::Mesh > > & meshes\n) \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 (\n    const std::vector< Magnum::Vector3 > & scalings\n) \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 (\n    RobotDARTSimu * simu,\n    dart::dynamics::ShapeNode * shape,\n    const std::vector< std::reference_wrapper< Magnum::GL::Mesh > > & meshes,\n    gs::CubeMap & shader,\n    gs::CubeMap & texture_shader,\n    Object3D * parent,\n    Magnum::SceneGraph::DrawableGroup3D * group\n) \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 (\n    const std::vector< gs::Material > & materials\n) \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 (\n    const std::vector< std::reference_wrapper< Magnum::GL::Mesh > > & meshes\n) \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 (\n    const std::vector< Magnum::Vector3 > & scalings\n) \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 (\n    RobotDARTSimu * simu,\n    dart::dynamics::ShapeNode * shape,\n    const std::vector< std::reference_wrapper< Magnum::GL::Mesh > > & meshes,\n    const std::vector< gs::Material > & materials,\n    gs::PhongMultiLight & color,\n    gs::PhongMultiLight & texture,\n    Object3D * parent,\n    Magnum::SceneGraph::DrawableGroup3D * group\n) \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 (\n    std::reference_wrapper< gs::PhongMultiLight > shader\n) \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 (\n    const std::vector< gs::Material > & materials\n) \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 (\n    const std::vector< std::reference_wrapper< Magnum::GL::Mesh > > & meshes\n) \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 (\n    const std::vector< Magnum::Vector3 > & scalings\n) \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 (\n    const std::vector< bool > & softBody\n) \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 (\n    std::reference_wrapper< gs::PhongMultiLight > shader\n) \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 (\n    bool transparent=true\n) \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 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 (\n    int argc,\n    char ** argv,\n    RobotDARTSimu * simu,\n    const GraphicsConfiguration & configuration=GraphicsConfiguration ()\n) \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 () \n
"},{"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":"
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 (\n    ExitEvent & 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 (\n    KeyEvent & 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 (\n    KeyEvent & 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 (\n    MouseMoveEvent & 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 (\n    MouseScrollEvent & 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 (\n    ViewportEvent & 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 (\n    const 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 (\n    Magnum::Platform::WindowlessGLContext * context\n) \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 () \n
"},{"location":"api/structrobot__dart_1_1gui_1_1magnum_1_1GlobalData/#function-operator","title":"function operator=","text":"
void robot_dart::gui::magnum::GlobalData::operator= (\n    const 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 (\n    size_t N\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 () \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_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 (\n    const GraphicsConfiguration & configuration=default_configuration()\n) \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 (\n    RobotDARTSimu * 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 () \n
"},{"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 () \n

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 (\n    RobotDARTSimu * simu,\n    dart::dynamics::ShapeNode * shape,\n    const std::vector< std::reference_wrapper< Magnum::GL::Mesh > > & meshes,\n    gs::ShadowMapColor & shader,\n    gs::ShadowMapColor & texture_shader,\n    Object3D * parent,\n    Magnum::SceneGraph::DrawableGroup3D * group\n) \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 (\n    const std::vector< gs::Material > & materials\n) \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 (\n    const std::vector< std::reference_wrapper< Magnum::GL::Mesh > > & meshes\n) \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 (\n    const std::vector< Magnum::Vector3 > & scalings\n) \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 (\n    RobotDARTSimu * simu,\n    dart::dynamics::ShapeNode * shape,\n    const std::vector< std::reference_wrapper< Magnum::GL::Mesh > > & meshes,\n    gs::ShadowMap & shader,\n    gs::ShadowMap & texture_shader,\n    Object3D * parent,\n    Magnum::SceneGraph::DrawableGroup3D * group\n) \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 (\n    const std::vector< gs::Material > & materials\n) \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 (\n    const std::vector< std::reference_wrapper< Magnum::GL::Mesh > > & meshes\n) \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 (\n    const std::vector< Magnum::Vector3 > & scalings\n) \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 (\n    int argc,\n    char ** argv,\n    RobotDARTSimu * simu,\n    const GraphicsConfiguration & configuration=GraphicsConfiguration ()\n) \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 () \n
"},{"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 (\n    const GraphicsConfiguration & configuration=default_configuration()\n) \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 (\n    RobotDARTSimu * 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 () \n
"},{"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 () \n

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 (\n    const Magnum::Vector3 & direction,\n    const Material & material\n) \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 (\n    const Magnum::Vector3 & position,\n    const Material & material,\n    Magnum::Float intensity,\n    const Magnum::Vector3 & attenuationTerms\n) \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 (\n    const Magnum::Vector3 & position,\n    const Material & material,\n    const Magnum::Vector3 & spot_direction,\n    Magnum::Float spot_exponent,\n    Magnum::Float spot_cut_off,\n    Magnum::Float intensity,\n    const Magnum::Vector3 & attenuationTerms\n) \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 (\n    Magnum::Image2D * image,\n    Magnum::Float near_plane,\n    Magnum::Float far_plane\n) \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 (\n    Magnum::Image2D * image,\n    bool linearize,\n    Magnum::Float near_plane,\n    Magnum::Float far_plane\n) \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 (\n    Magnum::Image2D * image\n) \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 (\n    const fs::path & filename\n) \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 (\n    Object3D & object,\n    Magnum::Int width,\n    Magnum::Int height\n) \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 () \n
"},{"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 (\n    Magnum::SceneGraph::DrawableGroup3D & drawables,\n    Magnum::GL::AbstractFramebuffer & framebuffer,\n    Magnum::PixelFormat format,\n    RobotDARTSimu * simu,\n    const DebugDrawData & debug_data,\n    bool draw_debug=true\n) \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 (\n    Magnum::Float speed\n) \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 () \n
"},{"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 (\n    const Magnum::Vector3 & camera,\n    const Magnum::Vector3 & center,\n    const Magnum::Vector3 & up=Magnum::Vector3::zAxis()\n) \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 (\n    const Magnum::Vector2i & shift\n) \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 (\n    bool recording,\n    bool recording_depth=false\n) \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 (\n    const std::string & video_fname,\n    int fps\n) \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 () \n
"},{"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 () \n
"},{"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 () \n
"},{"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 (\n    Magnum::Float near_plane,\n    Magnum::Float far_plane,\n    Magnum::Float fov,\n    Magnum::Int width,\n    Magnum::Int height\n) \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 (\n    Magnum::Float far_plane\n) \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 (\n    Magnum::Float fov\n) \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 (\n    Magnum::Float near_plane\n) \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 (\n    const Magnum::Vector2 & speed\n) \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 (\n    const Magnum::Vector2i & size\n) \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 (\n    Magnum::Float speed\n) \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 (\n    std::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 () \n

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 {\n    DiffuseTexture = 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 (\n    Flags flags={}\n) \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 (\n    Magnum::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 (\n    Magnum::Float far_plane\n) \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 (\n    Magnum::Int index\n) \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 (\n    const Magnum::Vector3 & position\n) \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 (\n    Material & material\n) \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 (\n    Magnum::Matrix4 matrices\n) \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 (\n    const Magnum::Matrix4 & matrix\n) \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 {\n    DiffuseTexture = 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 (\n    Flags flags={}\n) \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 (\n    Magnum::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 (\n    Magnum::GL::CubeMapTextureArray & texture\n) \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 (\n    Magnum::Float far_plane\n) \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 (\n    Magnum::Int index\n) \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 (\n    const Magnum::Vector3 & position\n) \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 (\n    Material & material\n) \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 (\n    Magnum::Matrix4 matrices\n) \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 (\n    const Magnum::Matrix4 & matrix\n) \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 () \n
"},{"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 (\n    const Magnum::Vector4 & position,\n    const Material & material,\n    const Magnum::Vector3 & spot_direction,\n    Magnum::Float spot_exponent,\n    Magnum::Float spot_cut_off,\n    const Magnum::Vector4 & attenuation,\n    bool cast_shadows=true\n) \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 () \n
"},{"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 () \n
"},{"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 (\n    const Magnum::Vector4 & attenuation\n) \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 (\n    bool cast_shadows\n) \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 (\n    const Material & material\n) \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 (\n    const Magnum::Vector4 & position\n) \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 (\n    const Magnum::Matrix4 & shadowTransform\n) \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 (\n    Magnum::Float spot_cut_off\n) \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 (\n    const Magnum::Vector3 & spot_direction\n) \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 (\n    Magnum::Float spot_exponent\n) \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 (\n    const Magnum::Vector4 & transformed_position\n) \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 (\n    const Magnum::Vector3 & transformed_spot_direction\n) \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 () \n
"},{"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 () \n
"},{"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 () \n
"},{"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 () \n
"},{"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 () \n
"},{"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 (\n    const Magnum::Color4 & ambient,\n    const Magnum::Color4 & diffuse,\n    const Magnum::Color4 & specular,\n    Magnum::Float shininess\n) \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 (\n    Magnum::GL::Texture2D * ambient_texture,\n    Magnum::GL::Texture2D * diffuse_texture,\n    Magnum::GL::Texture2D * specular_texture,\n    Magnum::Float shininess\n) \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 () \n
"},{"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 () \n
"},{"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 () \n
"},{"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 () \n
"},{"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 (\n    const Magnum::Color4 & ambient\n) \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 (\n    Magnum::GL::Texture2D * ambient_texture\n) \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 (\n    const Magnum::Color4 & diffuse\n) \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 (\n    Magnum::GL::Texture2D * diffuse_texture\n) \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 (\n    Magnum::Float shininess\n) \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 (\n    const Magnum::Color4 & specular\n) \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 (\n    Magnum::GL::Texture2D * specular_texture\n) \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 () \n
"},{"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 () \n
"},{"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 () \n
"},{"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 {\n    AmbientTexture = 1 << 0,\n    DiffuseTexture = 1 << 1,\n    SpecularTexture = 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 (\n    Flags flags={},\n    Magnum::Int max_lights=10\n) \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 (\n    Magnum::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 (\n    Magnum::GL::CubeMapTextureArray & texture\n) \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 (\n    Magnum::GL::CubeMapTextureArray & texture\n) \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 (\n    Magnum::GL::Texture2DArray & texture\n) \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 (\n    Magnum::GL::Texture2DArray & texture\n) \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 (\n    const Magnum::Matrix4 & matrix\n) \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 (\n    Magnum::Float far_plane\n) \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 (\n    bool shadows\n) \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 (\n    Magnum::Int i,\n    const Light & light\n) \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 (\n    Material & material\n) \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 (\n    const Magnum::Matrix3x3 & matrix\n) \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 (\n    const Magnum::Matrix4 & matrix\n) \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 (\n    Magnum::Float specular_strength\n) \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 (\n    const Magnum::Matrix4 & matrix\n) \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 (\n    bool shadows\n) \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 {\n    DiffuseTexture = 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 (\n    Flags flags={}\n) \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 (\n    Magnum::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 (\n    Material & material\n) \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 (\n    const Magnum::Matrix4 & matrix\n) \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 (\n    const Magnum::Matrix4 & matrix\n) \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 {\n    DiffuseTexture = 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 (\n    Flags flags={}\n) \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 (\n    Magnum::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 (\n    Material & material\n) \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 (\n    const Magnum::Matrix4 & matrix\n) \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 (\n    const Magnum::Matrix4 & matrix\n) \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 (\n    BaseApplication * app,\n    size_t width,\n    size_t height,\n    size_t freq=30,\n    bool draw_debug=false\n) \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 (\n    dart::dynamics::BodyNode * body,\n    const 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 (\n    dart::dynamics::Joint *,\n    const 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 (\n    double\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 () \n
"},{"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 () \n
"},{"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 () \n
"},{"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 (\n    bool draw=true\n) \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 () \n
"},{"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 (\n    const Eigen::Vector3d & camera_pos,\n    const Eigen::Vector3d & look_at=Eigen::Vector3d(0, 0, 0),\n    const Eigen::Vector3d & up=Eigen::Vector3d(0, 0, 1)\n) \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 () \n
"},{"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 () \n
"},{"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 () \n
"},{"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 (\n    const std::string & video_fname\n) \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 () \n
"},{"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 (\n    size_t frequency=1000,\n    const std::string & urdf=\"unitree_a1/a1.urdf\",\n    const std::vector< std::pair< std::string, std::string > > & packages=('a1_description', 'unitree_a1/a1_description')\n) \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 (\n    const std::string & urdf=\"arm.urdf\"\n) \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 (\n    size_t frequency=1000,\n    const std::string & urdf=\"franka/franka.urdf\",\n    const std::vector< std::pair< std::string, std::string > > & packages=('franka_description', 'franka/franka_description')\n) \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 (\n    RobotDARTSimu *\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 (\n    RobotDARTSimu *\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 (\n    const std::string & urdf=\"pexod.urdf\"\n) \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 (\n    size_t frequency=1000,\n    const std::string & urdf=\"icub/icub.urdf\",\n    const std::vector< std::pair< std::string, std::string > > & packages=('icub_description', 'icub/icub_description')\n) \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 (\n    RobotDARTSimu *\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 (\n    RobotDARTSimu *\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 (\n    size_t frequency=1000,\n    const std::string & urdf=\"iiwa/iiwa.urdf\",\n    const std::vector< std::pair< std::string, std::string > > & packages=('iiwa_description', 'iiwa/iiwa_description')\n) \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 (\n    RobotDARTSimu *\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 (\n    RobotDARTSimu *\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 (\n    const std::string & urdf=\"pendulum.urdf\"\n) \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 __

  • #include <robot_dart/robots/talos.hpp>

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 (\n    size_t frequency=1000,\n    const std::string & urdf=\"talos/talos.urdf\",\n    const std::vector< std::pair< std::string, std::string > > & packages=('talos_description', 'talos/talos_description')\n) \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 (\n    RobotDARTSimu *\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 (\n    RobotDARTSimu *\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 (\n    size_t frequency=1000,\n    const std::string & urdf=\"talos/talos_fast_collision.urdf\",\n    const std::vector< std::pair< std::string, std::string > > & packages=('talos_description', 'talos/talos_description')\n) \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 () \n
"},{"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 (\n    RobotDARTSimu *\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 (\n    size_t frequency=1000,\n    const std::string & urdf=\"talos/talos_fast.urdf\",\n    const std::vector< std::pair< std::string, std::string > > & packages=('talos_description', 'talos/talos_description')\n) \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 __

  • #include <robot_dart/robots/tiago.hpp>

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 (\n    size_t frequency=1000,\n    const std::string & urdf=\"tiago/tiago_steel.urdf\",\n    const std::vector< std::pair< std::string, std::string > > & packages=('tiago_description', 'tiago/tiago_description')\n) \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 (\n    const std::string & type,\n    const std::string & joint_name,\n    bool override_mimic=false,\n    bool override_base=false,\n    bool override_caster=false\n) \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 (\n    const std::string & type,\n    const std::vector< std::string > & joint_names={},\n    bool override_mimic=false,\n    bool override_base=false,\n    bool override_caster=false\n) \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 (\n    RobotDARTSimu *\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 (\n    RobotDARTSimu *\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 (\n    size_t frequency=1000,\n    const std::string & urdf=\"ur3e/ur3e.urdf\",\n    const std::vector< std::pair< std::string, std::string > > & packages=('ur3e_description', 'ur3e/ur3e_description')\n) \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 (\n    RobotDARTSimu *\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 (\n    RobotDARTSimu *\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 (\n    size_t frequency=1000,\n    const std::string & urdf=\"ur3e/ur3e_with_schunk_hand.urdf\",\n    const std::vector< std::pair< std::string, std::string > > & packages=('ur3e_description', 'ur3e/ur3e_description')\n) \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 (\n    const std::string & urdf=\"vx300/vx300.urdf\",\n    const std::vector< std::pair< std::string, std::string > > & packages=('interbotix_xsarm_descriptions', 'vx300')\n) \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 (\n    dart::dynamics::Joint * joint,\n    size_t frequency=1000,\n    const std::string & direction=\"child_to_parent\"\n) \n
"},{"location":"api/classrobot__dart_1_1sensor_1_1ForceTorque/#function-forcetorque-22","title":"function ForceTorque [2/2]","text":"
inline robot_dart::sensor::ForceTorque::ForceTorque (\n    const std::shared_ptr< Robot > & robot,\n    const std::string & joint_name,\n    size_t frequency=1000,\n    const std::string & direction=\"child_to_parent\"\n) \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 (\n    dart::dynamics::BodyNode *,\n    const 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 (\n    double\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 (\n    const IMUConfig & config\n) \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 (\n    dart::dynamics::Joint *,\n    const 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 (\n    double\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 (\n    dart::dynamics::BodyNode * b,\n    size_t f\n) \n
"},{"location":"api/structrobot__dart_1_1sensor_1_1IMUConfig/#function-imuconfig-23","title":"function IMUConfig [\u2154]","text":"
inline robot_dart::sensor::IMUConfig::IMUConfig (\n    const Eigen::Vector3d & gyro_bias,\n    const Eigen::Vector3d & accel_bias,\n    dart::dynamics::BodyNode * b,\n    size_t f\n) \n
"},{"location":"api/structrobot__dart_1_1sensor_1_1IMUConfig/#function-imuconfig-33","title":"function IMUConfig [3/3]","text":"
inline robot_dart::sensor::IMUConfig::IMUConfig () \n

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 (\n    size_t freq=40\n) \n
"},{"location":"api/classrobot__dart_1_1sensor_1_1Sensor/#function-activate","title":"function activate","text":"
void robot_dart::sensor::Sensor::activate (\n    bool enable=true\n) \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 (\n    dart::dynamics::BodyNode * body,\n    const Eigen::Isometry3d & tf=Eigen::Isometry3d::Identity()\n) \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 (\n    const std::shared_ptr< Robot > & robot,\n    const std::string & body_name,\n    const Eigen::Isometry3d & tf=Eigen::Isometry3d::Identity()\n) \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 (\n    dart::dynamics::Joint * joint,\n    const Eigen::Isometry3d & tf=Eigen::Isometry3d::Identity()\n) \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 (\n    const std::shared_ptr< Robot > & robot,\n    const std::string & joint_name,\n    const Eigen::Isometry3d & tf=Eigen::Isometry3d::Identity()\n) \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 (\n    double\n) = 0\n
"},{"location":"api/classrobot__dart_1_1sensor_1_1Sensor/#function-detach","title":"function detach","text":"
void robot_dart::sensor::Sensor::detach () \n
"},{"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 (\n    double t\n) \n
"},{"location":"api/classrobot__dart_1_1sensor_1_1Sensor/#function-set_frequency","title":"function set_frequency","text":"
void robot_dart::sensor::Sensor::set_frequency (\n    size_t freq\n) \n
"},{"location":"api/classrobot__dart_1_1sensor_1_1Sensor/#function-set_pose","title":"function set_pose","text":"
void robot_dart::sensor::Sensor::set_pose (\n    const Eigen::Isometry3d & tf\n) \n
"},{"location":"api/classrobot__dart_1_1sensor_1_1Sensor/#function-set_simu","title":"function set_simu","text":"
void robot_dart::sensor::Sensor::set_simu (\n    RobotDARTSimu * simu\n) \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 () \n
"},{"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 (\n    dart::dynamics::Joint * joint,\n    size_t frequency=1000\n) \n
"},{"location":"api/classrobot__dart_1_1sensor_1_1Torque/#function-torque-22","title":"function Torque [2/2]","text":"
inline robot_dart::sensor::Torque::Torque (\n    const std::shared_ptr< Robot > & robot,\n    const std::string & joint_name,\n    size_t frequency=1000\n) \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 (\n    dart::dynamics::BodyNode *,\n    const 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 (\n    double\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=2<< 2, 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 (\n    const std::string & text,\n    const Eigen::Affine2d & tf=Eigen::Affine2d::Identity(),\n    Eigen::Vector4d color=Eigen::Vector4d(1, 1, 1, 1),\n    std::uint8_t alignment=2<< 2,\n    bool draw_bg=false,\n    Eigen::Vector4d bg_color=Eigen::Vector4d(0, 0, 0, 0.75),\n    double font_size=28\n) \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 (\n    dart::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 (\n    dart::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 (\n    const std::shared_ptr< Robot > & robot\n) \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 (\n    const std::shared_ptr< simu::TextData > & data\n) \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 (\n    size_t index\n) \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 (\n    const std::shared_ptr< Robot > & robot\n) \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::gs","text":"

Namespace List > gs

"},{"location":"api/namespacerobot__dart_1_1gui_1_1magnum_1_1gs_1_1_0d21/#public-types","title":"Public Types","text":"Type Name enum Magnum::Int gs"},{"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-gs","title":"enum gs","text":"
enum gs::gs;\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/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

  • #include \"robot_dart_simu.hpp\"
  • #include \"utils_headers_dart_dynamics.hpp\"
  • #include <unordered_map>
  • #include <vector>
"},{"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\n#include \"robot_dart_simu.hpp\"\n#include \"utils_headers_dart_dynamics.hpp\"\n\n#include <unordered_map>\n#include <vector>\n\nnamespace robot_dart {\n    namespace simu {\n        struct GUIData {\n        private:\n            struct RobotData {\n                bool casting_shadows;\n                bool is_ghost;\n            };\n\n            std::unordered_map<dart::dynamics::ShapeNode*, RobotData> robot_data;\n            std::unordered_map<Robot*, std::vector<std::pair<dart::dynamics::BodyNode*, double>>> robot_axes;\n            std::vector<std::shared_ptr<simu::TextData>> text_drawings;\n\n        public:\n            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 = 2 << 2, bool draw_bg = false, Eigen::Vector4d bg_color = Eigen::Vector4d(0, 0, 0, 0.75), double font_size = 28)\n            {\n                text_drawings.emplace_back(new TextData{text, tf, color, alignment, draw_bg, bg_color, font_size});\n\n                return text_drawings.back();\n            }\n\n            void remove_text(const std::shared_ptr<simu::TextData>& data)\n            {\n                for (size_t i = 0; i < text_drawings.size(); i++) {\n                    if (text_drawings[i] == data) {\n                        text_drawings.erase(text_drawings.begin() + i);\n                        return;\n                    }\n                }\n            }\n\n            void remove_text(size_t index)\n            {\n                if (index >= text_drawings.size())\n                    return;\n                text_drawings.erase(text_drawings.begin() + index);\n            }\n\n            void update_robot(const std::shared_ptr<Robot>& robot)\n            {\n                auto robot_ptr = &*robot;\n                auto skel = robot->skeleton();\n                bool cast = robot->cast_shadows();\n                bool ghost = robot->ghost();\n\n                for (size_t i = 0; i < skel->getNumBodyNodes(); ++i) {\n                    auto bd = skel->getBodyNode(i);\n#if DART_VERSION_AT_LEAST(6, 13, 0)\n                    bd->eachShapeNodeWith<dart::dynamics::VisualAspect>([this, cast, ghost](dart::dynamics::ShapeNode* shapeNode) {\n                        robot_data[shapeNode] = {cast, ghost};\n                    });\n#else\n                    auto& shapes = bd->getShapeNodesWith<dart::dynamics::VisualAspect>();\n                    for (size_t j = 0; j < shapes.size(); j++) {\n                        robot_data[shapes[j]] = {cast, ghost};\n                    }\n#endif\n                }\n\n                auto& axes = robot->drawing_axes();\n                if (axes.size() > 0)\n                    robot_axes[robot_ptr] = axes;\n            }\n\n            void remove_robot(const std::shared_ptr<Robot>& robot)\n            {\n                auto robot_ptr = &*robot;\n                auto skel = robot->skeleton();\n                for (size_t i = 0; i < skel->getNumShapeNodes(); ++i) {\n                    auto shape = skel->getShapeNode(i);\n                    auto shape_iter = robot_data.find(shape);\n                    if (shape_iter != robot_data.end())\n                        robot_data.erase(shape_iter);\n                }\n\n                auto iter = robot_axes.find(robot_ptr);\n                if (iter != robot_axes.end())\n                    robot_axes.erase(iter);\n            }\n\n            bool cast_shadows(dart::dynamics::ShapeNode* shape) const\n            {\n                auto shape_iter = robot_data.find(shape);\n                if (shape_iter != robot_data.end())\n                    return robot_data.at(shape).casting_shadows;\n                // if not in the array, cast shadow by default\n                return true;\n            }\n\n            bool ghost(dart::dynamics::ShapeNode* shape) const\n            {\n                auto shape_iter = robot_data.find(shape);\n                if (shape_iter != robot_data.end())\n                    return robot_data.at(shape).is_ghost;\n                // if not in the array, the robot is not ghost by default\n                return false;\n            }\n\n            std::vector<std::pair<dart::dynamics::BodyNode*, double>> drawing_axes() const\n            {\n                std::vector<std::pair<dart::dynamics::BodyNode*, double>> axes;\n                for (std::pair<Robot*, std::vector<std::pair<dart::dynamics::BodyNode*, double>>> elem : robot_axes) {\n                    axes.insert(axes.end(), elem.second.begin(), elem.second.end());\n                }\n\n                return axes;\n            }\n\n            const std::vector<std::shared_ptr<simu::TextData>>& drawing_texts() const { return text_drawings; }\n        };\n    } // namespace simu\n} // namespace robot_dart\n\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

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

  • #include <unordered_map>
  • #include <robot_dart/utils.hpp>
"},{"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\n#include <unordered_map>\n\n#include <robot_dart/utils.hpp>\n\nnamespace robot_dart {\n    class RobotDARTSimu;\n    namespace control {\n        class RobotControl;\n    }\n\n    class Robot : public std::enable_shared_from_this<Robot> {\n    public:\n        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);\n        Robot(const std::string& model_file, const std::string& robot_name = \"robot\", bool is_urdf_string = false, bool cast_shadows = true);\n        Robot(dart::dynamics::SkeletonPtr skeleton, const std::string& robot_name = \"robot\", bool cast_shadows = true);\n        virtual ~Robot() {}\n\n        std::shared_ptr<Robot> clone() const;\n        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;\n\n        dart::dynamics::SkeletonPtr skeleton();\n        dart::dynamics::BodyNode* body_node(const std::string& body_name);\n        dart::dynamics::BodyNode* body_node(size_t body_index);\n\n        dart::dynamics::Joint* joint(const std::string& joint_name);\n        dart::dynamics::Joint* joint(size_t joint_index);\n\n        dart::dynamics::DegreeOfFreedom* dof(const std::string& dof_name);\n        dart::dynamics::DegreeOfFreedom* dof(size_t dof_index);\n\n        const std::string& name() const;\n        // to use the same urdf somewhere else\n        const std::string& model_filename() const { return _model_filename; }\n        const std::vector<std::pair<std::string, std::string>>& model_packages() const { return _packages; }\n\n        void update(double t);\n\n        void reinit_controllers();\n\n        size_t num_controllers() const;\n        std::vector<std::shared_ptr<control::RobotControl>> controllers() const;\n        std::vector<std::shared_ptr<control::RobotControl>> active_controllers() const;\n\n        std::shared_ptr<control::RobotControl> controller(size_t index) const;\n\n        void add_controller(\n            const std::shared_ptr<control::RobotControl>& controller, double weight = 1.0);\n        void remove_controller(const std::shared_ptr<control::RobotControl>& controller);\n        void remove_controller(size_t index);\n        void clear_controllers();\n\n        void fix_to_world();\n        // pose: Orientation-Position\n        void free_from_world(const Eigen::Vector6d& pose = Eigen::Vector6d::Zero());\n\n        bool fixed() const;\n        bool free() const;\n\n        virtual void reset();\n\n        void clear_external_forces();\n        void clear_internal_forces();\n        void reset_commands();\n\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\n        void set_actuator_types(const std::string& type, const std::vector<std::string>& joint_names = {}, bool override_mimic = false, bool override_base = false);\n        void set_actuator_type(const std::string& type, const std::string& joint_name, bool override_mimic = false, bool override_base = false);\n        void set_mimic(const std::string& joint_name, const std::string& mimic_joint_name, double multiplier = 1., double offset = 0.);\n\n        std::string actuator_type(const std::string& joint_name) const;\n        std::vector<std::string> actuator_types(const std::vector<std::string>& joint_names = {}) const;\n\n        void set_position_enforced(const std::vector<bool>& enforced, const std::vector<std::string>& dof_names = {});\n        void set_position_enforced(bool enforced, const std::vector<std::string>& dof_names = {});\n\n        std::vector<bool> position_enforced(const std::vector<std::string>& dof_names = {}) const;\n\n        void force_position_bounds();\n\n        void set_damping_coeffs(const std::vector<double>& damps, const std::vector<std::string>& dof_names = {});\n        void set_damping_coeffs(double damp, const std::vector<std::string>& dof_names = {});\n\n        std::vector<double> damping_coeffs(const std::vector<std::string>& dof_names = {}) const;\n\n        void set_coulomb_coeffs(const std::vector<double>& cfrictions, const std::vector<std::string>& dof_names = {});\n        void set_coulomb_coeffs(double cfriction, const std::vector<std::string>& dof_names = {});\n\n        std::vector<double> coulomb_coeffs(const std::vector<std::string>& dof_names = {}) const;\n\n        void set_spring_stiffnesses(const std::vector<double>& stiffnesses, const std::vector<std::string>& dof_names = {});\n        void set_spring_stiffnesses(double stiffness, const std::vector<std::string>& dof_names = {});\n\n        std::vector<double> spring_stiffnesses(const std::vector<std::string>& dof_names = {}) const;\n\n        // the friction direction is in local frame\n        void set_friction_dir(const std::string& body_name, const Eigen::Vector3d& direction);\n        void set_friction_dir(size_t body_index, const Eigen::Vector3d& direction);\n        Eigen::Vector3d friction_dir(const std::string& body_name);\n        Eigen::Vector3d friction_dir(size_t body_index);\n\n        void set_friction_coeff(const std::string& body_name, double value);\n        void set_friction_coeff(size_t body_index, double value);\n        void set_friction_coeffs(double value);\n        double friction_coeff(const std::string& body_name);\n        double friction_coeff(size_t body_index);\n\n        void set_secondary_friction_coeff(const std::string& body_name, double value);\n        void set_secondary_friction_coeff(size_t body_index, double value);\n        void set_secondary_friction_coeffs(double value);\n        double secondary_friction_coeff(const std::string& body_name);\n        double secondary_friction_coeff(size_t body_index);\n\n        void set_restitution_coeff(const std::string& body_name, double value);\n        void set_restitution_coeff(size_t body_index, double value);\n        void set_restitution_coeffs(double value);\n        double restitution_coeff(const std::string& body_name);\n        double restitution_coeff(size_t body_index);\n\n        Eigen::Isometry3d base_pose() const;\n        Eigen::Vector6d base_pose_vec() const;\n        void set_base_pose(const Eigen::Isometry3d& tf);\n        void set_base_pose(const Eigen::Vector6d& pose);\n\n        size_t num_dofs() const;\n        size_t num_joints() const;\n        size_t num_bodies() const;\n\n        Eigen::Vector3d com() const;\n        Eigen::Vector6d com_velocity() const;\n        Eigen::Vector6d com_acceleration() const;\n\n        Eigen::VectorXd positions(const std::vector<std::string>& dof_names = {}) const;\n        void set_positions(const Eigen::VectorXd& positions, const std::vector<std::string>& dof_names = {});\n\n        Eigen::VectorXd position_lower_limits(const std::vector<std::string>& dof_names = {}) const;\n        void set_position_lower_limits(const Eigen::VectorXd& positions, const std::vector<std::string>& dof_names = {});\n        Eigen::VectorXd position_upper_limits(const std::vector<std::string>& dof_names = {}) const;\n        void set_position_upper_limits(const Eigen::VectorXd& positions, const std::vector<std::string>& dof_names = {});\n\n        Eigen::VectorXd velocities(const std::vector<std::string>& dof_names = {}) const;\n        void set_velocities(const Eigen::VectorXd& velocities, const std::vector<std::string>& dof_names = {});\n\n        Eigen::VectorXd velocity_lower_limits(const std::vector<std::string>& dof_names = {}) const;\n        void set_velocity_lower_limits(const Eigen::VectorXd& velocities, const std::vector<std::string>& dof_names = {});\n        Eigen::VectorXd velocity_upper_limits(const std::vector<std::string>& dof_names = {}) const;\n        void set_velocity_upper_limits(const Eigen::VectorXd& velocities, const std::vector<std::string>& dof_names = {});\n\n        Eigen::VectorXd accelerations(const std::vector<std::string>& dof_names = {}) const;\n        void set_accelerations(const Eigen::VectorXd& accelerations, const std::vector<std::string>& dof_names = {});\n\n        Eigen::VectorXd acceleration_lower_limits(const std::vector<std::string>& dof_names = {}) const;\n        void set_acceleration_lower_limits(const Eigen::VectorXd& accelerations, const std::vector<std::string>& dof_names = {});\n        Eigen::VectorXd acceleration_upper_limits(const std::vector<std::string>& dof_names = {}) const;\n        void set_acceleration_upper_limits(const Eigen::VectorXd& accelerations, const std::vector<std::string>& dof_names = {});\n\n        Eigen::VectorXd forces(const std::vector<std::string>& dof_names = {}) const;\n        void set_forces(const Eigen::VectorXd& forces, const std::vector<std::string>& dof_names = {});\n\n        Eigen::VectorXd force_lower_limits(const std::vector<std::string>& dof_names = {}) const;\n        void set_force_lower_limits(const Eigen::VectorXd& forces, const std::vector<std::string>& dof_names = {});\n        Eigen::VectorXd force_upper_limits(const std::vector<std::string>& dof_names = {}) const;\n        void set_force_upper_limits(const Eigen::VectorXd& forces, const std::vector<std::string>& dof_names = {});\n\n        Eigen::VectorXd commands(const std::vector<std::string>& dof_names = {}) const;\n        void set_commands(const Eigen::VectorXd& commands, const std::vector<std::string>& dof_names = {});\n\n        std::pair<Eigen::Vector6d, Eigen::Vector6d> force_torque(size_t joint_index) const;\n\n        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);\n        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);\n        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);\n        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);\n\n        void set_external_torque(const std::string& body_name, const Eigen::Vector3d& torque, bool local = false);\n        void set_external_torque(size_t body_index, const Eigen::Vector3d& torque, bool local = false);\n        void add_external_torque(const std::string& body_name, const Eigen::Vector3d& torque, bool local = false);\n        void add_external_torque(size_t body_index, const Eigen::Vector3d& torque, bool local = false);\n\n        Eigen::Vector6d external_forces(const std::string& body_name) const;\n        Eigen::Vector6d external_forces(size_t body_index) const;\n\n        Eigen::Isometry3d body_pose(const std::string& body_name) const;\n        Eigen::Isometry3d body_pose(size_t body_index) const;\n\n        Eigen::Vector6d body_pose_vec(const std::string& body_name) const;\n        Eigen::Vector6d body_pose_vec(size_t body_index) const;\n\n        Eigen::Vector6d body_velocity(const std::string& body_name) const;\n        Eigen::Vector6d body_velocity(size_t body_index) const;\n\n        Eigen::Vector6d body_acceleration(const std::string& body_name) const;\n        Eigen::Vector6d body_acceleration(size_t body_index) const;\n\n        std::vector<std::string> body_names() const;\n        std::string body_name(size_t body_index) const;\n        void set_body_name(size_t body_index, const std::string& body_name);\n        size_t body_index(const std::string& body_name) const;\n\n        double body_mass(const std::string& body_name) const;\n        double body_mass(size_t body_index) const;\n        void set_body_mass(const std::string& body_name, double mass);\n        void set_body_mass(size_t body_index, double mass);\n        void add_body_mass(const std::string& body_name, double mass);\n        void add_body_mass(size_t body_index, double mass);\n\n        Eigen::MatrixXd jacobian(const std::string& body_name, const std::vector<std::string>& dof_names = {}) const;\n        Eigen::MatrixXd jacobian_deriv(const std::string& body_name, const std::vector<std::string>& dof_names = {}) const;\n\n        Eigen::MatrixXd com_jacobian(const std::vector<std::string>& dof_names = {}) const;\n        Eigen::MatrixXd com_jacobian_deriv(const std::vector<std::string>& dof_names = {}) const;\n\n        Eigen::MatrixXd mass_matrix(const std::vector<std::string>& dof_names = {}) const;\n        Eigen::MatrixXd aug_mass_matrix(const std::vector<std::string>& dof_names = {}) const;\n        Eigen::MatrixXd inv_mass_matrix(const std::vector<std::string>& dof_names = {}) const;\n        Eigen::MatrixXd inv_aug_mass_matrix(const std::vector<std::string>& dof_names = {}) const;\n\n        Eigen::VectorXd coriolis_forces(const std::vector<std::string>& dof_names = {}) const;\n        Eigen::VectorXd gravity_forces(const std::vector<std::string>& dof_names = {}) const;\n        Eigen::VectorXd coriolis_gravity_forces(const std::vector<std::string>& dof_names = {}) const;\n        Eigen::VectorXd constraint_forces(const std::vector<std::string>& dof_names = {}) const;\n\n        // Get only the part of vector for DOFs in dof_names\n        Eigen::VectorXd vec_dof(const Eigen::VectorXd& vec, const std::vector<std::string>& dof_names) const;\n\n        void update_joint_dof_maps();\n        const std::unordered_map<std::string, size_t>& dof_map() const;\n        const std::unordered_map<std::string, size_t>& joint_map() const;\n\n        std::vector<std::string> dof_names(bool filter_mimics = false, bool filter_locked = false, bool filter_passive = false) const;\n        std::vector<std::string> mimic_dof_names() const;\n        std::vector<std::string> locked_dof_names() const;\n        std::vector<std::string> passive_dof_names() const;\n        std::string dof_name(size_t dof_index) const;\n        size_t dof_index(const std::string& dof_name) const;\n\n        std::vector<std::string> joint_names() const;\n        std::string joint_name(size_t joint_index) const;\n        void set_joint_name(size_t joint_index, const std::string& joint_name);\n        size_t joint_index(const std::string& joint_name) const;\n\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)\n        void set_color_mode(const std::string& color_mode);\n        void set_color_mode(const std::string& color_mode, const std::string& body_name);\n\n        void set_self_collision(bool enable_self_collisions = true, bool enable_adjacent_collisions = false);\n        bool self_colliding() const;\n        // This returns true if self colliding AND adjacent checks are on\n        bool adjacent_colliding() const;\n\n        // GUI options\n        void set_cast_shadows(bool cast_shadows = true);\n        bool cast_shadows() const;\n\n        void set_ghost(bool ghost = true);\n        bool ghost() const;\n\n        void set_draw_axis(const std::string& body_name, double size = 0.25);\n        void remove_all_drawing_axis();\n        const std::vector<std::pair<dart::dynamics::BodyNode*, double>>& drawing_axes() const;\n\n        // helper functions\n        static std::shared_ptr<Robot> create_box(const Eigen::Vector3d& dims,\n            const Eigen::Isometry3d& tf, const std::string& type = \"free\",\n            double mass = 1.0, const Eigen::Vector4d& color = dart::Color::Red(1.0),\n            const std::string& box_name = \"box\");\n        // pose: 6D log_map\n        static std::shared_ptr<Robot> create_box(const Eigen::Vector3d& dims,\n            const Eigen::Vector6d& pose = Eigen::Vector6d::Zero(), const std::string& type = \"free\",\n            double mass = 1.0, const Eigen::Vector4d& color = dart::Color::Red(1.0),\n            const std::string& box_name = \"box\");\n\n        static std::shared_ptr<Robot> create_ellipsoid(const Eigen::Vector3d& dims,\n            const Eigen::Isometry3d& tf, const std::string& type = \"free\",\n            double mass = 1.0, const Eigen::Vector4d& color = dart::Color::Red(1.0),\n            const std::string& ellipsoid_name = \"ellipsoid\");\n        // pose: 6D log_map\n        static std::shared_ptr<Robot> create_ellipsoid(const Eigen::Vector3d& dims,\n            const Eigen::Vector6d& pose = Eigen::Vector6d::Zero(), const std::string& type = \"free\",\n            double mass = 1.0, const Eigen::Vector4d& color = dart::Color::Red(1.0),\n            const std::string& ellipsoid_name = \"ellipsoid\");\n\n    protected:\n        std::string _get_path(const std::string& filename) const;\n        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);\n\n        void _set_color_mode(dart::dynamics::MeshShape::ColorMode color_mode, dart::dynamics::SkeletonPtr skel);\n        void _set_color_mode(dart::dynamics::MeshShape::ColorMode color_mode, dart::dynamics::ShapeNode* sn);\n        void _set_actuator_type(size_t joint_index, dart::dynamics::Joint::ActuatorType type, bool override_mimic = false, bool override_base = false);\n        void _set_actuator_types(const std::vector<dart::dynamics::Joint::ActuatorType>& types, bool override_mimic = false, bool override_base = false);\n        void _set_actuator_types(dart::dynamics::Joint::ActuatorType type, bool override_mimic = false, bool override_base = false);\n\n        dart::dynamics::Joint::ActuatorType _actuator_type(size_t joint_index) const;\n        std::vector<dart::dynamics::Joint::ActuatorType> _actuator_types() const;\n\n        Eigen::MatrixXd _jacobian(const Eigen::MatrixXd& full_jacobian, const std::vector<std::string>& dof_names) const;\n        Eigen::MatrixXd _mass_matrix(const Eigen::MatrixXd& full_mass_matrix, const std::vector<std::string>& dof_names) const;\n\n        virtual void _post_addition(RobotDARTSimu*) {}\n        virtual void _post_removal(RobotDARTSimu*) {}\n\n        friend class RobotDARTSimu;\n\n        std::string _robot_name;\n        std::string _model_filename;\n        std::vector<std::pair<std::string, std::string>> _packages;\n        dart::dynamics::SkeletonPtr _skeleton;\n        std::vector<std::shared_ptr<control::RobotControl>> _controllers;\n        std::unordered_map<std::string, size_t> _dof_map, _joint_map;\n        bool _cast_shadows;\n        bool _is_ghost;\n        std::vector<std::pair<dart::dynamics::BodyNode*, double>> _axis_shapes;\n    };\n} // namespace robot_dart\n\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

  • #include \"pd_control.hpp\"
  • #include \"robot_dart/robot.hpp\"
  • #include \"robot_dart/utils.hpp\"
  • #include \"robot_dart/utils_headers_dart_dynamics.hpp\"
"},{"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\"\n\nnamespace robot_dart {\n    namespace control {\n        PDControl::PDControl() : RobotControl() {}\n        PDControl::PDControl(const Eigen::VectorXd& ctrl, bool full_control, bool use_angular_errors) : RobotControl(ctrl, full_control), _use_angular_errors(use_angular_errors) {}\n        PDControl::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) {}\n\n        void PDControl::configure()\n        {\n            if (_ctrl.size() == _control_dof)\n                _active = true;\n\n            if (_Kp.size() == 0)\n                set_pd(10., 0.1);\n        }\n\n        Eigen::VectorXd PDControl::calculate(double)\n        {\n            ROBOT_DART_ASSERT(_control_dof == _ctrl.size(), \"PDControl: Controller parameters size is not the same as DOFs of the robot\", Eigen::VectorXd::Zero(_control_dof));\n            auto robot = _robot.lock();\n\n            Eigen::VectorXd dq = robot->velocities(_controllable_dofs);\n\n            Eigen::VectorXd error;\n            if (!_use_angular_errors) {\n                Eigen::VectorXd q = robot->positions(_controllable_dofs);\n                error = _ctrl - q;\n            }\n            else {\n                error = Eigen::VectorXd::Zero(_control_dof);\n\n                std::unordered_map<size_t, Eigen::VectorXd> joint_vals, joint_desired, errors;\n\n                for (int i = 0; i < _control_dof; ++i) {\n                    auto dof = robot->dof(_controllable_dofs[i]);\n                    size_t joint_index = dof->getJoint()->getJointIndexInSkeleton();\n                    if (joint_vals.find(joint_index) == joint_vals.end()) {\n                        joint_vals[joint_index] = dof->getJoint()->getPositions();\n                        joint_desired[joint_index] = dof->getJoint()->getPositions();\n                    }\n\n                    joint_desired[joint_index][dof->getIndexInJoint()] = _ctrl[i];\n                }\n\n                for (int i = 0; i < _control_dof; ++i) {\n                    auto dof = robot->dof(_controllable_dofs[i]);\n                    size_t joint_index = dof->getJoint()->getJointIndexInSkeleton();\n                    size_t dof_index_in_joint = dof->getIndexInJoint();\n\n                    Eigen::VectorXd val;\n                    if (errors.find(joint_index) == errors.end()) {\n                        val = Eigen::VectorXd(dof->getJoint()->getNumDofs());\n\n                        std::string joint_type = robot->dof(_controllable_dofs[i])->getJoint()->getType();\n                        if (joint_type == dart::dynamics::RevoluteJoint::getStaticType()) {\n                            val[dof_index_in_joint] = _angle_dist(_ctrl[i], joint_vals[joint_index][dof_index_in_joint]);\n                        }\n                        else if (joint_type == dart::dynamics::BallJoint::getStaticType()) {\n                            Eigen::Matrix3d R_desired = dart::math::expMapRot(joint_desired[joint_index]);\n                            Eigen::Matrix3d R_current = dart::math::expMapRot(joint_vals[joint_index]);\n                            val = dart::math::logMap(R_desired * R_current.transpose());\n                        }\n                        else if (joint_type == dart::dynamics::EulerJoint::getStaticType()) {\n                            // TO-DO: Check if this is 100% correct\n                            for (size_t d = 0; d < dof->getJoint()->getNumDofs(); d++)\n                                val[d] = _angle_dist(joint_desired[joint_index][d], joint_vals[joint_index][d]);\n                        }\n                        else if (joint_type == dart::dynamics::FreeJoint::getStaticType()) {\n                            auto free_joint = static_cast<dart::dynamics::FreeJoint*>(dof->getJoint());\n\n                            Eigen::Isometry3d tf_desired = free_joint->convertToTransform(joint_desired[joint_index]);\n                            Eigen::Isometry3d tf_current = free_joint->convertToTransform(joint_vals[joint_index]);\n\n                            val.tail(3) = tf_desired.translation() - tf_current.translation();\n                            val.head(3) = dart::math::logMap(tf_desired.linear().matrix() * tf_current.linear().matrix().transpose());\n                        }\n                        else {\n                            val[dof_index_in_joint] = _ctrl[i] - joint_vals[joint_index][dof_index_in_joint];\n                        }\n\n                        errors[joint_index] = val;\n                    }\n                    else\n                        val = errors[joint_index];\n                    error(i) = val[dof_index_in_joint];\n                }\n            }\n\n            Eigen::VectorXd commands = _Kp.array() * error.array() - _Kd.array() * dq.array();\n\n            return commands;\n        }\n\n        void 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        }\n\n        void PDControl::set_pd(const Eigen::VectorXd& Kp, const Eigen::VectorXd& Kd)\n        {\n            ROBOT_DART_ASSERT(Kp.size() == _control_dof, \"PDControl: The Kp size is not the same as the DOFs!\", );\n            ROBOT_DART_ASSERT(Kd.size() == _control_dof, \"PDControl: The Kd size is not the same as the DOFs!\", );\n            _Kp = Kp;\n            _Kd = Kd;\n        }\n\n        std::pair<Eigen::VectorXd, Eigen::VectorXd> PDControl::pd() const\n        {\n            return std::make_pair(_Kp, _Kd);\n        }\n\n        bool PDControl::using_angular_errors() const { return _use_angular_errors; }\n\n        void PDControl::set_use_angular_errors(bool enable) { _use_angular_errors = enable; }\n\n        std::shared_ptr<RobotControl> PDControl::clone() const\n        {\n            return std::make_shared<PDControl>(*this);\n        }\n\n        double PDControl::_angle_dist(double target, double current)\n        {\n            double theta = target - current;\n            while (theta < -M_PI)\n                theta += 2 * M_PI;\n            while (theta > M_PI)\n                theta -= 2 * M_PI;\n            return 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

  • #include <utility>
  • #include <robot_dart/control/robot_control.hpp>
  • #include <robot_dart/robot.hpp>
"},{"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\n#include <utility>\n\n#include <robot_dart/control/robot_control.hpp>\n#include <robot_dart/robot.hpp>\n\nnamespace robot_dart {\n    namespace control {\n\n        class PDControl : public RobotControl {\n        public:\n            PDControl();\n            PDControl(const Eigen::VectorXd& ctrl, bool full_control = false, bool use_angular_errors = true);\n            PDControl(const Eigen::VectorXd& ctrl, const std::vector<std::string>& controllable_dofs, bool use_angular_errors = true);\n\n            void configure() override;\n            Eigen::VectorXd calculate(double) override;\n\n            void set_pd(double p, double d);\n            void set_pd(const Eigen::VectorXd& p, const Eigen::VectorXd& d);\n\n            std::pair<Eigen::VectorXd, Eigen::VectorXd> pd() const;\n\n            bool using_angular_errors() const;\n            void set_use_angular_errors(bool enable = true);\n\n            std::shared_ptr<RobotControl> clone() const override;\n\n        protected:\n            Eigen::VectorXd _Kp;\n            Eigen::VectorXd _Kd;\n            bool _use_angular_errors;\n\n            static 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

  • #include <robot_dart/control/robot_control.hpp>
  • #include <robot_dart/robot.hpp>
"},{"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\n#include <robot_dart/control/robot_control.hpp>\n#include <robot_dart/robot.hpp>\n\nnamespace robot_dart {\n    namespace control {\n\n        template <typename Policy>\n        class PolicyControl : public RobotControl {\n        public:\n            PolicyControl() : RobotControl() {}\n            PolicyControl(double dt, const Eigen::VectorXd& ctrl, bool full_control = false) : RobotControl(ctrl, full_control), _dt(dt), _first(true), _full_dt(false) {}\n            PolicyControl(const Eigen::VectorXd& ctrl, bool full_control = false) : RobotControl(ctrl, full_control), _dt(0.), _first(true), _full_dt(true) {}\n            PolicyControl(double dt, const Eigen::VectorXd& ctrl, const std::vector<std::string>& controllable_dofs) : RobotControl(ctrl, controllable_dofs), _dt(dt), _first(true), _full_dt(false) {}\n            PolicyControl(const Eigen::VectorXd& ctrl, const std::vector<std::string>& controllable_dofs) : RobotControl(ctrl, controllable_dofs), _dt(0.), _first(true), _full_dt(true) {}\n\n            void configure() override\n            {\n                _policy.set_params(_ctrl);\n                if (_policy.output_size() == _control_dof)\n                    _active = true;\n                else\n                    ROBOT_DART_WARNING(_policy.output_size() != _control_dof, \"Control DoF != Policy output size. Policy is not active.\");\n                auto robot = _robot.lock();\n                if (_full_dt)\n                    _dt = robot->skeleton()->getTimeStep();\n                _first = true;\n                _i = 0;\n                _threshold = -robot->skeleton()->getTimeStep() * 0.5;\n            }\n\n            void set_h_params(const Eigen::VectorXd& h_params)\n            {\n                _policy.set_h_params(h_params);\n            }\n\n            Eigen::VectorXd h_params() const\n            {\n                return _policy.h_params();\n            }\n\n            Eigen::VectorXd calculate(double t) override\n            {\n                ROBOT_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));\n                if (_first || _full_dt || (t - _prev_time - _dt) >= _threshold) {\n                    _prev_commands = _policy.query(_robot.lock(), t);\n\n                    _first = false;\n                    _prev_time = t;\n                    _i++;\n                }\n\n                return _prev_commands;\n            }\n\n            std::shared_ptr<RobotControl> clone() const override\n            {\n                return std::make_shared<PolicyControl>(*this);\n            }\n\n        protected:\n            int _i;\n            Policy _policy;\n            double _dt, _prev_time, _threshold;\n            Eigen::VectorXd _prev_commands;\n            bool _first, _full_dt;\n        };\n    } // namespace control\n} // namespace robot_dart\n\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

  • #include \"robot_control.hpp\"
  • #include \"robot_dart/robot.hpp\"
  • #include \"robot_dart/utils.hpp\"
  • #include \"robot_dart/utils_headers_dart_dynamics.hpp\"
"},{"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\"\n\nnamespace robot_dart {\n    namespace control {\n        RobotControl::RobotControl() : _weight(1.), _active(false), _check_free(true) {}\n        RobotControl::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) {}\n        RobotControl::RobotControl(const Eigen::VectorXd& ctrl, bool full_control) : _ctrl(ctrl), _weight(1.), _active(false), _check_free(!full_control) {}\n\n        void RobotControl::set_parameters(const Eigen::VectorXd& ctrl)\n        {\n            _ctrl = ctrl;\n            _active = false;\n            init();\n        }\n\n        const Eigen::VectorXd& RobotControl::parameters() const\n        {\n            return _ctrl;\n        }\n\n        void RobotControl::init()\n        {\n            ROBOT_DART_ASSERT(_robot.use_count() > 0, \"RobotControl: parent robot should be initialized; use set_robot()\", );\n            auto robot = _robot.lock();\n            _dof = robot->skeleton()->getNumDofs();\n\n            if (_check_free && robot->free()) {\n                auto names = robot->dof_names(true, true, true);\n                _controllable_dofs = std::vector<std::string>(names.begin() + 6, names.end());\n            }\n            else if (_controllable_dofs.empty()) {\n                // we cannot control mimic, locked and passive joints\n                _controllable_dofs = robot->dof_names(true, true, true);\n            }\n\n            _control_dof = _controllable_dofs.size();\n\n            configure();\n        }\n\n        void RobotControl::set_robot(const std::shared_ptr<Robot>& robot)\n        {\n            _robot = robot;\n        }\n\n        std::shared_ptr<Robot> RobotControl::robot() const\n        {\n            return _robot.lock();\n        }\n\n        void RobotControl::activate(bool enable)\n        {\n            _active = false;\n            if (enable) {\n                init();\n            }\n        }\n\n        bool RobotControl::active() const\n        {\n            return _active;\n        }\n\n        const std::vector<std::string>& RobotControl::controllable_dofs() const { return _controllable_dofs; }\n\n        double RobotControl::weight() const\n        {\n            return _weight;\n        }\n\n        void 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

  • #include <robot_dart/utils.hpp>
  • #include <memory>
  • #include <vector>
"},{"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\n#include <robot_dart/utils.hpp>\n\n#include <memory>\n#include <vector>\n\nnamespace robot_dart {\n    class Robot;\n\n    namespace control {\n\n        class RobotControl {\n        public:\n            RobotControl();\n            RobotControl(const Eigen::VectorXd& ctrl, bool full_control = false);\n            RobotControl(const Eigen::VectorXd& ctrl, const std::vector<std::string>& controllable_dofs);\n            virtual ~RobotControl() {}\n\n            void set_parameters(const Eigen::VectorXd& ctrl);\n            const Eigen::VectorXd& parameters() const;\n\n            void init();\n\n            void set_robot(const std::shared_ptr<Robot>& robot);\n            std::shared_ptr<Robot> robot() const;\n\n            void activate(bool enable = true);\n            bool active() const;\n\n            const std::vector<std::string>& controllable_dofs() const;\n\n            double weight() const;\n            void set_weight(double weight);\n\n            virtual void configure() = 0;\n            // TO-DO: Maybe make this const?\n            virtual Eigen::VectorXd calculate(double t) = 0;\n            virtual std::shared_ptr<RobotControl> clone() const = 0;\n\n        protected:\n            std::weak_ptr<Robot> _robot;\n            Eigen::VectorXd _ctrl;\n            double _weight;\n            bool _active, _check_free = false;\n            int _dof, _control_dof;\n            std::vector<std::string> _controllable_dofs;\n        };\n    } // namespace control\n} // namespace robot_dart\n\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

  • #include \"simple_control.hpp\"
  • #include \"robot_dart/robot.hpp\"
  • #include \"robot_dart/utils.hpp\"
"},{"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\"\n\nnamespace robot_dart {\n    namespace control {\n        SimpleControl::SimpleControl() : RobotControl() {}\n        SimpleControl::SimpleControl(const Eigen::VectorXd& ctrl, bool full_control) : RobotControl(ctrl, full_control) {}\n        SimpleControl::SimpleControl(const Eigen::VectorXd& ctrl, const std::vector<std::string>& controllable_dofs) : RobotControl(ctrl, controllable_dofs) {}\n\n        void SimpleControl::configure()\n        {\n            if (_ctrl.size() == _control_dof)\n                _active = true;\n        }\n\n        Eigen::VectorXd SimpleControl::calculate(double)\n        {\n            ROBOT_DART_ASSERT(_control_dof == _ctrl.size(), \"SimpleControl: Controller parameters size is not the same as DOFs of the robot\", Eigen::VectorXd::Zero(_control_dof));\n            return _ctrl;\n        }\n\n        std::shared_ptr<RobotControl> SimpleControl::clone() const\n        {\n            return 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

  • #include <robot_dart/control/robot_control.hpp>
"},{"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\n#include <robot_dart/control/robot_control.hpp>\n\nnamespace robot_dart {\n    namespace control {\n\n        class SimpleControl : public RobotControl {\n        public:\n            SimpleControl();\n            SimpleControl(const Eigen::VectorXd& ctrl, bool full_control = false);\n            SimpleControl(const Eigen::VectorXd& ctrl, const std::vector<std::string>& controllable_dofs);\n\n            void configure() override;\n            Eigen::VectorXd calculate(double) override;\n            std::shared_ptr<RobotControl> clone() const override;\n        };\n    } // namespace control\n} // namespace robot_dart\n\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

  • #include <robot_dart/gui/helper.hpp>
"},{"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\n#include <robot_dart/gui/helper.hpp>\n\nnamespace robot_dart {\n    class RobotDARTSimu;\n\n    namespace gui {\n        class Base {\n        public:\n            Base() {}\n\n            virtual ~Base() {}\n\n            virtual void set_simu(RobotDARTSimu* simu) { _simu = simu; }\n            const RobotDARTSimu* simu() const { return _simu; }\n\n            virtual bool done() const { return false; }\n\n            virtual void refresh() {}\n\n            virtual void set_render_period(double) {}\n\n            virtual void set_enable(bool) {}\n            virtual void set_fps(int) {}\n\n            virtual Image image() { return Image(); }\n            virtual GrayscaleImage depth_image() { return GrayscaleImage(); }\n            virtual GrayscaleImage raw_depth_image() { return GrayscaleImage(); }\n            virtual DepthImage depth_array() { return DepthImage(); }\n\n            virtual size_t width() const { return 0; }\n            virtual size_t height() const { return 0; }\n\n        protected:\n            RobotDARTSimu* _simu = nullptr;\n        };\n    } // namespace gui\n} // namespace robot_dart\n\n#endif\n
"},{"location":"api/helper_8cpp/","title":"File helper.cpp","text":"

FileList > gui > helper.cpp

Go to the source code of this file

  • #include \"helper.hpp\"
  • #include \"stb_image_write.h\"
"},{"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\n#define STB_IMAGE_WRITE_IMPLEMENTATION\n#include \"stb_image_write.h\"\n\nnamespace robot_dart {\n    namespace gui {\n        void save_png_image(const std::string& filename, const Image& rgb)\n        {\n            auto ends_with = [](const std::string& value, const std::string& ending) {\n                if (ending.size() > value.size())\n                    return false;\n                return std::equal(ending.rbegin(), ending.rend(), value.rbegin());\n            };\n\n            std::string png = \".png\";\n            if (ends_with(filename, png))\n                png = \"\";\n\n            stbi_write_png((filename + png).c_str(), rgb.width, rgb.height, rgb.channels, rgb.data.data(), rgb.width * rgb.channels);\n        }\n\n        void save_png_image(const std::string& filename, const GrayscaleImage& gray)\n        {\n            auto ends_with = [](const std::string& value, const std::string& ending) {\n                if (ending.size() > value.size())\n                    return false;\n                return std::equal(ending.rbegin(), ending.rend(), value.rbegin());\n            };\n\n            std::string png = \".png\";\n            if (ends_with(filename, png))\n                png = \"\";\n\n            stbi_write_png((filename + png).c_str(), gray.width, gray.height, 1, gray.data.data(), gray.width);\n        }\n\n        GrayscaleImage convert_rgb_to_grayscale(const Image& rgb)\n        {\n            assert(rgb.channels == 3);\n            size_t width = rgb.width;\n            size_t height = rgb.height;\n\n            GrayscaleImage gray;\n            gray.width = width;\n            gray.height = height;\n            gray.data.resize(width * height);\n\n            for (size_t h = 0; h < height; h++) {\n                for (size_t w = 0; w < width; w++) {\n                    int id = w + h * width;\n                    int id_rgb = w * rgb.channels + h * (width * rgb.channels);\n                    uint8_t color = 0.3 * rgb.data[id_rgb + 0] + 0.59 * rgb.data[id_rgb + 1] + 0.11 * rgb.data[id_rgb + 2];\n                    gray.data[id] = color;\n                }\n            }\n\n            return gray;\n        }\n\n        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)\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/.\n            auto point_3d = [](const Eigen::Matrix3d& K, size_t u, size_t v, double depth) {\n                double fx = K(0, 0);\n                double fy = K(1, 1);\n                double cx = K(0, 2);\n                double cy = K(1, 2);\n                double gamma = K(0, 1);\n\n                Eigen::Vector3d p;\n                p << 0., 0., -depth;\n\n                p(1) = (cy - v) * depth / fy;\n                p(0) = -((cx - u) * depth - gamma * p(1)) / fx;\n\n                return p;\n            };\n\n            std::vector<Eigen::Vector3d> point_cloud;\n\n            size_t height = depth_image.height;\n            size_t width = depth_image.width;\n            for (size_t h = 0; h < height; h++) {\n                for (size_t w = 0; w < width; w++) {\n                    int id = w + h * width;\n                    if (depth_image.data[id] >= 0.99 * far_plane) // close to far plane\n                        continue;\n                    Eigen::Vector4d pp;\n                    pp.head(3) = point_3d(intrinsic_matrix, w, h, depth_image.data[id]);\n                    pp.tail(1) << 1.;\n                    pp = tf.inverse() * pp;\n\n                    point_cloud.push_back(pp.head(3));\n                }\n            }\n\n            return 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

  • #include <string>
  • #include <vector>
  • #include <robot_dart/utils.hpp>
"},{"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\n#include <string>\n#include <vector>\n\n#include <robot_dart/utils.hpp>\n\nnamespace robot_dart {\n    namespace gui {\n        struct Image {\n            size_t width = 0, height = 0;\n            size_t channels = 3;\n            std::vector<uint8_t> data;\n        };\n\n        struct GrayscaleImage {\n            size_t width = 0, height = 0;\n            std::vector<uint8_t> data;\n        };\n\n        struct DepthImage {\n            size_t width = 0, height = 0;\n            std::vector<double> data;\n        };\n\n        void save_png_image(const std::string& filename, const Image& rgb);\n        void save_png_image(const std::string& filename, const GrayscaleImage& gray);\n\n        GrayscaleImage convert_rgb_to_grayscale(const Image& rgb);\n\n        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 = 1000.);\n    } // namespace gui\n} // namespace robot_dart\n\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

  • #include \"base_application.hpp\"
  • #include <robot_dart/gui/magnum/gs/helper.hpp>
  • #include <robot_dart/robot_dart_simu.hpp>
  • #include <robot_dart/utils.hpp>
  • #include <robot_dart/utils_headers_dart_dynamics.hpp>
  • #include <Corrade/Containers/StridedArrayView.h>
  • #include <Corrade/Utility/Resource.h>
  • #include <Magnum/GL/CubeMapTexture.h>
  • #include <Magnum/GL/DefaultFramebuffer.h>
  • #include <Magnum/GL/Renderer.h>
  • #include <Magnum/GL/Texture.h>
  • #include <Magnum/GL/TextureFormat.h>
  • #include <Magnum/MeshTools/Compile.h>
  • #include <Magnum/MeshTools/CompressIndices.h>
  • #include <Magnum/MeshTools/Interleave.h>
  • #include <Magnum/Primitives/Axis.h>
  • #include <Magnum/Primitives/Square.h>
  • #include <Magnum/Trade/MeshData.h>
  • #include <Magnum/Trade/PhongMaterialData.h>
"},{"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":"

File: api/base__application_8cpp_source.md

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

  • #include <mutex>
  • #include <unistd.h>
  • #include <unordered_map>
  • #include <robot_dart/gui/helper.hpp>
  • #include <robot_dart/gui/magnum/drawables.hpp>
  • #include <robot_dart/gui/magnum/gs/camera.hpp>
  • #include <robot_dart/gui/magnum/gs/cube_map.hpp>
  • #include <robot_dart/gui/magnum/gs/cube_map_color.hpp>
  • #include <robot_dart/gui/magnum/gs/phong_multi_light.hpp>
  • #include <robot_dart/gui/magnum/gs/shadow_map.hpp>
  • #include <robot_dart/gui/magnum/gs/shadow_map_color.hpp>
  • #include <robot_dart/gui/magnum/types.hpp>
  • #include <robot_dart/utils_headers_external_gui.hpp>
  • #include <Magnum/GL/CubeMapTextureArray.h>
  • #include <Magnum/GL/Framebuffer.h>
  • #include <Magnum/GL/Mesh.h>
  • #include <Magnum/GL/TextureArray.h>
  • #include <Magnum/Platform/GLContext.h>
  • #include <Magnum/Platform/WindowlessEglApplication.h>
  • #include <Magnum/Shaders/DistanceFieldVector.h>
  • #include <Magnum/Shaders/Flat.h>
  • #include <Magnum/Shaders/VertexColor.h>
  • #include <Magnum/Text/AbstractFont.h>
  • #include <Magnum/Text/DistanceFieldGlyphCache.h>
  • #include <Magnum/Text/Renderer.h>
"},{"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 (\n    name\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 (\n    name,\n    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
"},{"location":"api/base__application_8hpp/#define-release_gl_context","title":"define release_gl_context","text":"
#define release_gl_context (\n    name\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\n#include <mutex>\n#include <unistd.h>\n#include <unordered_map>\n\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\n#include <robot_dart/utils_headers_external_gui.hpp>\n\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\n#include <Magnum/Text/AbstractFont.h>\n#include <Magnum/Text/DistanceFieldGlyphCache.h>\n#include <Magnum/Text/Renderer.h>\n\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\n#define get_gl_context(name) get_gl_context_with_sleep(name, 0)\n\n#define release_gl_context(name) robot_dart::gui::magnum::GlobalData::instance()->free_gl_context(name);\n\nnamespace robot_dart {\n    namespace gui {\n        namespace magnum {\n            struct GlobalData {\n            public:\n                static GlobalData* instance()\n                {\n                    static GlobalData gdata;\n                    return &gdata;\n                }\n\n                GlobalData(const GlobalData&) = delete;\n                void operator=(const GlobalData&) = delete;\n\n                Magnum::Platform::WindowlessGLContext* gl_context();\n                void free_gl_context(Magnum::Platform::WindowlessGLContext* context);\n\n                /* You should call this before starting to draw or after finished */\n                void set_max_contexts(size_t N);\n\n            private:\n                GlobalData() = default;\n                ~GlobalData() = default;\n\n                void _create_contexts();\n\n                std::vector<Magnum::Platform::WindowlessGLContext> _gl_contexts;\n                std::vector<bool> _used;\n                std::mutex _context_mutex;\n                size_t _max_contexts = 4;\n            };\n\n            struct GraphicsConfiguration {\n                // General\n                size_t width = 640;\n                size_t height = 480;\n                std::string title = \"DART\";\n\n                // Shadows\n                bool shadowed = true;\n                bool transparent_shadows = true;\n                size_t shadow_map_size = 1024;\n\n                // Lights\n                size_t max_lights = 3;\n                double specular_strength = 0.25; // strength of the specular component\n\n                // These options are only for the main camera\n                bool draw_main_camera = true;\n                bool draw_debug = true;\n                bool draw_text = true;\n\n                // Background (default = black)\n                Eigen::Vector4d bg_color{0.0, 0.0, 0.0, 1.0};\n            };\n\n            struct DebugDrawData {\n                Magnum::Shaders::VertexColorGL3D* axes_shader;\n                Magnum::GL::Mesh* axes_mesh;\n                Magnum::Shaders::FlatGL2D* background_shader;\n                Magnum::GL::Mesh* background_mesh;\n\n                Magnum::Shaders::DistanceFieldVectorGL2D* text_shader;\n                Magnum::GL::Buffer* text_vertices;\n                Magnum::GL::Buffer* text_indices;\n                Magnum::Text::AbstractFont* font;\n                Magnum::Text::DistanceFieldGlyphCache* cache;\n            };\n\n            class BaseApplication {\n            public:\n                BaseApplication(const GraphicsConfiguration& configuration = GraphicsConfiguration());\n                virtual ~BaseApplication() {}\n\n                void init(RobotDARTSimu* simu, const GraphicsConfiguration& configuration);\n\n                void clear_lights();\n                void add_light(const gs::Light& light);\n                gs::Light& light(size_t i);\n                std::vector<gs::Light>& lights();\n                size_t num_lights() const;\n\n                Magnum::SceneGraph::DrawableGroup3D& drawables() { return _drawables; }\n                Scene3D& scene() { return _scene; }\n                gs::Camera& camera() { return *_camera; }\n                const gs::Camera& camera() const { return *_camera; }\n\n                bool done() const;\n\n                void look_at(const Eigen::Vector3d& camera_pos,\n                    const Eigen::Vector3d& look_at,\n                    const Eigen::Vector3d& up);\n\n                virtual void render() {}\n\n                void update_lights(const gs::Camera& camera);\n                void update_graphics();\n                void render_shadows();\n\n                bool attach_camera(gs::Camera& camera, dart::dynamics::BodyNode* body);\n\n                // video (FPS is mandatory here, see the Graphics class for automatic computation)\n                void record_video(const std::string& video_fname, int fps) { _camera->record_video(video_fname, fps); }\n\n                bool shadowed() const { return _shadowed; }\n                bool transparent_shadows() const { return _transparent_shadows; }\n                void enable_shadows(bool enable = true, bool drawTransparentShadows = false);\n\n                Corrade::Containers::Optional<Magnum::Image2D>& image() { return _camera->image(); }\n\n                // This is for visualization purposes\n                GrayscaleImage depth_image();\n\n                // Image filled with depth buffer values\n                GrayscaleImage raw_depth_image();\n\n                // \"Image\" filled with depth buffer values (this returns an array of doubles)\n                DepthImage depth_array();\n\n                // Access to debug data\n                DebugDrawData debug_draw_data()\n                {\n                    DebugDrawData data;\n                    data.axes_shader = _3D_axis_shader.get();\n                    data.background_shader = _background_shader.get();\n                    data.axes_mesh = _3D_axis_mesh.get();\n                    data.background_mesh = _background_mesh.get();\n                    data.text_shader = _text_shader.get();\n                    data.text_vertices = _text_vertices.get();\n                    data.text_indices = _text_indices.get();\n                    data.font = _font.get();\n                    data.cache = _glyph_cache.get();\n\n                    return data;\n                }\n\n            protected:\n                /* Magnum */\n                Scene3D _scene;\n                Magnum::SceneGraph::DrawableGroup3D _drawables, _shadowed_drawables, _shadowed_color_drawables, _cubemap_drawables, _cubemap_color_drawables;\n                std::unique_ptr<gs::PhongMultiLight> _color_shader, _texture_shader;\n\n                std::unique_ptr<gs::Camera> _camera;\n\n                bool _done = false;\n\n                /* GUI Config */\n                GraphicsConfiguration _configuration;\n\n                /* DART */\n                RobotDARTSimu* _simu;\n                std::unique_ptr<Magnum::DartIntegration::World> _dart_world;\n                std::unordered_map<Magnum::DartIntegration::Object*, ObjectStruct*> _drawable_objects;\n                std::vector<gs::Light> _lights;\n\n                /* Shadows */\n                bool _shadowed = true, _transparent_shadows = false;\n                int _transparentSize = 0;\n                std::unique_ptr<gs::ShadowMap> _shadow_shader, _shadow_texture_shader;\n                std::unique_ptr<gs::ShadowMapColor> _shadow_color_shader, _shadow_texture_color_shader;\n                std::unique_ptr<gs::CubeMap> _cubemap_shader, _cubemap_texture_shader;\n                std::unique_ptr<gs::CubeMapColor> _cubemap_color_shader, _cubemap_texture_color_shader;\n                std::vector<ShadowData> _shadow_data;\n                std::unique_ptr<Magnum::GL::Texture2DArray> _shadow_texture, _shadow_color_texture;\n                std::unique_ptr<Magnum::GL::CubeMapTextureArray> _shadow_cube_map, _shadow_color_cube_map;\n                int _max_lights = 5;\n                int _shadow_map_size = 512;\n                std::unique_ptr<Camera3D> _shadow_camera;\n                Object3D* _shadow_camera_object;\n\n                /* Debug visualization */\n                std::unique_ptr<Magnum::GL::Mesh> _3D_axis_mesh;\n                std::unique_ptr<Magnum::Shaders::VertexColorGL3D> _3D_axis_shader;\n                std::unique_ptr<Magnum::GL::Mesh> _background_mesh;\n                std::unique_ptr<Magnum::Shaders::FlatGL2D> _background_shader;\n\n                /* Text visualization */\n                std::unique_ptr<Magnum::Shaders::DistanceFieldVectorGL2D> _text_shader;\n                Corrade::PluginManager::Manager<Magnum::Text::AbstractFont> _font_manager;\n                Corrade::Containers::Pointer<Magnum::Text::DistanceFieldGlyphCache> _glyph_cache;\n                Corrade::Containers::Pointer<Magnum::Text::AbstractFont> _font;\n                Corrade::Containers::Pointer<Magnum::GL::Buffer> _text_vertices;\n                Corrade::Containers::Pointer<Magnum::GL::Buffer> _text_indices;\n\n                /* Importer */\n                Corrade::PluginManager::Manager<Magnum::Trade::AbstractImporter> _importer_manager;\n\n                void _gl_clean_up();\n                void _prepare_shadows();\n            };\n\n            template <typename T>\n            inline BaseApplication* make_application(RobotDARTSimu* simu, const GraphicsConfiguration& configuration = GraphicsConfiguration())\n            {\n                int argc = 0;\n                char** argv = NULL;\n\n                return 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\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

  • #include <robot_dart/gui/base.hpp>
  • #include <robot_dart/gui/magnum/glfw_application.hpp>
  • #include <robot_dart/gui/magnum/gs/helper.hpp>
  • #include <robot_dart/gui/magnum/utils_headers_eigen.hpp>
  • #include <robot_dart/robot_dart_simu.hpp>
  • #include <Corrade/Utility/Resource.h>
"},{"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 () \n

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\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\n// We need this for CORRADE_RESOURCE_INITIALIZE\n#include <Corrade/Utility/Resource.h>\n\ninline static void robot_dart_initialize_magnum_resources()\n{\n    CORRADE_RESOURCE_INITIALIZE(RobotDARTShaders);\n}\n\nnamespace robot_dart {\n    namespace gui {\n        namespace magnum {\n            template <typename T = GlfwApplication>\n            class BaseGraphics : public Base {\n            public:\n                BaseGraphics(const GraphicsConfiguration& configuration = GraphicsConfiguration())\n                    : _configuration(configuration), _enabled(true)\n                {\n                    robot_dart_initialize_magnum_resources();\n                }\n\n                virtual ~BaseGraphics() {}\n\n                virtual void set_simu(RobotDARTSimu* simu) override\n                {\n                    ROBOT_DART_EXCEPTION_ASSERT(simu, \"Simulation pointer is null!\");\n                    _simu = simu;\n                    _magnum_app.reset(make_application<T>(simu, _configuration));\n                }\n\n                size_t width() const override\n                {\n                    ROBOT_DART_EXCEPTION_ASSERT(_magnum_app, \"MagnumApp pointer is null!\");\n                    return _magnum_app->camera().width();\n                }\n\n                size_t height() const override\n                {\n                    ROBOT_DART_EXCEPTION_ASSERT(_magnum_app, \"MagnumApp pointer is null!\");\n                    return _magnum_app->camera().height();\n                }\n\n                bool done() const override\n                {\n                    ROBOT_DART_EXCEPTION_ASSERT(_magnum_app, \"MagnumApp pointer is null!\");\n                    return _magnum_app->done();\n                }\n\n                void refresh() override\n                {\n                    if (!_enabled)\n                        return;\n\n                    ROBOT_DART_EXCEPTION_ASSERT(_magnum_app, \"MagnumApp pointer is null!\");\n                    _magnum_app->render();\n                }\n\n                void set_enable(bool enable) override\n                {\n                    _enabled = enable;\n                }\n\n                void set_fps(int fps) override { _fps = fps; }\n\n                void look_at(const Eigen::Vector3d& camera_pos,\n                    const Eigen::Vector3d& look_at = Eigen::Vector3d(0, 0, 0),\n                    const Eigen::Vector3d& up = Eigen::Vector3d(0, 0, 1))\n                {\n                    ROBOT_DART_EXCEPTION_ASSERT(_magnum_app, \"MagnumApp pointer is null!\");\n                    _magnum_app->look_at(camera_pos, look_at, up);\n                }\n\n                void clear_lights()\n                {\n                    ROBOT_DART_EXCEPTION_ASSERT(_magnum_app, \"MagnumApp pointer is null!\");\n                    _magnum_app->clear_lights();\n                }\n\n                void add_light(const magnum::gs::Light& light)\n                {\n                    ROBOT_DART_EXCEPTION_ASSERT(_magnum_app, \"MagnumApp pointer is null!\");\n                    _magnum_app->add_light(light);\n                }\n\n                std::vector<gs::Light>& lights()\n                {\n                    ROBOT_DART_EXCEPTION_ASSERT(_magnum_app, \"MagnumApp pointer is null!\");\n                    return _magnum_app->lights();\n                }\n\n                size_t num_lights() const\n                {\n                    ROBOT_DART_EXCEPTION_ASSERT(_magnum_app, \"MagnumApp pointer is null!\");\n                    return _magnum_app->num_lights();\n                }\n\n                magnum::gs::Light& light(size_t i)\n                {\n                    ROBOT_DART_EXCEPTION_ASSERT(_magnum_app, \"MagnumApp pointer is null!\");\n                    return _magnum_app->light(i);\n                }\n\n                void record_video(const std::string& video_fname, int fps = -1)\n                {\n                    int fps_computed = (fps == -1) ? _fps : fps;\n                    ROBOT_DART_EXCEPTION_ASSERT(fps_computed != -1, \"Video FPS not set!\");\n                    ROBOT_DART_EXCEPTION_ASSERT(_magnum_app, \"MagnumApp pointer is null!\");\n\n                    _magnum_app->record_video(video_fname, fps_computed);\n                }\n\n                bool shadowed() const\n                {\n                    ROBOT_DART_EXCEPTION_ASSERT(_magnum_app, \"MagnumApp pointer is null!\");\n                    return _magnum_app->shadowed();\n                }\n\n                bool transparent_shadows() const\n                {\n                    ROBOT_DART_EXCEPTION_ASSERT(_magnum_app, \"MagnumApp pointer is null!\");\n                    return _magnum_app->transparent_shadows();\n                }\n\n                void enable_shadows(bool enable = true, bool transparent = true)\n                {\n                    ROBOT_DART_EXCEPTION_ASSERT(_magnum_app, \"MagnumApp pointer is null!\");\n                    _magnum_app->enable_shadows(enable, transparent);\n                }\n\n                Magnum::Image2D* magnum_image()\n                {\n                    ROBOT_DART_EXCEPTION_ASSERT(_magnum_app, \"MagnumApp pointer is null!\");\n                    if (_magnum_app->image())\n                        return &(*_magnum_app->image());\n                    return nullptr;\n                }\n\n                Image image() override\n                {\n                    auto image = magnum_image();\n                    if (image)\n                        return gs::rgb_from_image(image);\n                    return Image();\n                }\n\n                GrayscaleImage depth_image() override\n                {\n                    ROBOT_DART_EXCEPTION_ASSERT(_magnum_app, \"MagnumApp pointer is null!\");\n                    return _magnum_app->depth_image();\n                }\n\n                GrayscaleImage raw_depth_image() override\n                {\n                    ROBOT_DART_EXCEPTION_ASSERT(_magnum_app, \"MagnumApp pointer is null!\");\n                    return _magnum_app->raw_depth_image();\n                }\n\n                DepthImage depth_array() override\n                {\n                    ROBOT_DART_EXCEPTION_ASSERT(_magnum_app, \"MagnumApp pointer is null!\");\n                    return _magnum_app->depth_array();\n                }\n\n                gs::Camera& camera()\n                {\n                    ROBOT_DART_EXCEPTION_ASSERT(_magnum_app, \"MagnumApp pointer is null!\");\n                    return _magnum_app->camera();\n                }\n\n                const gs::Camera& camera() const\n                {\n                    ROBOT_DART_EXCEPTION_ASSERT(_magnum_app, \"MagnumApp pointer is null!\");\n                    return _magnum_app->camera();\n                }\n\n                Eigen::Matrix3d camera_intrinsic_matrix() const\n                {\n                    ROBOT_DART_EXCEPTION_ASSERT(_magnum_app, \"MagnumApp pointer is null!\");\n                    return Magnum::EigenIntegration::cast<Eigen::Matrix3d>(Magnum::Matrix3d(_magnum_app->camera().intrinsic_matrix()));\n                }\n\n                Eigen::Matrix4d camera_extrinsic_matrix() const\n                {\n                    ROBOT_DART_EXCEPTION_ASSERT(_magnum_app, \"MagnumApp pointer is null!\");\n                    return Magnum::EigenIntegration::cast<Eigen::Matrix4d>(Magnum::Matrix4d(_magnum_app->camera().extrinsic_matrix()));\n                }\n\n                BaseApplication* magnum_app()\n                {\n                    ROBOT_DART_EXCEPTION_ASSERT(_magnum_app, \"MagnumApp pointer is null!\");\n                    return &*_magnum_app;\n                }\n\n                const BaseApplication* magnum_app() const\n                {\n                    ROBOT_DART_EXCEPTION_ASSERT(_magnum_app, \"MagnumApp pointer is null!\");\n                    return &*_magnum_app;\n                }\n\n            protected:\n                GraphicsConfiguration _configuration;\n                bool _enabled;\n                int _fps;\n                std::unique_ptr<BaseApplication> _magnum_app;\n\n                Corrade::Utility::Debug _magnum_silence_output{nullptr};\n            };\n        } // namespace magnum\n    } // namespace gui\n} // namespace robot_dart\n\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

  • #include <robot_dart/gui/magnum/drawables.hpp>
  • #include <robot_dart/gui_data.hpp>
  • #include <robot_dart/robot_dart_simu.hpp>
  • #include <robot_dart/utils.hpp>
  • #include <Magnum/GL/CubeMapTexture.h>
  • #include <Magnum/GL/DefaultFramebuffer.h>
  • #include <Magnum/GL/Mesh.h>
  • #include <Magnum/GL/Renderer.h>
  • #include <Magnum/GL/AbstractFramebuffer.h>
  • #include <Magnum/GL/GL.h>
"},{"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\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\n#include <Magnum/GL/AbstractFramebuffer.h>\n#include <Magnum/GL/GL.h>\n\nnamespace robot_dart {\n    namespace gui {\n        namespace magnum {\n            // DrawableObject\n            DrawableObject::DrawableObject(\n                RobotDARTSimu* simu,\n                dart::dynamics::ShapeNode* shape,\n                const std::vector<std::reference_wrapper<Magnum::GL::Mesh>>& meshes,\n                const std::vector<gs::Material>& materials,\n                gs::PhongMultiLight& color,\n                gs::PhongMultiLight& texture,\n                Object3D* parent,\n                Magnum::SceneGraph::DrawableGroup3D* group)\n                : Object3D{parent},\n                  Magnum::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            }\n\n            DrawableObject& DrawableObject::set_meshes(const std::vector<std::reference_wrapper<Magnum::GL::Mesh>>& meshes)\n            {\n                _meshes = meshes;\n                return *this;\n            }\n\n            DrawableObject& DrawableObject::set_materials(const std::vector<gs::Material>& materials)\n            {\n                _materials = materials;\n                return *this;\n            }\n\n            DrawableObject& DrawableObject::set_soft_bodies(const std::vector<bool>& softBody)\n            {\n                _is_soft_body = softBody;\n                return *this;\n            }\n\n            DrawableObject& DrawableObject::set_scalings(const std::vector<Magnum::Vector3>& scalings)\n            {\n                _scalings = scalings;\n\n                _has_negative_scaling.resize(_scalings.size());\n                for (size_t i = 0; i < scalings.size(); i++) {\n                    _has_negative_scaling[i] = false;\n                    for (size_t j = 0; j < 3; j++)\n                        if (_scalings[i][j] < 0.f) {\n                            _has_negative_scaling[i] = true;\n                            break;\n                        }\n                }\n\n                return *this;\n            }\n\n            DrawableObject& DrawableObject::set_transparent(bool transparent)\n            {\n                _isTransparent = transparent;\n                return *this;\n            }\n\n            DrawableObject& DrawableObject::set_color_shader(std::reference_wrapper<gs::PhongMultiLight> shader)\n            {\n                _color_shader = shader;\n                return *this;\n            }\n\n            DrawableObject& DrawableObject::set_texture_shader(std::reference_wrapper<gs::PhongMultiLight> shader)\n            {\n                _texture_shader = shader;\n                return *this;\n            }\n\n            void DrawableObject::draw(const Magnum::Matrix4& transformationMatrix, Magnum::SceneGraph::Camera3D& camera)\n            {\n                for (size_t i = 0; i < _meshes.size(); i++) {\n                    Magnum::GL::Mesh& mesh = _meshes[i];\n                    Magnum::Matrix4 scalingMatrix = Magnum::Matrix4::scaling(_scalings[i]);\n                    bool isColor = !_materials[i].has_diffuse_texture();\n                    if (_is_soft_body[i])\n                        Magnum::GL::Renderer::disable(Magnum::GL::Renderer::Feature::FaceCulling);\n                    else if (_has_negative_scaling[i])\n                        Magnum::GL::Renderer::setFaceCullingMode(Magnum::GL::Renderer::PolygonFacing::Front);\n                    if (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                    }\n                    else {\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                    }\n\n                    if (_is_soft_body[i])\n                        Magnum::GL::Renderer::enable(Magnum::GL::Renderer::Feature::FaceCulling);\n                    else if (_has_negative_scaling[i])\n                        Magnum::GL::Renderer::setFaceCullingMode(Magnum::GL::Renderer::PolygonFacing::Back);\n                }\n            }\n\n            // ShadowedObject\n            ShadowedObject::ShadowedObject(\n                RobotDARTSimu* simu,\n                dart::dynamics::ShapeNode* shape,\n                const std::vector<std::reference_wrapper<Magnum::GL::Mesh>>& meshes,\n                gs::ShadowMap& shader,\n                gs::ShadowMap& texture_shader,\n                Object3D* parent,\n                Magnum::SceneGraph::DrawableGroup3D* group)\n                : Object3D{parent},\n                  Magnum::SceneGraph::Drawable3D{*this, group},\n                  _simu(simu),\n                  _shape(shape),\n                  _meshes{meshes},\n                  _shader{shader},\n                  _texture_shader(texture_shader) {}\n\n            ShadowedObject& ShadowedObject::set_meshes(const std::vector<std::reference_wrapper<Magnum::GL::Mesh>>& meshes)\n            {\n                _meshes = meshes;\n                return *this;\n            }\n\n            ShadowedObject& ShadowedObject::set_materials(const std::vector<gs::Material>& materials)\n            {\n                _materials = materials;\n                return *this;\n            }\n\n            ShadowedObject& ShadowedObject::set_scalings(const std::vector<Magnum::Vector3>& scalings)\n            {\n                _scalings = scalings;\n                return *this;\n            }\n\n            void ShadowedObject::draw(const Magnum::Matrix4& transformationMatrix, Magnum::SceneGraph::Camera3D& camera)\n            {\n                if (!_simu->gui_data()->cast_shadows(_shape))\n                    return;\n                for (size_t i = 0; i < _meshes.size(); i++) {\n                    Magnum::GL::Mesh& mesh = _meshes[i];\n                    Magnum::Matrix4 scalingMatrix = Magnum::Matrix4::scaling(_scalings[i]);\n                    bool isColor = !_materials[i].has_diffuse_texture();\n                    if (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                    }\n                    else {\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\n            // ShadowedColorObject\n            ShadowedColorObject::ShadowedColorObject(\n                RobotDARTSimu* simu,\n                dart::dynamics::ShapeNode* shape,\n                const std::vector<std::reference_wrapper<Magnum::GL::Mesh>>& meshes,\n                gs::ShadowMapColor& shader,\n                gs::ShadowMapColor& texture_shader,\n                Object3D* parent,\n                Magnum::SceneGraph::DrawableGroup3D* group)\n                : Object3D{parent},\n                  Magnum::SceneGraph::Drawable3D{*this, group},\n                  _simu(simu),\n                  _shape(shape),\n                  _meshes{meshes},\n                  _shader{shader},\n                  _texture_shader(texture_shader) {}\n\n            ShadowedColorObject& ShadowedColorObject::set_meshes(const std::vector<std::reference_wrapper<Magnum::GL::Mesh>>& meshes)\n            {\n                _meshes = meshes;\n                return *this;\n            }\n\n            ShadowedColorObject& ShadowedColorObject::set_materials(const std::vector<gs::Material>& materials)\n            {\n                _materials = materials;\n                return *this;\n            }\n\n            ShadowedColorObject& ShadowedColorObject::set_scalings(const std::vector<Magnum::Vector3>& scalings)\n            {\n                _scalings = scalings;\n                return *this;\n            }\n\n            void ShadowedColorObject::draw(const Magnum::Matrix4& transformationMatrix, Magnum::SceneGraph::Camera3D& camera)\n            {\n                if (!_simu->gui_data()->cast_shadows(_shape))\n                    return;\n                for (size_t i = 0; i < _meshes.size(); i++) {\n                    Magnum::GL::Mesh& mesh = _meshes[i];\n                    Magnum::Matrix4 scalingMatrix = Magnum::Matrix4::scaling(_scalings[i]);\n                    bool isColor = !_materials[i].has_diffuse_texture();\n                    if (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                    }\n                    else {\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\n            // CubeMapShadowedObject\n            CubeMapShadowedObject::CubeMapShadowedObject(\n                RobotDARTSimu* simu,\n                dart::dynamics::ShapeNode* shape,\n                const std::vector<std::reference_wrapper<Magnum::GL::Mesh>>& meshes,\n                gs::CubeMap& shader,\n                gs::CubeMap& texture_shader,\n                Object3D* parent,\n                Magnum::SceneGraph::DrawableGroup3D* group)\n                : Object3D{parent},\n                  Magnum::SceneGraph::Drawable3D{*this, group},\n                  _simu(simu),\n                  _shape(shape),\n                  _meshes{meshes},\n                  _shader{shader},\n                  _texture_shader(texture_shader) {}\n\n            CubeMapShadowedObject& CubeMapShadowedObject::set_meshes(const std::vector<std::reference_wrapper<Magnum::GL::Mesh>>& meshes)\n            {\n                _meshes = meshes;\n                return *this;\n            }\n\n            CubeMapShadowedObject& CubeMapShadowedObject::set_materials(const std::vector<gs::Material>& materials)\n            {\n                _materials = materials;\n                return *this;\n            }\n\n            CubeMapShadowedObject& CubeMapShadowedObject::set_scalings(const std::vector<Magnum::Vector3>& scalings)\n            {\n                _scalings = scalings;\n                return *this;\n            }\n\n            void CubeMapShadowedObject::draw(const Magnum::Matrix4&, Magnum::SceneGraph::Camera3D&)\n            {\n                for (size_t i = 0; i < _meshes.size(); i++) {\n                    Magnum::GL::Mesh& mesh = _meshes[i];\n                    Magnum::Matrix4 scalingMatrix = Magnum::Matrix4::scaling(_scalings[i]);\n                    bool isColor = !_materials[i].has_diffuse_texture();\n                    if (isColor) {\n                        (_shader.get())\n                            .set_transformation_matrix(absoluteTransformation() * scalingMatrix)\n                            .set_material(_materials[i])\n                            .draw(mesh);\n                    }\n                    else {\n                        (_texture_shader.get())\n                            .set_transformation_matrix(absoluteTransformation() * scalingMatrix)\n                            .set_material(_materials[i])\n                            .draw(mesh);\n                    }\n                }\n            }\n\n            // CubeMapShadowedColorObject\n            CubeMapShadowedColorObject::CubeMapShadowedColorObject(\n                RobotDARTSimu* simu,\n                dart::dynamics::ShapeNode* shape,\n                const std::vector<std::reference_wrapper<Magnum::GL::Mesh>>& meshes,\n                gs::CubeMapColor& shader,\n                gs::CubeMapColor& texture_shader,\n                Object3D* parent,\n                Magnum::SceneGraph::DrawableGroup3D* group)\n                : Object3D{parent},\n                  Magnum::SceneGraph::Drawable3D{*this, group},\n                  _simu(simu),\n                  _shape(shape),\n                  _meshes{meshes},\n                  _shader{shader},\n                  _texture_shader(texture_shader) {}\n\n            CubeMapShadowedColorObject& CubeMapShadowedColorObject::set_meshes(const std::vector<std::reference_wrapper<Magnum::GL::Mesh>>& meshes)\n            {\n                _meshes = meshes;\n                return *this;\n            }\n\n            CubeMapShadowedColorObject& CubeMapShadowedColorObject::set_materials(const std::vector<gs::Material>& materials)\n            {\n                _materials = materials;\n                return *this;\n            }\n\n            CubeMapShadowedColorObject& CubeMapShadowedColorObject::set_scalings(const std::vector<Magnum::Vector3>& scalings)\n            {\n                _scalings = scalings;\n                return *this;\n            }\n\n            void CubeMapShadowedColorObject::draw(const Magnum::Matrix4&, Magnum::SceneGraph::Camera3D&)\n            {\n                if (!_simu->gui_data()->cast_shadows(_shape))\n                    return;\n                for (size_t i = 0; i < _meshes.size(); i++) {\n                    Magnum::GL::Mesh& mesh = _meshes[i];\n                    Magnum::Matrix4 scalingMatrix = Magnum::Matrix4::scaling(_scalings[i]);\n                    bool isColor = !_materials[i].has_diffuse_texture();\n                    if (isColor) {\n                        (_shader.get())\n                            .set_transformation_matrix(absoluteTransformation() * scalingMatrix)\n                            .set_material(_materials[i])\n                            .draw(mesh);\n                    }\n                    else {\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

  • #include <robot_dart/gui/helper.hpp>
  • #include <robot_dart/gui/magnum/gs/cube_map.hpp>
  • #include <robot_dart/gui/magnum/gs/cube_map_color.hpp>
  • #include <robot_dart/gui/magnum/gs/phong_multi_light.hpp>
  • #include <robot_dart/gui/magnum/gs/shadow_map.hpp>
  • #include <robot_dart/gui/magnum/gs/shadow_map_color.hpp>
  • #include <robot_dart/gui/magnum/types.hpp>
  • #include <Magnum/GL/Framebuffer.h>
  • #include <Magnum/SceneGraph/Drawable.h>
"},{"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\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\n#include <Magnum/GL/Framebuffer.h>\n\n#include <Magnum/SceneGraph/Drawable.h>\n\nnamespace dart {\n    namespace dynamics {\n        class ShapeNode;\n    }\n} // namespace dart\n\nnamespace robot_dart {\n    class RobotDARTSimu;\n\n    namespace gui {\n        namespace magnum {\n            class DrawableObject : public Object3D, public Magnum::SceneGraph::Drawable3D {\n            public:\n                explicit DrawableObject(\n                    RobotDARTSimu* simu,\n                    dart::dynamics::ShapeNode* shape,\n                    const std::vector<std::reference_wrapper<Magnum::GL::Mesh>>& meshes,\n                    const std::vector<gs::Material>& materials,\n                    gs::PhongMultiLight& color,\n                    gs::PhongMultiLight& texture,\n                    Object3D* parent,\n                    Magnum::SceneGraph::DrawableGroup3D* group);\n\n                DrawableObject& set_meshes(const std::vector<std::reference_wrapper<Magnum::GL::Mesh>>& meshes);\n                DrawableObject& set_materials(const std::vector<gs::Material>& materials);\n                DrawableObject& set_soft_bodies(const std::vector<bool>& softBody);\n                DrawableObject& set_scalings(const std::vector<Magnum::Vector3>& scalings);\n                DrawableObject& set_transparent(bool transparent = true);\n\n                DrawableObject& set_color_shader(std::reference_wrapper<gs::PhongMultiLight> shader);\n                DrawableObject& set_texture_shader(std::reference_wrapper<gs::PhongMultiLight> shader);\n\n                const std::vector<gs::Material>& materials() const { return _materials; }\n                bool transparent() const { return _isTransparent; }\n\n                RobotDARTSimu* simu() const { return _simu; }\n                dart::dynamics::ShapeNode* shape() const { return _shape; }\n\n            private:\n                void draw(const Magnum::Matrix4& transformationMatrix, Magnum::SceneGraph::Camera3D& camera) override;\n\n                RobotDARTSimu* _simu;\n                dart::dynamics::ShapeNode* _shape;\n                std::vector<std::reference_wrapper<Magnum::GL::Mesh>> _meshes;\n                std::reference_wrapper<gs::PhongMultiLight> _color_shader;\n                std::reference_wrapper<gs::PhongMultiLight> _texture_shader;\n                std::vector<gs::Material> _materials;\n                std::vector<Magnum::Vector3> _scalings;\n                std::vector<bool> _has_negative_scaling;\n                std::vector<bool> _is_soft_body;\n                bool _isTransparent;\n            };\n\n            class ShadowedObject : public Object3D, public Magnum::SceneGraph::Drawable3D {\n            public:\n                explicit ShadowedObject(\n                    RobotDARTSimu* simu,\n                    dart::dynamics::ShapeNode* shape,\n                    const std::vector<std::reference_wrapper<Magnum::GL::Mesh>>& meshes,\n                    gs::ShadowMap& shader,\n                    gs::ShadowMap& texture_shader,\n                    Object3D* parent,\n                    Magnum::SceneGraph::DrawableGroup3D* group);\n\n                ShadowedObject& set_meshes(const std::vector<std::reference_wrapper<Magnum::GL::Mesh>>& meshes);\n                ShadowedObject& set_materials(const std::vector<gs::Material>& materials);\n                ShadowedObject& set_scalings(const std::vector<Magnum::Vector3>& scalings);\n\n                RobotDARTSimu* simu() const { return _simu; }\n                dart::dynamics::ShapeNode* shape() const { return _shape; }\n\n            private:\n                void draw(const Magnum::Matrix4& transformationMatrix, Magnum::SceneGraph::Camera3D& camera) override;\n\n                RobotDARTSimu* _simu;\n                dart::dynamics::ShapeNode* _shape;\n                std::vector<std::reference_wrapper<Magnum::GL::Mesh>> _meshes;\n                std::reference_wrapper<gs::ShadowMap> _shader, _texture_shader;\n                std::vector<gs::Material> _materials;\n                std::vector<Magnum::Vector3> _scalings;\n            };\n\n            class ShadowedColorObject : public Object3D, public Magnum::SceneGraph::Drawable3D {\n            public:\n                explicit ShadowedColorObject(\n                    RobotDARTSimu* simu,\n                    dart::dynamics::ShapeNode* shape,\n                    const std::vector<std::reference_wrapper<Magnum::GL::Mesh>>& meshes,\n                    gs::ShadowMapColor& shader,\n                    gs::ShadowMapColor& texture_shader,\n                    Object3D* parent,\n                    Magnum::SceneGraph::DrawableGroup3D* group);\n\n                ShadowedColorObject& set_meshes(const std::vector<std::reference_wrapper<Magnum::GL::Mesh>>& meshes);\n                ShadowedColorObject& set_materials(const std::vector<gs::Material>& materials);\n                ShadowedColorObject& set_scalings(const std::vector<Magnum::Vector3>& scalings);\n\n                RobotDARTSimu* simu() const { return _simu; }\n                dart::dynamics::ShapeNode* shape() const { return _shape; }\n\n            private:\n                void draw(const Magnum::Matrix4& transformationMatrix, Magnum::SceneGraph::Camera3D& camera) override;\n\n                RobotDARTSimu* _simu;\n                dart::dynamics::ShapeNode* _shape;\n                std::vector<std::reference_wrapper<Magnum::GL::Mesh>> _meshes;\n                std::reference_wrapper<gs::ShadowMapColor> _shader, _texture_shader;\n                std::vector<gs::Material> _materials;\n                std::vector<Magnum::Vector3> _scalings;\n            };\n\n            class CubeMapShadowedObject : public Object3D, public Magnum::SceneGraph::Drawable3D {\n            public:\n                explicit CubeMapShadowedObject(\n                    RobotDARTSimu* simu,\n                    dart::dynamics::ShapeNode* shape,\n                    const std::vector<std::reference_wrapper<Magnum::GL::Mesh>>& meshes,\n                    gs::CubeMap& shader,\n                    gs::CubeMap& texture_shader,\n                    Object3D* parent,\n                    Magnum::SceneGraph::DrawableGroup3D* group);\n\n                CubeMapShadowedObject& set_meshes(const std::vector<std::reference_wrapper<Magnum::GL::Mesh>>& meshes);\n                CubeMapShadowedObject& set_materials(const std::vector<gs::Material>& materials);\n                CubeMapShadowedObject& set_scalings(const std::vector<Magnum::Vector3>& scalings);\n\n                RobotDARTSimu* simu() const { return _simu; }\n                dart::dynamics::ShapeNode* shape() const { return _shape; }\n\n            private:\n                void draw(const Magnum::Matrix4& transformationMatrix, Magnum::SceneGraph::Camera3D& camera) override;\n\n                RobotDARTSimu* _simu;\n                dart::dynamics::ShapeNode* _shape;\n                std::vector<std::reference_wrapper<Magnum::GL::Mesh>> _meshes;\n                std::reference_wrapper<gs::CubeMap> _shader, _texture_shader;\n                std::vector<gs::Material> _materials;\n                std::vector<Magnum::Vector3> _scalings;\n            };\n\n            class CubeMapShadowedColorObject : public Object3D, public Magnum::SceneGraph::Drawable3D {\n            public:\n                explicit CubeMapShadowedColorObject(\n                    RobotDARTSimu* simu,\n                    dart::dynamics::ShapeNode* shape,\n                    const std::vector<std::reference_wrapper<Magnum::GL::Mesh>>& meshes,\n                    gs::CubeMapColor& shader,\n                    gs::CubeMapColor& texture_shader,\n                    Object3D* parent,\n                    Magnum::SceneGraph::DrawableGroup3D* group);\n\n                CubeMapShadowedColorObject& set_meshes(const std::vector<std::reference_wrapper<Magnum::GL::Mesh>>& meshes);\n                CubeMapShadowedColorObject& set_materials(const std::vector<gs::Material>& materials);\n                CubeMapShadowedColorObject& set_scalings(const std::vector<Magnum::Vector3>& scalings);\n\n                RobotDARTSimu* simu() const { return _simu; }\n                dart::dynamics::ShapeNode* shape() const { return _shape; }\n\n            private:\n                void draw(const Magnum::Matrix4& transformationMatrix, Magnum::SceneGraph::Camera3D& camera) override;\n\n                RobotDARTSimu* _simu;\n                dart::dynamics::ShapeNode* _shape;\n                std::vector<std::reference_wrapper<Magnum::GL::Mesh>> _meshes;\n                std::reference_wrapper<gs::CubeMapColor> _shader, _texture_shader;\n                std::vector<gs::Material> _materials;\n                std::vector<Magnum::Vector3> _scalings;\n            };\n\n            struct ShadowData {\n                Magnum::GL::Framebuffer shadow_framebuffer{Magnum::NoCreate};\n                Magnum::GL::Framebuffer shadow_color_framebuffer{Magnum::NoCreate};\n            };\n\n            struct ObjectStruct {\n                DrawableObject* drawable;\n                ShadowedObject* shadowed;\n                ShadowedColorObject* shadowed_color;\n                CubeMapShadowedObject* cubemapped;\n                CubeMapShadowedColorObject* 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

  • #include \"glfw_application.hpp\"
  • #include \"robot_dart/utils.hpp\"
  • #include <Magnum/GL/DefaultFramebuffer.h>
  • #include <Magnum/GL/Renderer.h>
  • #include <Magnum/GL/Version.h>
  • #include <Magnum/PixelFormat.h>
"},{"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":"

File: api/glfw__application_8cpp_source.md

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

  • #include <robot_dart/gui/magnum/base_application.hpp>
  • #include <Magnum/Platform/GlfwApplication.h>
"},{"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\n#include <robot_dart/gui/magnum/base_application.hpp>\n\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>\n\nnamespace robot_dart {\n    namespace gui {\n        namespace magnum {\n            class GlfwApplication : public BaseApplication, public Magnum::Platform::Application {\n            public:\n                explicit GlfwApplication(int argc, char** argv, RobotDARTSimu* simu, const GraphicsConfiguration& configuration = GraphicsConfiguration());\n\n                ~GlfwApplication();\n\n                void render() override;\n\n            protected:\n                RobotDARTSimu* _simu;\n                Magnum::Float _speed_move, _speed_strafe;\n                bool _draw_main_camera, _draw_debug;\n                Magnum::Color4 _bg_color;\n\n                static constexpr Magnum::Float _speed = 0.05f;\n\n                void viewportEvent(ViewportEvent& event) override;\n\n                void drawEvent() override;\n\n                virtual void keyReleaseEvent(KeyEvent& event) override;\n                virtual void keyPressEvent(KeyEvent& event) override;\n\n                virtual void mouseScrollEvent(MouseScrollEvent& event) override;\n                virtual void mouseMoveEvent(MouseMoveEvent& event) override;\n\n                void exitEvent(ExitEvent& event) override;\n            };\n        } // namespace magnum\n    } // namespace gui\n} // namespace robot_dart\n\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

  • #include <robot_dart/gui/magnum/graphics.hpp>
"},{"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>\n\nnamespace robot_dart {\n    namespace gui {\n        namespace magnum {\n            void Graphics::set_simu(RobotDARTSimu* simu)\n            {\n                BaseGraphics<GlfwApplication>::set_simu(simu);\n                // we synchronize by default if we have the graphics activated\n                simu->scheduler().set_sync(true);\n                // enable summary text when graphics activated\n                simu->enable_text_panel(true);\n                simu->enable_status_bar(true);\n            }\n\n            GraphicsConfiguration Graphics::default_configuration()\n            {\n                return 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

  • #include <robot_dart/gui/magnum/base_graphics.hpp>
"},{"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\n#include <robot_dart/gui/magnum/base_graphics.hpp>\n\nnamespace robot_dart {\n    namespace gui {\n        namespace magnum {\n            class Graphics : public BaseGraphics<GlfwApplication> {\n            public:\n                Graphics(const GraphicsConfiguration& configuration = default_configuration()) : BaseGraphics<GlfwApplication>(configuration) {}\n                ~Graphics() {}\n\n                void set_simu(RobotDARTSimu* simu) override;\n\n                static GraphicsConfiguration default_configuration();\n            };\n        } // namespace magnum\n    } // namespace gui\n} // namespace robot_dart\n\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

  • #include \"camera.hpp\"
  • #include \"robot_dart/gui/magnum/base_application.hpp\"
  • #include \"robot_dart/gui_data.hpp\"
  • #include \"robot_dart/robot_dart_simu.hpp\"
  • #include \"robot_dart/utils.hpp\"
  • #include <external/process.hpp>
  • #include <algorithm>
  • #include <Corrade/Containers/ArrayViewStl.h>
  • #include <Corrade/Containers/StridedArrayView.h>
  • #include <Corrade/Utility/Algorithms.h>
  • #include <Magnum/GL/AbstractFramebuffer.h>
  • #include <Magnum/GL/GL.h>
  • #include <Magnum/GL/PixelFormat.h>
  • #include <Magnum/GL/Renderer.h>
  • #include <Magnum/ImageView.h>
  • #include <Magnum/PixelFormat.h>
  • #include <robot_dart/gui/magnum/utils_headers_eigen.hpp>
  • #include <utheque/utheque.hpp>
"},{"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":"

File: api/gs_2camera_8cpp_source.md

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

  • #include <robot_dart/gui/magnum/gs/light.hpp>
  • #include <robot_dart/gui/magnum/types.hpp>
  • #include <robot_dart/robot_dart_simu.hpp>
  • #include <Corrade/Containers/Optional.h>
  • #include <Magnum/GL/Mesh.h>
  • #include <Magnum/Image.h>
  • #include <Magnum/Shaders/DistanceFieldVector.h>
  • #include <Magnum/Shaders/VertexColor.h>
  • #include <Magnum/Text/Renderer.h>
"},{"location":"api/gs_2camera_8hpp/#namespaces","title":"Namespaces","text":"Type Name namespace TinyProcessLib namespace robot_dart namespace gui namespace magnum namespace gs"},{"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\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\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>\n\nnamespace TinyProcessLib {\n    class Process;\n}\n\nnamespace robot_dart {\n    namespace gui {\n        namespace magnum {\n            struct DebugDrawData;\n\n            namespace gs {\n                // This is partly code from the ThirdPersonCameraController of https://github.com/alexesDev/magnum-tips\n                class Camera : public Object3D {\n                public:\n                    explicit Camera(Object3D& object, Magnum::Int width, Magnum::Int height);\n                    ~Camera();\n\n                    Camera3D& camera() const;\n                    Object3D& root_object();\n                    Object3D& camera_object() const;\n\n                    Camera& set_viewport(const Magnum::Vector2i& size);\n\n                    Camera& move(const Magnum::Vector2i& shift);\n                    Camera& forward(Magnum::Float speed);\n                    Camera& strafe(Magnum::Float speed);\n\n                    Camera& set_speed(const Magnum::Vector2& speed);\n                    Camera& set_near_plane(Magnum::Float near_plane);\n                    Camera& set_far_plane(Magnum::Float far_plane);\n                    Camera& set_fov(Magnum::Float fov);\n                    Camera& set_camera_params(Magnum::Float near_plane, Magnum::Float far_plane, Magnum::Float fov, Magnum::Int width, Magnum::Int height);\n\n                    Magnum::Vector2 speed() const { return _speed; }\n                    Magnum::Float near_plane() const { return _near_plane; }\n                    Magnum::Float far_plane() const { return _far_plane; }\n                    Magnum::Float fov() const { return static_cast<Magnum::Float>(_fov); }\n                    Magnum::Int width() const { return _camera->viewport()[0]; }\n                    Magnum::Int height() const { return _camera->viewport()[1]; }\n                    Magnum::Matrix3 intrinsic_matrix() const;\n                    Magnum::Matrix4 extrinsic_matrix() const;\n\n                    Camera& look_at(const Magnum::Vector3& camera, const Magnum::Vector3& center, const Magnum::Vector3& up = Magnum::Vector3::zAxis());\n\n                    void transform_lights(std::vector<gs::Light>& lights) const;\n\n                    void record(bool recording, bool recording_depth = false)\n                    {\n                        _recording = recording;\n                        _recording_depth = recording_depth;\n                    }\n\n                    // FPS is mandatory here (compared to Graphics and CameraOSR)\n                    void record_video(const std::string& video_fname, int fps);\n                    bool recording() { return _recording; }\n                    bool recording_depth() { return _recording_depth; }\n\n                    Corrade::Containers::Optional<Magnum::Image2D>& image() { return _image; }\n                    Corrade::Containers::Optional<Magnum::Image2D>& depth_image() { return _depth_image; }\n\n                    void draw(Magnum::SceneGraph::DrawableGroup3D& drawables, Magnum::GL::AbstractFramebuffer& framebuffer, Magnum::PixelFormat format, RobotDARTSimu* simu, const DebugDrawData& debug_data, bool draw_debug = true);\n\n                private:\n                    Object3D* _yaw_object;\n                    Object3D* _pitch_object;\n                    Object3D* _camera_object;\n\n                    Camera3D* _camera;\n                    Magnum::Vector2 _speed{-0.01f, 0.01f};\n\n                    Magnum::Vector3 _up, _front, _right;\n                    Magnum::Float _aspect_ratio, _near_plane, _far_plane;\n                    Magnum::Rad _fov;\n                    Magnum::Int _width, _height;\n\n                    bool _recording = false, _recording_depth = false;\n                    bool _recording_video = false;\n                    Corrade::Containers::Optional<Magnum::Image2D> _image, _depth_image;\n\n                    TinyProcessLib::Process* _ffmpeg_process = nullptr;\n\n                    void _clean_up_subprocess();\n                };\n            } // namespace gs\n        } // namespace magnum\n    } // namespace gui\n} // namespace robot_dart\n\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

  • #include <Corrade/Utility/Resource.h>
  • #include <Magnum/GL/Context.h>
  • #include <Magnum/GL/Extensions.h>
  • #include <Magnum/GL/Shader.h>
  • #include <string>
"},{"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\n#include <Corrade/Utility/Resource.h>\n\n#include <Magnum/GL/Context.h>\n#include <Magnum/GL/Extensions.h>\n#include <Magnum/GL/Shader.h>\n\n#include <string>\n\nnamespace robot_dart {\n    namespace gui {\n        namespace magnum {\n            namespace gs {\n                namespace {\n                    enum : Magnum::Int { AmbientTextureLayer = 0,\n                        DiffuseTextureLayer = 1,\n                        SpecularTextureLayer = 2 };\n                }\n            } // namespace gs\n        } // namespace magnum\n    } // namespace gui\n} // namespace robot_dart\n\nnamespace Magnum {\n    namespace Shaders {\n        namespace Implementation {\n\n            inline GL::Shader createCompatibilityShader(const Utility::Resource& rs, GL::Version version, GL::Shader::Type type)\n            {\n                GL::Shader shader(version, type);\n\n#ifndef MAGNUM_TARGET_GLES\n                if (GL::Context::current().isExtensionDisabled<GL::Extensions::ARB::explicit_attrib_location>(version))\n                    shader.addSource(\"#define DISABLE_GL_ARB_explicit_attrib_location\\n\");\n                if (GL::Context::current().isExtensionDisabled<GL::Extensions::ARB::shading_language_420pack>(version))\n                    shader.addSource(\"#define DISABLE_GL_ARB_shading_language_420pack\\n\");\n                if (GL::Context::current().isExtensionDisabled<GL::Extensions::ARB::explicit_uniform_location>(version))\n                    shader.addSource(\"#define DISABLE_GL_ARB_explicit_uniform_location\\n\");\n#endif\n\n#ifndef MAGNUM_TARGET_GLES2\n                if (type == GL::Shader::Type::Vertex && GL::Context::current().isExtensionDisabled<GL::Extensions::MAGNUM::shader_vertex_id>(version))\n                    shader.addSource(\"#define DISABLE_GL_MAGNUM_shader_vertex_id\\n\");\n#endif\n\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\n                shader.addSource(\"#ifndef GL_ES\\n#define GL_ES 1\\n#endif\\n\");\n#endif\n\n                shader.addSource(rs.get(\"compatibility.glsl\"));\n                return shader;\n            }\n\n        } // namespace Implementation\n    } // namespace Shaders\n} // namespace Magnum\n\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

  • #include \"cube_map.hpp\"
  • #include \"create_compatibility_shader.hpp\"
  • #include <Magnum/GL/Texture.h>
"},{"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\n#include <Magnum/GL/Texture.h>\n\nnamespace robot_dart {\n    namespace gui {\n        namespace magnum {\n            namespace gs {\n                CubeMap::CubeMap(CubeMap::Flags flags) : _flags(flags)\n                {\n                    Corrade::Utility::Resource rs_shaders(\"RobotDARTShaders\");\n\n                    const Magnum::GL::Version version = Magnum::GL::Version::GL320;\n\n                    Magnum::GL::Shader vert = Magnum::Shaders::Implementation::createCompatibilityShader(\n                        rs_shaders, version, Magnum::GL::Shader::Type::Vertex);\n                    Magnum::GL::Shader geom = Magnum::Shaders::Implementation::createCompatibilityShader(\n                        rs_shaders, version, Magnum::GL::Shader::Type::Geometry);\n                    Magnum::GL::Shader frag = Magnum::Shaders::Implementation::createCompatibilityShader(\n                        rs_shaders, version, Magnum::GL::Shader::Type::Fragment);\n\n                    std::string defines = \"#define POSITION_ATTRIBUTE_LOCATION \" + std::to_string(Position::Location) + \"\\n\";\n                    defines += \"#define TEXTURECOORDINATES_ATTRIBUTE_LOCATION \" + std::to_string(TextureCoordinates::Location) + \"\\n\";\n\n                    vert.addSource(flags ? \"#define TEXTURED\\n\" : \"\")\n                        .addSource(defines)\n                        .addSource(rs_shaders.get(\"CubeMap.vert\"));\n                    geom.addSource(flags ? \"#define TEXTURED\\n\" : \"\")\n                        .addSource(rs_shaders.get(\"CubeMap.geom\"));\n                    frag.addSource(flags ? \"#define TEXTURED\\n\" : \"\")\n                        .addSource(rs_shaders.get(\"CubeMap.frag\"));\n\n                    CORRADE_INTERNAL_ASSERT_OUTPUT(Magnum::GL::Shader::compile({vert, geom, frag}));\n\n                    attachShaders({vert, geom, frag});\n\n                    if (!Magnum::GL::Context::current().isExtensionSupported<Magnum::GL::Extensions::ARB::explicit_attrib_location>(version)) {\n                        bindAttributeLocation(Position::Location, \"position\");\n                        if (flags)\n                            bindAttributeLocation(TextureCoordinates::Location, \"textureCoords\");\n                    }\n\n                    CORRADE_INTERNAL_ASSERT_OUTPUT(link());\n\n                    if (!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                }\n\n                CubeMap::CubeMap(Magnum::NoCreateT) noexcept : Magnum::GL::AbstractShaderProgram{Magnum::NoCreate} {}\n\n                CubeMap::Flags CubeMap::flags() const { return _flags; }\n\n                CubeMap& CubeMap::set_transformation_matrix(const Magnum::Matrix4& matrix)\n                {\n                    setUniform(_transformation_matrix_uniform, matrix);\n                    return *this;\n                }\n\n                CubeMap& CubeMap::set_shadow_matrices(Magnum::Matrix4 matrices[6])\n                {\n                    for (size_t i = 0; i < 6; i++)\n                        setUniform(_shadow_matrices_uniform + i, matrices[i]);\n                    return *this;\n                }\n\n                CubeMap& CubeMap::set_light_position(const Magnum::Vector3& position)\n                {\n                    setUniform(_light_position_uniform, position);\n                    return *this;\n                }\n\n                CubeMap& CubeMap::set_far_plane(Magnum::Float far_plane)\n                {\n                    setUniform(_far_plane_uniform, far_plane);\n                    return *this;\n                }\n\n                CubeMap& CubeMap::set_light_index(Magnum::Int index)\n                {\n                    setUniform(_light_index_uniform, index);\n                    return *this;\n                }\n\n                CubeMap& CubeMap::set_material(Material& material)\n                {\n                    if (material.has_diffuse_texture() && (_flags & Flag::DiffuseTexture)) {\n                        (*material.diffuse_texture()).bind(DiffuseTextureLayer);\n                        setUniform(_diffuse_color_uniform, Magnum::Color4{1.0f});\n                    }\n                    else\n                        setUniform(_diffuse_color_uniform, material.diffuse_color());\n\n                    return *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

  • #include <robot_dart/gui/magnum/gs/material.hpp>
  • #include <Corrade/Containers/ArrayView.h>
  • #include <Corrade/Containers/Reference.h>
  • #include <Corrade/Utility/Assert.h>
  • #include <Magnum/GL/AbstractShaderProgram.h>
  • #include <Magnum/Math/Color.h>
  • #include <Magnum/Math/Matrix4.h>
  • #include <Magnum/Shaders/Generic.h>
"},{"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\n#include <robot_dart/gui/magnum/gs/material.hpp>\n\n#include <Corrade/Containers/ArrayView.h>\n#include <Corrade/Containers/Reference.h>\n#include <Corrade/Utility/Assert.h>\n\n#include <Magnum/GL/AbstractShaderProgram.h>\n#include <Magnum/Math/Color.h>\n#include <Magnum/Math/Matrix4.h>\n#include <Magnum/Shaders/Generic.h>\n\nnamespace robot_dart {\n    namespace gui {\n        namespace magnum {\n            namespace gs {\n                class CubeMap : public Magnum::GL::AbstractShaderProgram {\n                public:\n                    using Position = Magnum::Shaders::Generic3D::Position;\n                    using TextureCoordinates = Magnum::Shaders::Generic3D::TextureCoordinates;\n\n                    enum class Flag : Magnum::UnsignedByte {\n                        DiffuseTexture = 1 << 0, \n                    };\n\n                    using Flags = Magnum::Containers::EnumSet<Flag>;\n\n                    explicit CubeMap(Flags flags = {});\n                    explicit CubeMap(Magnum::NoCreateT) noexcept;\n\n                    Flags flags() const;\n\n                    CubeMap& set_transformation_matrix(const Magnum::Matrix4& matrix);\n                    CubeMap& set_shadow_matrices(Magnum::Matrix4 matrices[6]);\n                    CubeMap& set_light_position(const Magnum::Vector3& position);\n                    CubeMap& set_far_plane(Magnum::Float far_plane);\n                    CubeMap& set_light_index(Magnum::Int index);\n                    CubeMap& set_material(Material& material);\n\n                private:\n                    Flags _flags;\n                    Magnum::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                };\n\n                CORRADE_ENUMSET_OPERATORS(CubeMap::Flags)\n            } // namespace gs\n        } // namespace magnum\n    } // namespace gui\n} // namespace robot_dart\n\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

  • #include \"cube_map_color.hpp\"
  • #include \"create_compatibility_shader.hpp\"
  • #include <Magnum/GL/CubeMapTextureArray.h>
  • #include <Magnum/GL/Texture.h>
"},{"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\n#include <Magnum/GL/CubeMapTextureArray.h>\n#include <Magnum/GL/Texture.h>\n\nnamespace robot_dart {\n    namespace gui {\n        namespace magnum {\n            namespace gs {\n                CubeMapColor::CubeMapColor(CubeMapColor::Flags flags) : _flags(flags)\n                {\n                    Corrade::Utility::Resource rs_shaders(\"RobotDARTShaders\");\n\n                    const Magnum::GL::Version version = Magnum::GL::Version::GL320;\n\n                    Magnum::GL::Shader vert = Magnum::Shaders::Implementation::createCompatibilityShader(\n                        rs_shaders, version, Magnum::GL::Shader::Type::Vertex);\n                    Magnum::GL::Shader geom = Magnum::Shaders::Implementation::createCompatibilityShader(\n                        rs_shaders, version, Magnum::GL::Shader::Type::Geometry);\n                    Magnum::GL::Shader frag = Magnum::Shaders::Implementation::createCompatibilityShader(\n                        rs_shaders, version, Magnum::GL::Shader::Type::Fragment);\n\n                    std::string defines = \"#define POSITION_ATTRIBUTE_LOCATION \" + std::to_string(Position::Location) + \"\\n\";\n                    defines += \"#define TEXTURECOORDINATES_ATTRIBUTE_LOCATION \" + std::to_string(TextureCoordinates::Location) + \"\\n\";\n\n                    vert.addSource(flags ? \"#define TEXTURED\\n\" : \"\")\n                        .addSource(defines)\n                        .addSource(rs_shaders.get(\"CubeMap.vert\"));\n                    geom.addSource(flags ? \"#define TEXTURED\\n\" : \"\")\n                        .addSource(rs_shaders.get(\"CubeMap.geom\"));\n                    frag.addSource(flags ? \"#define TEXTURED\\n\" : \"\")\n                        .addSource(rs_shaders.get(\"CubeMapColor.frag\"));\n\n                    CORRADE_INTERNAL_ASSERT_OUTPUT(Magnum::GL::Shader::compile({vert, geom, frag}));\n\n                    attachShaders({vert, geom, frag});\n\n                    if (!Magnum::GL::Context::current().isExtensionSupported<Magnum::GL::Extensions::ARB::explicit_attrib_location>(version)) {\n                        bindAttributeLocation(Position::Location, \"position\");\n                        if (flags)\n                            bindAttributeLocation(TextureCoordinates::Location, \"textureCoords\");\n                    }\n\n                    CORRADE_INTERNAL_ASSERT_OUTPUT(link());\n\n                    if (!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\n                    if (!Magnum::GL::Context::current()\n                             .isExtensionSupported<Magnum::GL::Extensions::ARB::shading_language_420pack>(version)) {\n                        setUniform(uniformLocation(\"cubeMapTextures\"), _cube_map_textures_location);\n                        if (flags) {\n                            if (flags & Flag::DiffuseTexture)\n                                setUniform(uniformLocation(\"diffuseTexture\"), DiffuseTextureLayer);\n                        }\n                    }\n                }\n\n                CubeMapColor::CubeMapColor(Magnum::NoCreateT) noexcept : Magnum::GL::AbstractShaderProgram{Magnum::NoCreate} {}\n\n                CubeMapColor::Flags CubeMapColor::flags() const { return _flags; }\n\n                CubeMapColor& CubeMapColor::set_transformation_matrix(const Magnum::Matrix4& matrix)\n                {\n                    setUniform(_transformation_matrix_uniform, matrix);\n                    return *this;\n                }\n\n                CubeMapColor& CubeMapColor::set_shadow_matrices(Magnum::Matrix4 matrices[6])\n                {\n                    for (size_t i = 0; i < 6; i++)\n                        setUniform(_shadow_matrices_uniform + i, matrices[i]);\n                    return *this;\n                }\n\n                CubeMapColor& CubeMapColor::set_light_position(const Magnum::Vector3& position)\n                {\n                    setUniform(_light_position_uniform, position);\n                    return *this;\n                }\n\n                CubeMapColor& CubeMapColor::set_far_plane(Magnum::Float far_plane)\n                {\n                    setUniform(_far_plane_uniform, far_plane);\n                    return *this;\n                }\n\n                CubeMapColor& CubeMapColor::set_light_index(Magnum::Int index)\n                {\n                    setUniform(_light_index_uniform, index);\n                    return *this;\n                }\n\n                CubeMapColor& CubeMapColor::set_material(Material& material)\n                {\n                    if (material.has_diffuse_texture() && (_flags & Flag::DiffuseTexture)) {\n                        (*material.diffuse_texture()).bind(DiffuseTextureLayer);\n                        setUniform(_diffuse_color_uniform, Magnum::Color4{1.0f});\n                    }\n                    else\n                        setUniform(_diffuse_color_uniform, material.diffuse_color());\n\n                    return *this;\n                }\n\n                CubeMapColor& CubeMapColor::bind_cube_map_texture(Magnum::GL::CubeMapTextureArray& texture)\n                {\n                    texture.bind(_cube_map_textures_location);\n                    return *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

  • #include <robot_dart/gui/magnum/gs/material.hpp>
  • #include <Corrade/Containers/ArrayView.h>
  • #include <Corrade/Containers/Reference.h>
  • #include <Corrade/Utility/Assert.h>
  • #include <Magnum/GL/AbstractShaderProgram.h>
  • #include <Magnum/Math/Color.h>
  • #include <Magnum/Math/Matrix4.h>
  • #include <Magnum/Shaders/Generic.h>
"},{"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\n#include <robot_dart/gui/magnum/gs/material.hpp>\n\n#include <Corrade/Containers/ArrayView.h>\n#include <Corrade/Containers/Reference.h>\n#include <Corrade/Utility/Assert.h>\n\n#include <Magnum/GL/AbstractShaderProgram.h>\n#include <Magnum/Math/Color.h>\n#include <Magnum/Math/Matrix4.h>\n#include <Magnum/Shaders/Generic.h>\n\nnamespace robot_dart {\n    namespace gui {\n        namespace magnum {\n            namespace gs {\n                class CubeMapColor : public Magnum::GL::AbstractShaderProgram {\n                public:\n                    using Position = Magnum::Shaders::Generic3D::Position;\n                    using TextureCoordinates = Magnum::Shaders::Generic3D::TextureCoordinates;\n\n                    enum class Flag : Magnum::UnsignedByte {\n                        DiffuseTexture = 1 << 0, \n                    };\n\n                    using Flags = Magnum::Containers::EnumSet<Flag>;\n\n                    explicit CubeMapColor(Flags flags = {});\n                    explicit CubeMapColor(Magnum::NoCreateT) noexcept;\n\n                    Flags flags() const;\n\n                    CubeMapColor& set_transformation_matrix(const Magnum::Matrix4& matrix);\n                    CubeMapColor& set_shadow_matrices(Magnum::Matrix4 matrices[6]);\n                    CubeMapColor& set_light_position(const Magnum::Vector3& position);\n                    CubeMapColor& set_far_plane(Magnum::Float far_plane);\n                    CubeMapColor& set_light_index(Magnum::Int index);\n                    CubeMapColor& set_material(Material& material);\n\n                    CubeMapColor& bind_cube_map_texture(Magnum::GL::CubeMapTextureArray& texture);\n\n                private:\n                    Flags _flags;\n                    Magnum::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                };\n\n                CORRADE_ENUMSET_OPERATORS(CubeMapColor::Flags)\n            } // namespace gs\n        } // namespace magnum\n    } // namespace gui\n} // namespace robot_dart\n\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

  • #include \"helper.hpp\"
  • #include <Corrade/Containers/ArrayViewStl.h>
  • #include <Corrade/Containers/StridedArrayView.h>
  • #include <Corrade/Utility/Algorithms.h>
  • #include <Magnum/Math/Color.h>
  • #include <Magnum/Math/PackingBatch.h>
"},{"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\n#include <Corrade/Containers/ArrayViewStl.h>\n#include <Corrade/Containers/StridedArrayView.h>\n#include <Corrade/Utility/Algorithms.h>\n\n#include <Magnum/Math/Color.h>\n#include <Magnum/Math/PackingBatch.h>\n\nnamespace robot_dart {\n    namespace gui {\n        namespace magnum {\n            namespace gs {\n                Image rgb_from_image(Magnum::Image2D* image)\n                {\n                    Image img;\n\n                    img.width = image->size().x();\n                    img.height = image->size().y();\n                    img.channels = 3;\n                    img.data.resize(image->size().product() * sizeof(Magnum::Color3ub));\n                    Corrade::Containers::StridedArrayView2D<const Magnum::Color3ub> src = image->pixels<Magnum::Color3ub>().flipped<0>();\n                    Corrade::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())}};\n                    Corrade::Utility::copy(src, dst);\n\n                    return img;\n                }\n\n                GrayscaleImage depth_from_image(Magnum::Image2D* image, bool linearize, Magnum::Float near_plane, Magnum::Float far_plane)\n                {\n                    GrayscaleImage img;\n\n                    img.width = image->size().x();\n                    img.height = image->size().y();\n                    img.data.resize(image->size().product() * sizeof(uint8_t));\n\n                    std::vector<Magnum::Float> data = std::vector<Magnum::Float>(image->size().product());\n                    Corrade::Containers::StridedArrayView2D<const Magnum::Float> src = image->pixels<Magnum::Float>().flipped<0>();\n                    Corrade::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())}};\n                    Corrade::Utility::copy(src, dst);\n\n                    if (linearize) {\n                        for (auto& depth : data)\n                            depth = (2.f * near_plane) / (far_plane + near_plane - depth * (far_plane - near_plane));\n                    }\n\n                    Corrade::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())}};\n\n                    Magnum::Math::packInto(dst, new_dst);\n\n                    return img;\n                }\n\n                DepthImage depth_array_from_image(Magnum::Image2D* image, Magnum::Float near_plane, Magnum::Float far_plane)\n                {\n                    DepthImage img;\n                    img.width = image->size().x();\n                    img.height = image->size().y();\n\n                    std::vector<Magnum::Float> data = std::vector<Magnum::Float>(image->size().product());\n                    Corrade::Containers::StridedArrayView2D<const Magnum::Float> src = image->pixels<Magnum::Float>().flipped<0>();\n                    Corrade::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())}};\n                    Corrade::Utility::copy(src, dst);\n\n                    img.data = std::vector<double>(data.begin(), data.end());\n\n                    double zNear = static_cast<double>(near_plane);\n                    double zFar = static_cast<double>(far_plane);\n\n                    // zNear * zFar / (zFar + d * (zNear - zFar));\n                    for (auto& depth : img.data)\n                        // depth = (2. * zNear) / (zFar + zNear - depth * (zFar - zNear));\n                        depth = (zNear * zFar) / (zFar - depth * (zFar - zNear));\n\n                    return 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

  • #include <robot_dart/gui/helper.hpp>
  • #include <vector>
  • #include <Magnum/Image.h>
"},{"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\n#include <robot_dart/gui/helper.hpp>\n\n#include <vector>\n\n#include <Magnum/Image.h>\n\nnamespace robot_dart {\n    namespace gui {\n        namespace magnum {\n            namespace gs {\n                Image rgb_from_image(Magnum::Image2D* image);\n                GrayscaleImage depth_from_image(Magnum::Image2D* image, bool linearize = false, Magnum::Float near_plane = 0.f, Magnum::Float far_plane = 100.f);\n                DepthImage 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\n#endif\n
"},{"location":"api/light_8cpp/","title":"File light.cpp","text":"

FileList > gs > light.cpp

Go to the source code of this file

  • #include \"light.hpp\"
  • #include <Magnum/GL/Texture.h>
"},{"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\n#include <Magnum/GL/Texture.h>\n\nnamespace robot_dart {\n    namespace gui {\n        namespace magnum {\n            namespace gs {\n                Light::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) {}\n\n                Light::Light(const Magnum::Vector4& position, const Material& material, const Magnum::Vector3& spot_direction,\n                    Magnum::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\n                // Magnum::Vector4& Light::position();\n                Magnum::Vector4 Light::position() const { return _position; }\n\n                Magnum::Vector4& Light::transformed_position() { return _transformed_position; }\n                Magnum::Vector4 Light::transformed_position() const { return _transformed_position; }\n\n                Material& Light::material() { return _material; }\n                Material Light::material() const { return _material; }\n\n                // Magnum::Vector3& Light::spot_direction() { return _spot_direction; }\n                Magnum::Vector3 Light::spot_direction() const { return _spot_direction; }\n\n                Magnum::Vector3& Light::transformed_spot_direction() { return _transformed_spot_direction; }\n                Magnum::Vector3 Light::transformed_spot_direction() const { return _transformed_spot_direction; }\n\n                Magnum::Float& Light::spot_exponent() { return _spot_exponent; }\n                Magnum::Float Light::spot_exponent() const { return _spot_exponent; }\n\n                Magnum::Float& Light::spot_cut_off() { return _spot_cut_off; }\n                Magnum::Float Light::spot_cut_off() const { return _spot_cut_off; }\n\n                Magnum::Vector4& Light::attenuation() { return _attenuation; }\n                Magnum::Vector4 Light::attenuation() const { return _attenuation; }\n\n                Magnum::Matrix4 Light::shadow_matrix() const { return _shadow_transform; }\n\n                bool Light::casts_shadows() const { return _cast_shadows; }\n\n                Light& Light::set_position(const Magnum::Vector4& position)\n                {\n                    _position = position;\n                    _transformed_position = position;\n                    return *this;\n                }\n\n                Light& Light::set_transformed_position(const Magnum::Vector4& transformed_position)\n                {\n                    _transformed_position = transformed_position;\n                    return *this;\n                }\n\n                Light& Light::set_material(const Material& material)\n                {\n                    _material = material;\n                    return *this;\n                }\n\n                Light& Light::set_spot_direction(const Magnum::Vector3& spot_direction)\n                {\n                    _spot_direction = spot_direction;\n                    _transformed_spot_direction = _spot_direction;\n                    return *this;\n                }\n\n                Light& Light::set_transformed_spot_direction(const Magnum::Vector3& transformed_spot_direction)\n                {\n                    _transformed_spot_direction = transformed_spot_direction;\n                    return *this;\n                }\n\n                Light& Light::set_spot_exponent(Magnum::Float spot_exponent)\n                {\n                    _spot_exponent = spot_exponent;\n                    return *this;\n                }\n\n                Light& Light::set_spot_cut_off(Magnum::Float spot_cut_off)\n                {\n                    _spot_cut_off = spot_cut_off;\n                    return *this;\n                }\n\n                Light& Light::set_attenuation(const Magnum::Vector4& attenuation)\n                {\n                    _attenuation = attenuation;\n                    return *this;\n                }\n\n                Light& Light::set_shadow_matrix(const Magnum::Matrix4& shadowTransform)\n                {\n                    _shadow_transform = shadowTransform;\n                    return *this;\n                }\n\n                Light& Light::set_casts_shadows(bool cast_shadows)\n                {\n                    _cast_shadows = cast_shadows;\n                    return *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

  • #include <robot_dart/gui/magnum/gs/material.hpp>
  • #include <Magnum/Math/Matrix4.h>
"},{"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\n#include <robot_dart/gui/magnum/gs/material.hpp>\n\n#include <Magnum/Math/Matrix4.h>\n\nnamespace robot_dart {\n    namespace gui {\n        namespace magnum {\n            namespace gs {\n                class Light {\n                public:\n                    Light();\n\n                    Light(const Magnum::Vector4& position, const Material& material, const Magnum::Vector3& spot_direction,\n                        Magnum::Float spot_exponent, Magnum::Float spot_cut_off, const Magnum::Vector4& attenuation, bool cast_shadows = true);\n\n                    // Magnum::Vector4& position();\n                    Magnum::Vector4 position() const;\n                    Magnum::Vector4& transformed_position();\n                    Magnum::Vector4 transformed_position() const;\n\n                    Material& material();\n                    Material material() const;\n\n                    // Magnum::Vector3& spot_direction();\n                    Magnum::Vector3 spot_direction() const;\n\n                    Magnum::Vector3& transformed_spot_direction();\n                    Magnum::Vector3 transformed_spot_direction() const;\n\n                    Magnum::Float& spot_exponent();\n                    Magnum::Float spot_exponent() const;\n\n                    Magnum::Float& spot_cut_off();\n                    Magnum::Float spot_cut_off() const;\n\n                    Magnum::Vector4& attenuation();\n                    Magnum::Vector4 attenuation() const;\n\n                    Magnum::Matrix4 shadow_matrix() const;\n                    bool casts_shadows() const;\n\n                    Light& set_position(const Magnum::Vector4& position);\n                    Light& set_transformed_position(const Magnum::Vector4& transformed_position);\n\n                    Light& set_material(const Material& material);\n\n                    Light& set_spot_direction(const Magnum::Vector3& spot_direction);\n                    Light& set_transformed_spot_direction(const Magnum::Vector3& transformed_spot_direction);\n                    Light& set_spot_exponent(Magnum::Float spot_exponent);\n                    Light& set_spot_cut_off(Magnum::Float spot_cut_off);\n\n                    Light& set_attenuation(const Magnum::Vector4& attenuation);\n\n                    Light& set_shadow_matrix(const Magnum::Matrix4& shadowTransform);\n                    Light& set_casts_shadows(bool cast_shadows);\n\n                protected:\n                    // Position for point-lights and spot-lights\n                    // Direction for directional lights (if position.w == 0)\n                    Magnum::Vector4 _position;\n                    // TO-DO: Handle dirtiness of transformed position\n                    Magnum::Vector4 _transformed_position;\n                    Material _material;\n                    Magnum::Vector3 _spot_direction;\n                    // TO-DO: Handle dirtiness of transformed spot direction\n                    Magnum::Vector3 _transformed_spot_direction;\n                    Magnum::Float _spot_exponent, _spot_cut_off;\n\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)\n                    Magnum::Vector4 _attenuation;\n\n                    // Shadow-Matrix\n                    Magnum::Matrix4 _shadow_transform{};\n\n                    // Whether it casts shadows\n                    bool _cast_shadows = true;\n                };\n\n                // Helpers for creating lights\n                inline Light create_point_light(const Magnum::Vector3& position, const Material& material,\n                    Magnum::Float intensity, const Magnum::Vector3& attenuationTerms)\n                {\n                    Light light;\n                    light.set_material(material);\n                    light.set_position(Magnum::Vector4{position, 1.f})\n                        .set_attenuation(Magnum::Vector4{attenuationTerms, intensity});\n\n                    return light;\n                }\n\n                inline Light create_spot_light(const Magnum::Vector3& position, const Material& material,\n                    const Magnum::Vector3& spot_direction, Magnum::Float spot_exponent, Magnum::Float spot_cut_off,\n                    Magnum::Float intensity, const Magnum::Vector3& attenuationTerms)\n                {\n                    return Light(Magnum::Vector4{position, 1.f}, material, spot_direction, spot_exponent, spot_cut_off,\n                        Magnum::Vector4{attenuationTerms, intensity});\n                }\n\n                inline Light create_directional_light(\n                    const Magnum::Vector3& direction, const Material& material)\n                {\n                    Light light;\n                    light.set_material(material);\n                    light.set_position(Magnum::Vector4{direction, 0.f});\n\n                    return light;\n                }\n            } // namespace gs\n        } // namespace magnum\n    } // namespace gui\n} // namespace robot_dart\n\n#endif\n
"},{"location":"api/material_8cpp/","title":"File material.cpp","text":"

FileList > gs > material.cpp

Go to the source code of this file

  • #include \"material.hpp\"
  • #include <Magnum/GL/Texture.h>
"},{"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\n#include <Magnum/GL/Texture.h>\n\nnamespace robot_dart {\n    namespace gui {\n        namespace magnum {\n            namespace gs {\n                Material::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) {}\n\n                Material::Material(const Magnum::Color4& ambient, const Magnum::Color4& diffuse,\n                    const Magnum::Color4& specular, Magnum::Float shininess) : _ambient(ambient),\n                                                                               _diffuse(diffuse),\n                                                                               _specular(specular),\n                                                                               _shininess(shininess) {}\n\n                Material::Material(Magnum::GL::Texture2D* ambient_texture,\n                    Magnum::GL::Texture2D* diffuse_texture,\n                    Magnum::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) {}\n\n                Magnum::Color4& Material::ambient_color() { return _ambient; }\n                Magnum::Color4 Material::ambient_color() const { return _ambient; }\n\n                Magnum::Color4& Material::diffuse_color() { return _diffuse; }\n                Magnum::Color4 Material::diffuse_color() const { return _diffuse; }\n\n                Magnum::Color4& Material::specular_color() { return _specular; }\n                Magnum::Color4 Material::specular_color() const { return _specular; }\n\n                Magnum::Float& Material::shininess() { return _shininess; }\n                Magnum::Float Material::shininess() const { return _shininess; }\n\n                Magnum::GL::Texture2D* Material::ambient_texture() { return _ambient_texture; }\n                Magnum::GL::Texture2D* Material::diffuse_texture() { return _diffuse_texture; }\n                Magnum::GL::Texture2D* Material::specular_texture() { return _specular_texture; }\n\n                bool Material::has_ambient_texture() const { return _ambient_texture != NULL; }\n                bool Material::has_diffuse_texture() const { return _diffuse_texture != NULL; }\n                bool Material::has_specular_texture() const { return _specular_texture != NULL; }\n\n                Material& Material::set_ambient_color(const Magnum::Color4& ambient)\n                {\n                    _ambient = ambient;\n                    return *this;\n                }\n\n                Material& Material::set_diffuse_color(const Magnum::Color4& diffuse)\n                {\n                    _diffuse = diffuse;\n                    return *this;\n                }\n\n                Material& Material::set_specular_color(const Magnum::Color4& specular)\n                {\n                    _specular = specular;\n                    return *this;\n                }\n\n                Material& Material::set_shininess(Magnum::Float shininess)\n                {\n                    _shininess = shininess;\n                    return *this;\n                }\n\n                Material& Material::set_ambient_texture(Magnum::GL::Texture2D* ambient_texture)\n                {\n                    _ambient_texture = ambient_texture;\n                    return *this;\n                }\n\n                Material& Material::set_diffuse_texture(Magnum::GL::Texture2D* diffuse_texture)\n                {\n                    _diffuse_texture = diffuse_texture;\n                    return *this;\n                }\n\n                Material& Material::set_specular_texture(Magnum::GL::Texture2D* specular_texture)\n                {\n                    _specular_texture = specular_texture;\n                    return *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

  • #include <Corrade/Containers/Optional.h>
  • #include <Magnum/GL/GL.h>
  • #include <Magnum/Magnum.h>
  • #include <Magnum/Math/Color.h>
"},{"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\n#include <Corrade/Containers/Optional.h>\n\n#include <Magnum/GL/GL.h>\n#include <Magnum/Magnum.h>\n#include <Magnum/Math/Color.h>\n\nnamespace robot_dart {\n    namespace gui {\n        namespace magnum {\n            namespace gs {\n                class Material {\n                public:\n                    Material();\n\n                    Material(const Magnum::Color4& ambient, const Magnum::Color4& diffuse,\n                        const Magnum::Color4& specular, Magnum::Float shininess);\n\n                    Material(Magnum::GL::Texture2D* ambient_texture,\n                        Magnum::GL::Texture2D* diffuse_texture,\n                        Magnum::GL::Texture2D* specular_texture, Magnum::Float shininess);\n\n                    Magnum::Color4& ambient_color();\n                    Magnum::Color4 ambient_color() const;\n\n                    Magnum::Color4& diffuse_color();\n                    Magnum::Color4 diffuse_color() const;\n\n                    Magnum::Color4& specular_color();\n                    Magnum::Color4 specular_color() const;\n\n                    Magnum::Float& shininess();\n                    Magnum::Float shininess() const;\n\n                    Magnum::GL::Texture2D* ambient_texture();\n                    Magnum::GL::Texture2D* diffuse_texture();\n                    Magnum::GL::Texture2D* specular_texture();\n\n                    bool has_ambient_texture() const;\n                    bool has_diffuse_texture() const;\n                    bool has_specular_texture() const;\n\n                    Material& set_ambient_color(const Magnum::Color4& ambient);\n                    Material& set_diffuse_color(const Magnum::Color4& diffuse);\n                    Material& set_specular_color(const Magnum::Color4& specular);\n                    Material& set_shininess(Magnum::Float shininess);\n\n                    Material& set_ambient_texture(Magnum::GL::Texture2D* ambient_texture);\n                    Material& set_diffuse_texture(Magnum::GL::Texture2D* diffuse_texture);\n                    Material& set_specular_texture(Magnum::GL::Texture2D* specular_texture);\n\n                protected:\n                    Magnum::Color4 _ambient, _diffuse, _specular;\n                    Magnum::Float _shininess;\n                    Magnum::GL::Texture2D* _ambient_texture = NULL;\n                    Magnum::GL::Texture2D* _diffuse_texture = NULL;\n                    Magnum::GL::Texture2D* _specular_texture = NULL;\n                };\n            } // namespace gs\n        } // namespace magnum\n    } // namespace gui\n} // namespace robot_dart\n\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

  • #include \"phong_multi_light.hpp\"
  • #include \"create_compatibility_shader.hpp\"
  • #include <Magnum/GL/CubeMapTextureArray.h>
  • #include <Magnum/GL/Texture.h>
  • #include <Magnum/GL/TextureArray.h>
"},{"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\n#include <Magnum/GL/CubeMapTextureArray.h>\n#include <Magnum/GL/Texture.h>\n#include <Magnum/GL/TextureArray.h>\n\nnamespace robot_dart {\n    namespace gui {\n        namespace magnum {\n            namespace gs {\n                PhongMultiLight::PhongMultiLight(PhongMultiLight::Flags flags, Magnum::Int max_lights) : _flags(flags), _max_lights(max_lights)\n                {\n                    Corrade::Utility::Resource rs_shaders(\"RobotDARTShaders\");\n\n                    const Magnum::GL::Version version = Magnum::GL::Version::GL320;\n\n                    Magnum::GL::Shader vert = Magnum::Shaders::Implementation::createCompatibilityShader(\n                        rs_shaders, version, Magnum::GL::Shader::Type::Vertex);\n                    Magnum::GL::Shader frag = Magnum::Shaders::Implementation::createCompatibilityShader(\n                        rs_shaders, version, Magnum::GL::Shader::Type::Fragment);\n\n                    std::string defines = \"#define LIGHT_COUNT \" + std::to_string(_max_lights) + \"\\n\";\n                    defines += \"#define POSITION_ATTRIBUTE_LOCATION \" + std::to_string(Position::Location) + \"\\n\";\n                    defines += \"#define NORMAL_ATTRIBUTE_LOCATION \" + std::to_string(Normal::Location) + \"\\n\";\n                    defines += \"#define TEXTURECOORDINATES_ATTRIBUTE_LOCATION \" + std::to_string(TextureCoordinates::Location) + \"\\n\";\n\n                    vert.addSource(flags ? \"#define TEXTURED\\n\" : \"\")\n                        .addSource(defines)\n                        .addSource(rs_shaders.get(\"PhongMultiLight.vert\"));\n                    frag.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\"));\n\n                    CORRADE_INTERNAL_ASSERT_OUTPUT(Magnum::GL::Shader::compile({vert, frag}));\n\n                    attachShaders({vert, frag});\n\n                    if (!Magnum::GL::Context::current().isExtensionSupported<Magnum::GL::Extensions::ARB::explicit_attrib_location>(version)) {\n                        bindAttributeLocation(Position::Location, \"position\");\n                        bindAttributeLocation(Normal::Location, \"normal\");\n                        if (flags)\n                            bindAttributeLocation(TextureCoordinates::Location, \"textureCoords\");\n                    }\n\n                    CORRADE_INTERNAL_ASSERT_OUTPUT(link());\n\n                    /* Get light matrices uniform */\n                    _lights_matrices_uniform = uniformLocation(\"lightMatrices[0]\");\n\n                    if (!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                    }\n\n                    if (!Magnum::GL::Context::current()\n                             .isExtensionSupported<Magnum::GL::Extensions::ARB::shading_language_420pack>(version)) {\n                        setUniform(uniformLocation(\"shadowTextures\"), _shadow_textures_location);\n                        setUniform(uniformLocation(\"cubeMapTextures\"), _cube_map_textures_location);\n                        setUniform(uniformLocation(\"shadowColorTextures\"), _shadow_color_textures_location);\n                        setUniform(uniformLocation(\"cubeMapColorTextures\"), _cube_map_color_textures_location);\n                        if (flags) {\n                            if (flags & Flag::AmbientTexture)\n                                setUniform(uniformLocation(\"ambientTexture\"), AmbientTextureLayer);\n                            if (flags & Flag::DiffuseTexture)\n                                setUniform(uniformLocation(\"diffuseTexture\"), DiffuseTextureLayer);\n                            if (flags & Flag::SpecularTexture)\n                                setUniform(uniformLocation(\"specularTexture\"), SpecularTextureLayer);\n                        }\n                    }\n\n                    /* Set defaults (normally they are set in shader code itself, but just in case) */\n                    Material material;\n\n                    /* Default to fully opaque white so we can see the textures */\n                    if (flags & Flag::AmbientTexture)\n                        material.set_ambient_color(Magnum::Color4{1.0f});\n                    else\n                        material.set_ambient_color(Magnum::Color4{0.0f, 1.0f});\n\n                    if (flags & Flag::DiffuseTexture)\n                        material.set_diffuse_color(Magnum::Color4{1.0f});\n\n                    material.set_specular_color(Magnum::Color4{1.0f});\n                    material.set_shininess(80.0f);\n\n                    set_material(material);\n\n                    /* Lights defaults need to be set by code */\n                    /* All lights are disabled i.e., color equal to black */\n                    Light light;\n                    for (Magnum::Int i = 0; i < _max_lights; i++)\n                        set_light(i, light);\n                }\n\n                PhongMultiLight::PhongMultiLight(Magnum::NoCreateT) noexcept : Magnum::GL::AbstractShaderProgram{Magnum::NoCreate} {}\n\n                PhongMultiLight::Flags PhongMultiLight::flags() const { return _flags; }\n\n                PhongMultiLight& PhongMultiLight::set_material(Material& material)\n                {\n                    // TO-DO: Check if we should do this or let the user define the proper\n                    // material\n                    if (material.has_ambient_texture() && (_flags & Flag::AmbientTexture)) {\n                        (*material.ambient_texture()).bind(AmbientTextureLayer);\n                        setUniform(_ambient_color_uniform, Magnum::Color4{1.0f});\n                    }\n                    else\n                        setUniform(_ambient_color_uniform, material.ambient_color());\n\n                    if (material.has_diffuse_texture() && (_flags & Flag::DiffuseTexture)) {\n                        (*material.diffuse_texture()).bind(DiffuseTextureLayer);\n                        setUniform(_diffuse_color_uniform, Magnum::Color4{1.0f});\n                    }\n                    else\n                        setUniform(_diffuse_color_uniform, material.diffuse_color());\n\n                    if (material.has_specular_texture() && (_flags & Flag::SpecularTexture)) {\n                        (*material.specular_texture()).bind(SpecularTextureLayer);\n                        setUniform(_specular_color_uniform, Magnum::Color4{1.0f});\n                    }\n                    else\n                        setUniform(_specular_color_uniform, material.specular_color());\n\n                    setUniform(_shininess_uniform, material.shininess());\n\n                    return *this;\n                }\n\n                PhongMultiLight& PhongMultiLight::set_light(Magnum::Int i, const Light& light)\n                {\n                    CORRADE_INTERNAL_ASSERT(i >= 0 && i < _max_lights);\n                    Magnum::Vector4 attenuation = light.attenuation();\n\n                    // light position\n                    setUniform(_lights_uniform + i * _light_loc_size, light.transformed_position());\n                    // light material\n                    setUniform(_lights_uniform + i * _light_loc_size + 1, light.material().ambient_color());\n                    setUniform(_lights_uniform + i * _light_loc_size + 2, light.material().diffuse_color());\n                    setUniform(_lights_uniform + i * _light_loc_size + 3, light.material().specular_color());\n                    // spotlight properties\n                    setUniform(_lights_uniform + i * _light_loc_size + 4, light.transformed_spot_direction());\n                    setUniform(_lights_uniform + i * _light_loc_size + 5, light.spot_exponent());\n                    setUniform(_lights_uniform + i * _light_loc_size + 6, light.spot_cut_off());\n                    // intesity\n                    setUniform(_lights_uniform + i * _light_loc_size + 7, attenuation[3]);\n                    // constant attenuation term\n                    setUniform(_lights_uniform + i * _light_loc_size + 8, attenuation[0]);\n                    // linear attenuation term\n                    setUniform(_lights_uniform + i * _light_loc_size + 9, attenuation[1]);\n                    // quadratic attenuation term\n                    setUniform(_lights_uniform + i * _light_loc_size + 10, attenuation[2]);\n                    // world position\n                    setUniform(_lights_uniform + i * _light_loc_size + 11, light.position());\n                    // casts shadows?\n                    setUniform(_lights_uniform + i * _light_loc_size + 12, light.casts_shadows());\n\n                    setUniform(_lights_matrices_uniform + i, light.shadow_matrix());\n\n                    return *this;\n                }\n\n                PhongMultiLight& PhongMultiLight::set_transformation_matrix(const Magnum::Matrix4& matrix)\n                {\n                    setUniform(_transformation_matrix_uniform, matrix);\n                    return *this;\n                }\n\n                PhongMultiLight& PhongMultiLight::set_camera_matrix(const Magnum::Matrix4& matrix)\n                {\n                    setUniform(_camera_matrix_uniform, matrix);\n                    return *this;\n                }\n\n                PhongMultiLight& PhongMultiLight::set_normal_matrix(const Magnum::Matrix3x3& matrix)\n                {\n                    setUniform(_normal_matrix_uniform, matrix);\n                    return *this;\n                }\n\n                PhongMultiLight& PhongMultiLight::set_projection_matrix(const Magnum::Matrix4& matrix)\n                {\n                    setUniform(_projection_matrix_uniform, matrix);\n                    return *this;\n                }\n\n                PhongMultiLight& PhongMultiLight::set_far_plane(Magnum::Float far_plane)\n                {\n                    setUniform(_far_plane_uniform, far_plane);\n                    return *this;\n                }\n\n                PhongMultiLight& PhongMultiLight::set_is_shadowed(bool shadows)\n                {\n                    setUniform(_is_shadowed_uniform, shadows);\n                    return *this;\n                }\n\n                PhongMultiLight& PhongMultiLight::set_transparent_shadows(bool shadows)\n                {\n                    setUniform(_transparent_shadows_uniform, shadows);\n                    return *this;\n                }\n\n                PhongMultiLight& PhongMultiLight::set_specular_strength(Magnum::Float specular_strength)\n                {\n                    setUniform(_specular_strength_uniform, std::max(0.f, specular_strength));\n                    return *this;\n                }\n\n                PhongMultiLight& PhongMultiLight::bind_shadow_texture(Magnum::GL::Texture2DArray& texture)\n                {\n                    texture.bind(_shadow_textures_location);\n                    return *this;\n                }\n\n                PhongMultiLight& PhongMultiLight::bind_shadow_color_texture(Magnum::GL::Texture2DArray& texture)\n                {\n                    texture.bind(_shadow_color_textures_location);\n                    return *this;\n                }\n\n                PhongMultiLight& PhongMultiLight::bind_cube_map_texture(Magnum::GL::CubeMapTextureArray& texture)\n                {\n                    texture.bind(_cube_map_textures_location);\n                    return *this;\n                }\n\n                PhongMultiLight& PhongMultiLight::bind_cube_map_color_texture(Magnum::GL::CubeMapTextureArray& texture)\n                {\n                    texture.bind(_cube_map_color_textures_location);\n                    return *this;\n                }\n\n                Magnum::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

  • #include <robot_dart/gui/magnum/gs/light.hpp>
  • #include <Corrade/Containers/ArrayView.h>
  • #include <Corrade/Containers/Reference.h>
  • #include <Corrade/Utility/Assert.h>
  • #include <Magnum/GL/AbstractShaderProgram.h>
  • #include <Magnum/Math/Color.h>
  • #include <Magnum/Math/Matrix4.h>
  • #include <Magnum/Shaders/Generic.h>
"},{"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\n#include <robot_dart/gui/magnum/gs/light.hpp>\n\n#include <Corrade/Containers/ArrayView.h>\n#include <Corrade/Containers/Reference.h>\n#include <Corrade/Utility/Assert.h>\n\n#include <Magnum/GL/AbstractShaderProgram.h>\n#include <Magnum/Math/Color.h>\n#include <Magnum/Math/Matrix4.h>\n#include <Magnum/Shaders/Generic.h>\n\nnamespace robot_dart {\n    namespace gui {\n        namespace magnum {\n            namespace gs {\n                class PhongMultiLight : public Magnum::GL::AbstractShaderProgram {\n                public:\n                    using Position = Magnum::Shaders::Generic3D::Position;\n                    using Normal = Magnum::Shaders::Generic3D::Normal;\n                    using TextureCoordinates = Magnum::Shaders::Generic3D::TextureCoordinates;\n\n                    enum class Flag : Magnum::UnsignedByte {\n                        AmbientTexture = 1 << 0, \n                        DiffuseTexture = 1 << 1, \n                        SpecularTexture = 1 << 2 \n                    };\n\n                    using Flags = Magnum::Containers::EnumSet<Flag>;\n\n                    explicit PhongMultiLight(Flags flags = {}, Magnum::Int max_lights = 10);\n                    explicit PhongMultiLight(Magnum::NoCreateT) noexcept;\n\n                    Flags flags() const;\n\n                    PhongMultiLight& set_material(Material& material);\n                    PhongMultiLight& set_light(Magnum::Int i, const Light& light);\n\n                    PhongMultiLight& set_transformation_matrix(const Magnum::Matrix4& matrix);\n                    PhongMultiLight& set_camera_matrix(const Magnum::Matrix4& matrix);\n                    PhongMultiLight& set_normal_matrix(const Magnum::Matrix3x3& matrix);\n                    PhongMultiLight& set_projection_matrix(const Magnum::Matrix4& matrix);\n\n                    PhongMultiLight& set_far_plane(Magnum::Float far_plane);\n                    PhongMultiLight& set_is_shadowed(bool shadows);\n                    PhongMultiLight& set_transparent_shadows(bool shadows);\n                    PhongMultiLight& set_specular_strength(Magnum::Float specular_strength);\n\n                    PhongMultiLight& bind_shadow_texture(Magnum::GL::Texture2DArray& texture);\n                    PhongMultiLight& bind_shadow_color_texture(Magnum::GL::Texture2DArray& texture);\n                    PhongMultiLight& bind_cube_map_texture(Magnum::GL::CubeMapTextureArray& texture);\n                    PhongMultiLight& bind_cube_map_color_texture(Magnum::GL::CubeMapTextureArray& texture);\n\n                    Magnum::Int max_lights() const;\n\n                private:\n                    Flags _flags;\n                    Magnum::Int _max_lights = 10;\n                    Magnum::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};\n                    const Magnum::Int _light_loc_size = 13;\n                };\n\n                CORRADE_ENUMSET_OPERATORS(PhongMultiLight::Flags)\n            } // namespace gs\n        } // namespace magnum\n    } // namespace gui\n} // namespace robot_dart\n\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

  • #include \"shadow_map.hpp\"
  • #include \"create_compatibility_shader.hpp\"
  • #include <Magnum/GL/Texture.h>
"},{"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\n#include <Magnum/GL/Texture.h>\n\nnamespace robot_dart {\n    namespace gui {\n        namespace magnum {\n            namespace gs {\n                ShadowMap::ShadowMap(ShadowMap::Flags flags) : _flags(flags)\n                {\n                    Corrade::Utility::Resource rs_shaders(\"RobotDARTShaders\");\n\n                    const Magnum::GL::Version version = Magnum::GL::Version::GL320;\n\n                    Magnum::GL::Shader vert = Magnum::Shaders::Implementation::createCompatibilityShader(\n                        rs_shaders, version, Magnum::GL::Shader::Type::Vertex);\n                    Magnum::GL::Shader frag = Magnum::Shaders::Implementation::createCompatibilityShader(\n                        rs_shaders, version, Magnum::GL::Shader::Type::Fragment);\n\n                    std::string defines = \"#define POSITION_ATTRIBUTE_LOCATION \" + std::to_string(Position::Location) + \"\\n\";\n                    defines += \"#define TEXTURECOORDINATES_ATTRIBUTE_LOCATION \" + std::to_string(TextureCoordinates::Location) + \"\\n\";\n\n                    vert.addSource(flags ? \"#define TEXTURED\\n\" : \"\")\n                        .addSource(defines)\n                        .addSource(rs_shaders.get(\"ShadowMap.vert\"));\n                    frag.addSource(flags ? \"#define TEXTURED\\n\" : \"\")\n                        .addSource(rs_shaders.get(\"ShadowMap.frag\"));\n\n                    CORRADE_INTERNAL_ASSERT_OUTPUT(Magnum::GL::Shader::compile({vert, frag}));\n\n                    attachShaders({vert, frag});\n\n                    if (!Magnum::GL::Context::current().isExtensionSupported<Magnum::GL::Extensions::ARB::explicit_attrib_location>(version)) {\n                        bindAttributeLocation(Position::Location, \"position\");\n                        if (flags)\n                            bindAttributeLocation(TextureCoordinates::Location, \"textureCoords\");\n                    }\n\n                    CORRADE_INTERNAL_ASSERT_OUTPUT(link());\n\n                    if (!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                    }\n\n                    if (!Magnum::GL::Context::current()\n                             .isExtensionSupported<Magnum::GL::Extensions::ARB::shading_language_420pack>(version)\n                        && flags) {\n                        setUniform(uniformLocation(\"diffuseTexture\"), DiffuseTextureLayer);\n                    }\n                }\n\n                ShadowMap::ShadowMap(Magnum::NoCreateT) noexcept : Magnum::GL::AbstractShaderProgram{Magnum::NoCreate} {}\n\n                ShadowMap::Flags ShadowMap::flags() const { return _flags; }\n\n                ShadowMap& ShadowMap::set_transformation_matrix(const Magnum::Matrix4& matrix)\n                {\n                    setUniform(_transformation_matrix_uniform, matrix);\n                    return *this;\n                }\n\n                ShadowMap& ShadowMap::set_projection_matrix(const Magnum::Matrix4& matrix)\n                {\n                    setUniform(_projection_matrix_uniform, matrix);\n                    return *this;\n                }\n\n                ShadowMap& ShadowMap::set_material(Material& material)\n                {\n                    if (material.has_diffuse_texture() && (_flags & Flag::DiffuseTexture)) {\n                        (*material.diffuse_texture()).bind(DiffuseTextureLayer);\n                        setUniform(_diffuse_color_uniform, Magnum::Color4{1.0f});\n                    }\n                    else\n                        setUniform(_diffuse_color_uniform, material.diffuse_color());\n\n                    return *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

  • #include <robot_dart/gui/magnum/gs/material.hpp>
  • #include <Corrade/Containers/ArrayView.h>
  • #include <Corrade/Containers/Reference.h>
  • #include <Corrade/Utility/Assert.h>
  • #include <Magnum/GL/AbstractShaderProgram.h>
  • #include <Magnum/Math/Color.h>
  • #include <Magnum/Math/Matrix4.h>
  • #include <Magnum/Shaders/Generic.h>
"},{"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\n#include <robot_dart/gui/magnum/gs/material.hpp>\n\n#include <Corrade/Containers/ArrayView.h>\n#include <Corrade/Containers/Reference.h>\n#include <Corrade/Utility/Assert.h>\n\n#include <Magnum/GL/AbstractShaderProgram.h>\n#include <Magnum/Math/Color.h>\n#include <Magnum/Math/Matrix4.h>\n#include <Magnum/Shaders/Generic.h>\n\nnamespace robot_dart {\n    namespace gui {\n        namespace magnum {\n            namespace gs {\n                class ShadowMap : public Magnum::GL::AbstractShaderProgram {\n                public:\n                    using Position = Magnum::Shaders::Generic3D::Position;\n                    using TextureCoordinates = Magnum::Shaders::Generic3D::TextureCoordinates;\n\n                    enum class Flag : Magnum::UnsignedByte {\n                        DiffuseTexture = 1 << 0, \n                    };\n\n                    using Flags = Magnum::Containers::EnumSet<Flag>;\n\n                    explicit ShadowMap(Flags flags = {});\n                    explicit ShadowMap(Magnum::NoCreateT) noexcept;\n\n                    Flags flags() const;\n\n                    ShadowMap& set_transformation_matrix(const Magnum::Matrix4& matrix);\n                    ShadowMap& set_projection_matrix(const Magnum::Matrix4& matrix);\n                    ShadowMap& set_material(Material& material);\n\n                private:\n                    Flags _flags;\n                    Magnum::Int _transformation_matrix_uniform{0}, _projection_matrix_uniform{1}, _diffuse_color_uniform{2};\n                };\n\n                CORRADE_ENUMSET_OPERATORS(ShadowMap::Flags)\n            } // namespace gs\n        } // namespace magnum\n    } // namespace gui\n} // namespace robot_dart\n\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

  • #include \"shadow_map_color.hpp\"
  • #include \"create_compatibility_shader.hpp\"
  • #include <Magnum/GL/Texture.h>
"},{"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\n#include <Magnum/GL/Texture.h>\n\nnamespace robot_dart {\n    namespace gui {\n        namespace magnum {\n            namespace gs {\n                ShadowMapColor::ShadowMapColor(ShadowMapColor::Flags flags) : _flags(flags)\n                {\n                    Corrade::Utility::Resource rs_shaders(\"RobotDARTShaders\");\n\n                    const Magnum::GL::Version version = Magnum::GL::Version::GL320;\n\n                    Magnum::GL::Shader vert = Magnum::Shaders::Implementation::createCompatibilityShader(\n                        rs_shaders, version, Magnum::GL::Shader::Type::Vertex);\n                    Magnum::GL::Shader frag = Magnum::Shaders::Implementation::createCompatibilityShader(\n                        rs_shaders, version, Magnum::GL::Shader::Type::Fragment);\n\n                    std::string defines = \"#define POSITION_ATTRIBUTE_LOCATION \" + std::to_string(Position::Location) + \"\\n\";\n                    defines += \"#define TEXTURECOORDINATES_ATTRIBUTE_LOCATION \" + std::to_string(TextureCoordinates::Location) + \"\\n\";\n\n                    vert.addSource(flags ? \"#define TEXTURED\\n\" : \"\")\n                        .addSource(defines)\n                        .addSource(rs_shaders.get(\"ShadowMap.vert\"));\n                    frag.addSource(flags ? \"#define TEXTURED\\n\" : \"\")\n                        .addSource(rs_shaders.get(\"ShadowMapColor.frag\"));\n\n                    CORRADE_INTERNAL_ASSERT_OUTPUT(Magnum::GL::Shader::compile({vert, frag}));\n\n                    attachShaders({vert, frag});\n\n                    if (!Magnum::GL::Context::current().isExtensionSupported<Magnum::GL::Extensions::ARB::explicit_attrib_location>(version)) {\n                        bindAttributeLocation(Position::Location, \"position\");\n                        if (flags)\n                            bindAttributeLocation(TextureCoordinates::Location, \"textureCoords\");\n                    }\n\n                    CORRADE_INTERNAL_ASSERT_OUTPUT(link());\n\n                    if (!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                    }\n\n                    if (!Magnum::GL::Context::current()\n                             .isExtensionSupported<Magnum::GL::Extensions::ARB::shading_language_420pack>(version)\n                        && flags) {\n                        setUniform(uniformLocation(\"diffuseTexture\"), DiffuseTextureLayer);\n                    }\n                }\n\n                ShadowMapColor::ShadowMapColor(Magnum::NoCreateT) noexcept : Magnum::GL::AbstractShaderProgram{Magnum::NoCreate} {}\n\n                ShadowMapColor::Flags ShadowMapColor::flags() const { return _flags; }\n\n                ShadowMapColor& ShadowMapColor::set_transformation_matrix(const Magnum::Matrix4& matrix)\n                {\n                    setUniform(_transformation_matrix_uniform, matrix);\n                    return *this;\n                }\n\n                ShadowMapColor& ShadowMapColor::set_projection_matrix(const Magnum::Matrix4& matrix)\n                {\n                    setUniform(_projection_matrix_uniform, matrix);\n                    return *this;\n                }\n\n                ShadowMapColor& ShadowMapColor::set_material(Material& material)\n                {\n                    if (material.has_diffuse_texture() && (_flags & Flag::DiffuseTexture)) {\n                        (*material.diffuse_texture()).bind(DiffuseTextureLayer);\n                        setUniform(_diffuse_color_uniform, Magnum::Color4{1.0f});\n                    }\n                    else\n                        setUniform(_diffuse_color_uniform, material.diffuse_color());\n\n                    return *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

  • #include <robot_dart/gui/magnum/gs/material.hpp>
  • #include <Corrade/Containers/ArrayView.h>
  • #include <Corrade/Containers/Reference.h>
  • #include <Corrade/Utility/Assert.h>
  • #include <Magnum/GL/AbstractShaderProgram.h>
  • #include <Magnum/Math/Color.h>
  • #include <Magnum/Math/Matrix4.h>
  • #include <Magnum/Shaders/Generic.h>
"},{"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\n#include <robot_dart/gui/magnum/gs/material.hpp>\n\n#include <Corrade/Containers/ArrayView.h>\n#include <Corrade/Containers/Reference.h>\n#include <Corrade/Utility/Assert.h>\n\n#include <Magnum/GL/AbstractShaderProgram.h>\n#include <Magnum/Math/Color.h>\n#include <Magnum/Math/Matrix4.h>\n#include <Magnum/Shaders/Generic.h>\n\nnamespace robot_dart {\n    namespace gui {\n        namespace magnum {\n            namespace gs {\n                class ShadowMapColor : public Magnum::GL::AbstractShaderProgram {\n                public:\n                    using Position = Magnum::Shaders::Generic3D::Position;\n                    using TextureCoordinates = Magnum::Shaders::Generic3D::TextureCoordinates;\n\n                    enum class Flag : Magnum::UnsignedByte {\n                        DiffuseTexture = 1 << 0, \n                    };\n\n                    using Flags = Magnum::Containers::EnumSet<Flag>;\n\n                    explicit ShadowMapColor(Flags flags = {});\n                    explicit ShadowMapColor(Magnum::NoCreateT) noexcept;\n\n                    Flags flags() const;\n\n                    ShadowMapColor& set_transformation_matrix(const Magnum::Matrix4& matrix);\n                    ShadowMapColor& set_projection_matrix(const Magnum::Matrix4& matrix);\n                    ShadowMapColor& set_material(Material& material);\n\n                private:\n                    Flags _flags;\n                    Magnum::Int _transformation_matrix_uniform{0}, _projection_matrix_uniform{1}, _diffuse_color_uniform{2};\n                };\n\n                CORRADE_ENUMSET_OPERATORS(ShadowMapColor::Flags)\n            } // namespace gs\n        } // namespace magnum\n    } // namespace gui\n} // namespace robot_dart\n\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

  • #include \"camera.hpp\"
  • #include <Corrade/Containers/ArrayViewStl.h>
  • #include <Corrade/Containers/StridedArrayView.h>
  • #include <Corrade/Utility/Algorithms.h>
  • #include <Magnum/GL/PixelFormat.h>
  • #include <Magnum/GL/RenderbufferFormat.h>
  • #include <Magnum/GL/Renderer.h>
  • #include <Magnum/GL/TextureFormat.h>
  • #include <Magnum/ImageView.h>
  • #include <Magnum/PixelFormat.h>
  • #include <robot_dart/gui/magnum/utils_headers_eigen.hpp>
"},{"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":"

File: api/sensor_2camera_8cpp_source.md

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

  • #include <robot_dart/gui/magnum/base_application.hpp>
  • #include <robot_dart/gui/magnum/gs/helper.hpp>
  • #include <robot_dart/sensor/sensor.hpp>
  • #include <Magnum/GL/Framebuffer.h>
  • #include <Magnum/GL/Renderbuffer.h>
  • #include <Magnum/PixelFormat.h>
"},{"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\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\n#include <Magnum/GL/Framebuffer.h>\n#include <Magnum/GL/Renderbuffer.h>\n#include <Magnum/PixelFormat.h>\n\nnamespace robot_dart {\n    namespace gui {\n        namespace magnum {\n            namespace sensor {\n                class Camera : public robot_dart::sensor::Sensor {\n                public:\n                    Camera(BaseApplication* app, size_t width, size_t height, size_t freq = 30, bool draw_debug = false);\n                    ~Camera() {}\n\n                    void init() override;\n\n                    void calculate(double) override;\n\n                    std::string type() const override;\n\n                    void attach_to_body(dart::dynamics::BodyNode* body, const Eigen::Isometry3d& tf = Eigen::Isometry3d::Identity()) override;\n\n                    void attach_to_joint(dart::dynamics::Joint*, const Eigen::Isometry3d&) override\n                    {\n                        ROBOT_DART_WARNING(true, \"You cannot attach a camera to a joint!\");\n                    }\n\n                    gs::Camera& camera() { return *_camera; }\n                    const gs::Camera& camera() const { return *_camera; }\n\n                    Eigen::Matrix3d camera_intrinsic_matrix() const;\n                    Eigen::Matrix4d camera_extrinsic_matrix() const;\n\n                    bool drawing_debug() const { return _draw_debug; }\n                    void draw_debug(bool draw = true) { _draw_debug = draw; }\n\n                    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));\n\n                    // this will use the default FPS of the camera if fps == -1\n                    void record_video(const std::string& video_fname)\n                    {\n                        _camera->record_video(video_fname, _frequency);\n                    }\n\n                    Magnum::Image2D* magnum_image()\n                    {\n                        if (_camera->image())\n                            return &(*_camera->image());\n                        return nullptr;\n                    }\n\n                    Image image()\n                    {\n                        auto image = magnum_image();\n                        if (image)\n                            return gs::rgb_from_image(image);\n                        return Image();\n                    }\n\n                    Magnum::Image2D* magnum_depth_image()\n                    {\n                        if (_camera->depth_image())\n                            return &(*_camera->depth_image());\n                        return nullptr;\n                    }\n\n                    // This is for visualization purposes\n                    GrayscaleImage depth_image();\n\n                    // Image filled with depth buffer values\n                    GrayscaleImage raw_depth_image();\n\n                    // \"Image\" filled with depth buffer values (this returns an array of doubles)\n                    DepthImage depth_array();\n\n                protected:\n                    Magnum::GL::Framebuffer _framebuffer{Magnum::NoCreate};\n                    Magnum::PixelFormat _format;\n                    Magnum::GL::Renderbuffer _color, _depth;\n\n                    BaseApplication* _magnum_app;\n                    size_t _width, _height;\n\n                    std::unique_ptr<gs::Camera> _camera;\n\n                    bool _draw_debug;\n                };\n            } // namespace sensor\n        } // namespace magnum\n    } // namespace gui\n\n    namespace sensor {\n        using gui::magnum::sensor::Camera;\n    }\n} // namespace robot_dart\n\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

  • #include <Magnum/SceneGraph/Camera.h>
  • #include <Magnum/SceneGraph/MatrixTransformation3D.h>
  • #include <Magnum/SceneGraph/Scene.h>
"},{"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\n#include <Magnum/SceneGraph/Camera.h>\n#include <Magnum/SceneGraph/MatrixTransformation3D.h>\n#include <Magnum/SceneGraph/Scene.h>\n\nnamespace robot_dart {\n    namespace gui {\n        namespace magnum {\n            using Object3D = Magnum::SceneGraph::Object<Magnum::SceneGraph::MatrixTransformation3D>;\n            using Scene3D = Magnum::SceneGraph::Scene<Magnum::SceneGraph::MatrixTransformation3D>;\n            using Camera3D = Magnum::SceneGraph::Camera3D;\n        } // namespace magnum\n    } // namespace gui\n} // namespace robot_dart\n\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

  • #include <Magnum/EigenIntegration/GeometryIntegration.h>
  • #include <Magnum/EigenIntegration/Integration.h>

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\n#pragma GCC system_header\n\n#include <Magnum/EigenIntegration/GeometryIntegration.h>\n#include <Magnum/EigenIntegration/Integration.h>\n\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

  • #include \"windowless_gl_application.hpp\"
  • #include <Magnum/GL/RenderbufferFormat.h>
  • #include <Magnum/GL/Renderer.h>
"},{"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":"

File: api/windowless__gl__application_8cpp_source.md

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

  • #include <robot_dart/gui/magnum/base_application.hpp>
  • #include <Magnum/GL/Renderbuffer.h>
  • #include <Magnum/PixelFormat.h>
"},{"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\n#include <robot_dart/gui/magnum/base_application.hpp>\n\n#include <Magnum/GL/Renderbuffer.h>\n#include <Magnum/PixelFormat.h>\n\nnamespace robot_dart {\n    namespace gui {\n        namespace magnum {\n            class WindowlessGLApplication : public BaseApplication, public Magnum::Platform::WindowlessApplication {\n            public:\n                explicit WindowlessGLApplication(int argc, char** argv, RobotDARTSimu* simu, const GraphicsConfiguration& configuration = GraphicsConfiguration());\n                ~WindowlessGLApplication();\n\n                void render() override;\n\n            protected:\n                RobotDARTSimu* _simu;\n                bool _draw_main_camera, _draw_debug;\n                Magnum::Color4 _bg_color;\n                Magnum::GL::Framebuffer _framebuffer{Magnum::NoCreate};\n                Magnum::PixelFormat _format;\n                Magnum::GL::Renderbuffer _color{Magnum::NoCreate}, _depth{Magnum::NoCreate};\n                // size_t _index = 0;\n\n                virtual int exec() override { return 0; }\n            };\n        } // namespace magnum\n    } // namespace gui\n} // namespace robot_dart\n\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

  • #include <robot_dart/gui/magnum/windowless_graphics.hpp>
"},{"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>\n\nnamespace robot_dart {\n    namespace gui {\n        namespace magnum {\n            void WindowlessGraphics::set_simu(RobotDARTSimu* simu)\n            {\n                BaseGraphics<WindowlessGLApplication>::set_simu(simu);\n                // we should not synchronize by default if we want windowless graphics (usually used only for sensors)\n                simu->scheduler().set_sync(false);\n                // disable summary text when windowless graphics activated\n                simu->enable_text_panel(false);\n                simu->enable_status_bar(false);\n            }\n\n            GraphicsConfiguration WindowlessGraphics::default_configuration()\n            {\n                GraphicsConfiguration config;\n                // by default we do not draw text in windowless mode\n                config.draw_debug = false;\n                config.draw_text = false;\n\n                return 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

  • #include <robot_dart/gui/magnum/base_graphics.hpp>
  • #include <robot_dart/gui/magnum/windowless_gl_application.hpp>
"},{"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\n#include <robot_dart/gui/magnum/base_graphics.hpp>\n#include <robot_dart/gui/magnum/windowless_gl_application.hpp>\n\nnamespace robot_dart {\n    namespace gui {\n        namespace magnum {\n            class WindowlessGraphics : public BaseGraphics<WindowlessGLApplication> {\n            public:\n                WindowlessGraphics(const GraphicsConfiguration& configuration = default_configuration()) : BaseGraphics<WindowlessGLApplication>(configuration) {}\n                ~WindowlessGraphics() {}\n\n                void set_simu(RobotDARTSimu* simu) override;\n\n                static GraphicsConfiguration default_configuration();\n            };\n        } // namespace magnum\n    } // namespace gui\n} // namespace robot_dart\n\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

  • #include <stdlib.h>
"},{"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 (\n    int flip_boolean\n) \n
"},{"location":"api/stb__image__write_8h/#function-stbi_write_bmp","title":"function stbi_write_bmp","text":"
STBIWDEF int stbi_write_bmp (\n    char const * filename,\n    int w,\n    int h,\n    int comp,\n    const void * data\n) \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 (\n    stbi_write_func * func,\n    void * context,\n    int w,\n    int h,\n    int comp,\n    const void * data\n) \n
"},{"location":"api/stb__image__write_8h/#function-stbi_write_hdr","title":"function stbi_write_hdr","text":"
STBIWDEF int stbi_write_hdr (\n    char const * filename,\n    int w,\n    int h,\n    int comp,\n    const float * data\n) \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 (\n    stbi_write_func * func,\n    void * context,\n    int w,\n    int h,\n    int comp,\n    const float * data\n) \n
"},{"location":"api/stb__image__write_8h/#function-stbi_write_jpg","title":"function stbi_write_jpg","text":"
STBIWDEF int stbi_write_jpg (\n    char const * filename,\n    int x,\n    int y,\n    int comp,\n    const void * data,\n    int quality\n) \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 (\n    stbi_write_func * func,\n    void * context,\n    int x,\n    int y,\n    int comp,\n    const void * data,\n    int quality\n) \n
"},{"location":"api/stb__image__write_8h/#function-stbi_write_png","title":"function stbi_write_png","text":"
STBIWDEF int stbi_write_png (\n    char const * filename,\n    int w,\n    int h,\n    int comp,\n    const void * data,\n    int stride_in_bytes\n) \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 (\n    stbi_write_func * func,\n    void * context,\n    int w,\n    int h,\n    int comp,\n    const void * data,\n    int stride_in_bytes\n) \n
"},{"location":"api/stb__image__write_8h/#function-stbi_write_tga","title":"function stbi_write_tga","text":"
STBIWDEF int stbi_write_tga (\n    char const * filename,\n    int w,\n    int h,\n    int comp,\n    const void * data\n) \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 (\n    stbi_write_func * func,\n    void * context,\n    int w,\n    int h,\n    int comp,\n    const void * data\n) \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\n   Before #including,\n\n       #define STB_IMAGE_WRITE_IMPLEMENTATION\n\n   in the file that you want to have the implementation.\n\n   Will probably not work correctly with strict-aliasing optimizations.\n\nABOUT:\n\n   This header file is a library for writing images to C stdio or a callback.\n\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.\n\nBUILDING:\n\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),\n\nUNICODE:\n\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.\n\nUSAGE:\n\n   There are five functions, one for each image file format:\n\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\n     void stbi_flip_vertically_on_write(int flag); // flag is non-zero to flip data vertically\n\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\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\n   where the callback is:\n      void stbi_write_func(void *context, void *data, int size);\n\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\n\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\n   Each function returns 0 on failure and non-0 on success.\n\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\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\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\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\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\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\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).\n\nCREDITS:\n\n\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\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\n\nLICENSE\n\n  See end of file for license information.\n\n*/\n\n#pragma GCC system_header\n\n#ifndef INCLUDE_STB_IMAGE_WRITE_H\n#define INCLUDE_STB_IMAGE_WRITE_H\n\n#include <stdlib.h>\n\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\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\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\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\n\ntypedef void stbi_write_func(void *context, void *data, int size);\n\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);\n\nSTBIWDEF void stbi_flip_vertically_on_write(int flip_boolean);\n\n#endif//INCLUDE_STB_IMAGE_WRITE_H\n\n#ifdef STB_IMAGE_WRITE_IMPLEMENTATION\n\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\n#ifndef STBI_WRITE_NO_STDIO\n#include <stdio.h>\n#endif // STBI_WRITE_NO_STDIO\n\n#include <stdarg.h>\n#include <stdlib.h>\n#include <string.h>\n#include <math.h>\n\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\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\n#ifndef STBIW_REALLOC_SIZED\n#define STBIW_REALLOC_SIZED(p,oldsz,newsz) STBIW_REALLOC(p,newsz)\n#endif\n\n\n#ifndef STBIW_MEMMOVE\n#define STBIW_MEMMOVE(a,b,sz) memmove(a,b,sz)\n#endif\n\n\n#ifndef STBIW_ASSERT\n#include <assert.h>\n#define STBIW_ASSERT(x) assert(x)\n#endif\n\n#define STBIW_UCHAR(x) (unsigned char) ((x) & 0xff)\n\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\n\nSTBIWDEF void stbi_flip_vertically_on_write(int flag)\n{\n   stbi__flip_vertically_on_write = flag;\n}\n\ntypedef struct\n{\n   stbi_write_func *func;\n   void *context;\n} stbi__write_context;\n\n// initialize a callback-based context\nstatic void stbi__start_write_callbacks(stbi__write_context *s, stbi_write_func *c, void *context)\n{\n   s->func    = c;\n   s->context = context;\n}\n\n#ifndef STBI_WRITE_NO_STDIO\n\nstatic void stbi__stdio_write(void *context, void *data, int size)\n{\n   fwrite(data,1,size,(FILE*) context);\n}\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);\n\nSTBIWDEF int stbiw_convert_wchar_to_utf8(char *buffer, size_t bufferlen, const wchar_t* input)\n{\n    return WideCharToMultiByte(65001 /* UTF8 */, 0, input, -1, buffer, (int) bufferlen, NULL, NULL);\n}\n#endif\n\nstatic FILE *stbiw__fopen(char const *filename, char const *mode)\n{\n   FILE *f;\n#if defined(_MSC_VER) && defined(STBI_WINDOWS_UTF8)\n   wchar_t wMode[64];\n   wchar_t wFilename[1024];\n    if (0 == MultiByteToWideChar(65001 /* UTF8 */, 0, filename, -1, wFilename, sizeof(wFilename)))\n      return 0;\n\n    if (0 == MultiByteToWideChar(65001 /* UTF8 */, 0, mode, -1, wMode, sizeof(wMode)))\n      return 0;\n\n#if _MSC_VER >= 1400\n    if (0 != _wfopen_s(&f, wFilename, wMode))\n        f = 0;\n#else\n   f = _wfopen(wFilename, wMode);\n#endif\n\n#elif defined(_MSC_VER) && _MSC_VER >= 1400\n   if (0 != fopen_s(&f, filename, mode))\n      f=0;\n#else\n   f = fopen(filename, mode);\n#endif\n   return f;\n}\n\nstatic int stbi__start_write_file(stbi__write_context *s, const char *filename)\n{\n   FILE *f = stbiw__fopen(filename, \"wb\");\n   stbi__start_write_callbacks(s, stbi__stdio_write, (void *) f);\n   return f != NULL;\n}\n\nstatic void stbi__end_write_file(stbi__write_context *s)\n{\n   fclose((FILE *)s->context);\n}\n\n#endif // !STBI_WRITE_NO_STDIO\n\ntypedef unsigned int stbiw_uint32;\ntypedef int stb_image_write_test[sizeof(stbiw_uint32)==4 ? 1 : -1];\n\nstatic void stbiw__writefv(stbi__write_context *s, const char *fmt, va_list v)\n{\n   while (*fmt) {\n      switch (*fmt++) {\n         case ' ': break;\n         case '1': { unsigned char x = STBIW_UCHAR(va_arg(v, int));\n                     s->func(s->context,&x,1);\n                     break; }\n         case '2': { int x = va_arg(v,int);\n                     unsigned char b[2];\n                     b[0] = STBIW_UCHAR(x);\n                     b[1] = STBIW_UCHAR(x>>8);\n                     s->func(s->context,b,2);\n                     break; }\n         case '4': { stbiw_uint32 x = va_arg(v,int);\n                     unsigned char b[4];\n                     b[0]=STBIW_UCHAR(x);\n                     b[1]=STBIW_UCHAR(x>>8);\n                     b[2]=STBIW_UCHAR(x>>16);\n                     b[3]=STBIW_UCHAR(x>>24);\n                     s->func(s->context,b,4);\n                     break; }\n         default:\n            STBIW_ASSERT(0);\n            return;\n      }\n   }\n}\n\nstatic void stbiw__writef(stbi__write_context *s, const char *fmt, ...)\n{\n   va_list v;\n   va_start(v, fmt);\n   stbiw__writefv(s, fmt, v);\n   va_end(v);\n}\n\nstatic void stbiw__putc(stbi__write_context *s, unsigned char c)\n{\n   s->func(s->context, &c, 1);\n}\n\nstatic void stbiw__write3(stbi__write_context *s, unsigned char a, unsigned char b, unsigned char c)\n{\n   unsigned char arr[3];\n   arr[0] = a; arr[1] = b; arr[2] = c;\n   s->func(s->context, arr, 3);\n}\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{\n   unsigned char bg[3] = { 255, 0, 255}, px[3];\n   int k;\n\n   if (write_alpha < 0)\n      s->func(s->context, &d[comp - 1], 1);\n\n   switch (comp) {\n      case 2: // 2 pixels = mono + alpha, alpha is written separately, so same as 1-channel case\n      case 1:\n         if (expand_mono)\n            stbiw__write3(s, d[0], d[0], d[0]); // monochrome bmp\n         else\n            s->func(s->context, d, 1);  // monochrome TGA\n         break;\n      case 4:\n         if (!write_alpha) {\n            // composite against pink background\n            for (k = 0; k < 3; ++k)\n               px[k] = bg[k] + ((d[k] - bg[k]) * d[3]) / 255;\n            stbiw__write3(s, px[1 - rgb_dir], px[1], px[1 + rgb_dir]);\n            break;\n         }\n         /* FALLTHROUGH */\n      case 3:\n         stbiw__write3(s, d[1 - rgb_dir], d[1], d[1 + rgb_dir]);\n         break;\n   }\n   if (write_alpha > 0)\n      s->func(s->context, &d[comp - 1], 1);\n}\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{\n   stbiw_uint32 zero = 0;\n   int i,j, j_end;\n\n   if (y <= 0)\n      return;\n\n   if (stbi__flip_vertically_on_write)\n      vdir *= -1;\n\n   if (vdir < 0) {\n      j_end = -1; j = y-1;\n   } else {\n      j_end =  y; j = 0;\n   }\n\n   for (; j != j_end; j += vdir) {\n      for (i=0; i < x; ++i) {\n         unsigned char *d = (unsigned char *) data + (j*x+i)*comp;\n         stbiw__write_pixel(s, rgb_dir, comp, write_alpha, expand_mono, d);\n      }\n      s->func(s->context, &zero, scanline_pad);\n   }\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{\n   if (y < 0 || x < 0) {\n      return 0;\n   } else {\n      va_list v;\n      va_start(v, fmt);\n      stbiw__writefv(s, fmt, v);\n      va_end(v);\n      stbiw__write_pixels(s,rgb_dir,vdir,x,y,comp,data,alpha,pad, expand_mono);\n      return 1;\n   }\n}\n\nstatic int stbi_write_bmp_core(stbi__write_context *s, int x, int y, int comp, const void *data)\n{\n   int pad = (-x*3) & 3;\n   return 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\n            40, x,y, 1,24, 0,0,0,0,0,0);             // bitmap header\n}\n\nSTBIWDEF int stbi_write_bmp_to_func(stbi_write_func *func, void *context, int x, int y, int comp, const void *data)\n{\n   stbi__write_context s;\n   stbi__start_write_callbacks(&s, func, context);\n   return stbi_write_bmp_core(&s, x, y, comp, data);\n}\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{\n   stbi__write_context s;\n   if (stbi__start_write_file(&s,filename)) {\n      int r = stbi_write_bmp_core(&s, x, y, comp, data);\n      stbi__end_write_file(&s);\n      return r;\n   } else\n      return 0;\n}\n#endif \n\nstatic int stbi_write_tga_core(stbi__write_context *s, int x, int y, int comp, void *data)\n{\n   int has_alpha = (comp == 2 || comp == 4);\n   int colorbytes = has_alpha ? comp-1 : comp;\n   int format = colorbytes < 2 ? 3 : 2; // 3 color channels (RGB/RGBA) = 2, 1 color channel (Y/YA) = 3\n\n   if (y < 0 || x < 0)\n      return 0;\n\n   if (!stbi_write_tga_with_rle) {\n      return 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 {\n      int i,j,k;\n      int jend, jdir;\n\n      stbiw__writef(s, \"111 221 2222 11\", 0,0,format+8, 0,0,0, 0,0,x,y, (colorbytes + has_alpha) * 8, has_alpha * 8);\n\n      if (stbi__flip_vertically_on_write) {\n         j = 0;\n         jend = y;\n         jdir = 1;\n      } else {\n         j = y-1;\n         jend = -1;\n         jdir = -1;\n      }\n      for (; j != jend; j += jdir) {\n         unsigned char *row = (unsigned char *) data + j * x * comp;\n         int len;\n\n         for (i = 0; i < x; i += len) {\n            unsigned char *begin = row + i * comp;\n            int diff = 1;\n            len = 1;\n\n            if (i < x - 1) {\n               ++len;\n               diff = memcmp(begin, row + (i + 1) * comp, comp);\n               if (diff) {\n                  const unsigned char *prev = begin;\n                  for (k = i + 2; k < x && len < 128; ++k) {\n                     if (memcmp(prev, row + k * comp, comp)) {\n                        prev += comp;\n                        ++len;\n                     } else {\n                        --len;\n                        break;\n                     }\n                  }\n               } else {\n                  for (k = i + 2; k < x && len < 128; ++k) {\n                     if (!memcmp(begin, row + k * comp, comp)) {\n                        ++len;\n                     } else {\n                        break;\n                     }\n                  }\n               }\n            }\n\n            if (diff) {\n               unsigned char header = STBIW_UCHAR(len - 1);\n               s->func(s->context, &header, 1);\n               for (k = 0; k < len; ++k) {\n                  stbiw__write_pixel(s, -1, comp, has_alpha, 0, begin + k * comp);\n               }\n            } else {\n               unsigned char header = STBIW_UCHAR(len - 129);\n               s->func(s->context, &header, 1);\n               stbiw__write_pixel(s, -1, comp, has_alpha, 0, begin);\n            }\n         }\n      }\n   }\n   return 1;\n}\n\nSTBIWDEF int stbi_write_tga_to_func(stbi_write_func *func, void *context, int x, int y, int comp, const void *data)\n{\n   stbi__write_context s;\n   stbi__start_write_callbacks(&s, func, context);\n   return stbi_write_tga_core(&s, x, y, comp, (void *) data);\n}\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{\n   stbi__write_context s;\n   if (stbi__start_write_file(&s,filename)) {\n      int r = stbi_write_tga_core(&s, x, y, comp, (void *) data);\n      stbi__end_write_file(&s);\n      return r;\n   } else\n      return 0;\n}\n#endif\n\n// *************************************************************************************************\n// Radiance RGBE HDR writer\n// by Baldur Karlsson\n\n#define stbiw__max(a, b)  ((a) > (b) ? (a) : (b))\n\nstatic void stbiw__linear_to_rgbe(unsigned char *rgbe, float *linear)\n{\n   int exponent;\n   float maxcomp = stbiw__max(linear[0], stbiw__max(linear[1], linear[2]));\n\n   if (maxcomp < 1e-32f) {\n      rgbe[0] = rgbe[1] = rgbe[2] = rgbe[3] = 0;\n   } else {\n      float normalize = (float) frexp(maxcomp, &exponent) * 256.0f/maxcomp;\n\n      rgbe[0] = (unsigned char)(linear[0] * normalize);\n      rgbe[1] = (unsigned char)(linear[1] * normalize);\n      rgbe[2] = (unsigned char)(linear[2] * normalize);\n      rgbe[3] = (unsigned char)(exponent + 128);\n   }\n}\n\nstatic void stbiw__write_run_data(stbi__write_context *s, int length, unsigned char databyte)\n{\n   unsigned char lengthbyte = STBIW_UCHAR(length+128);\n   STBIW_ASSERT(length+128 <= 255);\n   s->func(s->context, &lengthbyte, 1);\n   s->func(s->context, &databyte, 1);\n}\n\nstatic void stbiw__write_dump_data(stbi__write_context *s, int length, unsigned char *data)\n{\n   unsigned char lengthbyte = STBIW_UCHAR(length);\n   STBIW_ASSERT(length <= 128); // inconsistent with spec but consistent with official code\n   s->func(s->context, &lengthbyte, 1);\n   s->func(s->context, data, length);\n}\n\nstatic void stbiw__write_hdr_scanline(stbi__write_context *s, int width, int ncomp, unsigned char *scratch, float *scanline)\n{\n   unsigned char scanlineheader[4] = { 2, 2, 0, 0 };\n   unsigned char rgbe[4];\n   float linear[3];\n   int x;\n\n   scanlineheader[2] = (width&0xff00)>>8;\n   scanlineheader[3] = (width&0x00ff);\n\n   /* skip RLE for images too small or large */\n   if (width < 8 || width >= 32768) {\n      for (x=0; x < width; x++) {\n         switch (ncomp) {\n            case 4: /* fallthrough */\n            case 3: linear[2] = scanline[x*ncomp + 2];\n                    linear[1] = scanline[x*ncomp + 1];\n                    linear[0] = scanline[x*ncomp + 0];\n                    break;\n            default:\n                    linear[0] = linear[1] = linear[2] = scanline[x*ncomp + 0];\n                    break;\n         }\n         stbiw__linear_to_rgbe(rgbe, linear);\n         s->func(s->context, rgbe, 4);\n      }\n   } else {\n      int c,r;\n      /* encode into scratch buffer */\n      for (x=0; x < width; x++) {\n         switch(ncomp) {\n            case 4: /* fallthrough */\n            case 3: linear[2] = scanline[x*ncomp + 2];\n                    linear[1] = scanline[x*ncomp + 1];\n                    linear[0] = scanline[x*ncomp + 0];\n                    break;\n            default:\n                    linear[0] = linear[1] = linear[2] = scanline[x*ncomp + 0];\n                    break;\n         }\n         stbiw__linear_to_rgbe(rgbe, linear);\n         scratch[x + width*0] = rgbe[0];\n         scratch[x + width*1] = rgbe[1];\n         scratch[x + width*2] = rgbe[2];\n         scratch[x + width*3] = rgbe[3];\n      }\n\n      s->func(s->context, scanlineheader, 4);\n\n      /* RLE each component separately */\n      for (c=0; c < 4; c++) {\n         unsigned char *comp = &scratch[width*c];\n\n         x = 0;\n         while (x < width) {\n            // find first run\n            r = x;\n            while (r+2 < width) {\n               if (comp[r] == comp[r+1] && comp[r] == comp[r+2])\n                  break;\n               ++r;\n            }\n            if (r+2 >= width)\n               r = width;\n            // dump up to first run\n            while (x < r) {\n               int len = r-x;\n               if (len > 128) len = 128;\n               stbiw__write_dump_data(s, len, &comp[x]);\n               x += len;\n            }\n            // if there's a run, output it\n            if (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\n               while (r < width && comp[r] == comp[x])\n                  ++r;\n               // output run up to r\n               while (x < r) {\n                  int len = r-x;\n                  if (len > 127) len = 127;\n                  stbiw__write_run_data(s, len, comp[x]);\n                  x += len;\n               }\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{\n   if (y <= 0 || x <= 0 || data == NULL)\n      return 0;\n   else {\n      // Each component is stored separately. Allocate scratch space for full output scanline.\n      unsigned char *scratch = (unsigned char *) STBIW_MALLOC(x*4);\n      int i, len;\n      char buffer[128];\n      char header[] = \"#?RADIANCE\\n# Written by stb_image_write.h\\nFORMAT=32-bit_rle_rgbe\\n\";\n      s->func(s->context, header, sizeof(header)-1);\n\n#ifdef __STDC_WANT_SECURE_LIB__\n      len = sprintf_s(buffer, sizeof(buffer), \"EXPOSURE=          1.0000000000000\\n\\n-Y %d +X %d\\n\", y, x);\n#else\n      len = sprintf(buffer, \"EXPOSURE=          1.0000000000000\\n\\n-Y %d +X %d\\n\", y, x);\n#endif\n      s->func(s->context, buffer, len);\n\n      for(i=0; i < y; i++)\n         stbiw__write_hdr_scanline(s, x, comp, scratch, data + comp*x*(stbi__flip_vertically_on_write ? y-1-i : i));\n      STBIW_FREE(scratch);\n      return 1;\n   }\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{\n   stbi__write_context s;\n   stbi__start_write_callbacks(&s, func, context);\n   return stbi_write_hdr_core(&s, x, y, comp, (float *) data);\n}\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{\n   stbi__write_context s;\n   if (stbi__start_write_file(&s,filename)) {\n      int r = stbi_write_hdr_core(&s, x, y, comp, (float *) data);\n      stbi__end_write_file(&s);\n      return r;\n   } else\n      return 0;\n}\n#endif // STBI_WRITE_NO_STDIO\n\n\n//\n// PNG writer\n//\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\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\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)\n\nstatic void *stbiw__sbgrowf(void **arr, int increment, int itemsize)\n{\n   int m = *arr ? 2*stbiw__sbm(*arr)+increment : increment+1;\n   void *p = STBIW_REALLOC_SIZED(*arr ? stbiw__sbraw(*arr) : 0, *arr ? (stbiw__sbm(*arr)*itemsize + sizeof(int)*2) : 0, itemsize * m + sizeof(int)*2);\n   STBIW_ASSERT(p);\n   if (p) {\n      if (!*arr) ((int *) p)[1] = 0;\n      *arr = (void *) ((int *) p + 2);\n      stbiw__sbm(*arr) = m;\n   }\n   return *arr;\n}\n\nstatic unsigned char *stbiw__zlib_flushf(unsigned char *data, unsigned int *bitbuffer, int *bitcount)\n{\n   while (*bitcount >= 8) {\n      stbiw__sbpush(data, STBIW_UCHAR(*bitbuffer));\n      *bitbuffer >>= 8;\n      *bitcount -= 8;\n   }\n   return data;\n}\n\nstatic int stbiw__zlib_bitrev(int code, int codebits)\n{\n   int res=0;\n   while (codebits--) {\n      res = (res << 1) | (code & 1);\n      code >>= 1;\n   }\n   return res;\n}\n\nstatic unsigned int stbiw__zlib_countm(unsigned char *a, unsigned char *b, int limit)\n{\n   int i;\n   for (i=0; i < limit && i < 258; ++i)\n      if (a[i] != b[i]) break;\n   return i;\n}\n\nstatic unsigned int stbiw__zhash(unsigned char *data)\n{\n   stbiw_uint32 hash = data[0] + (data[1] << 8) + (data[2] << 16);\n   hash ^= hash << 3;\n   hash += hash >> 5;\n   hash ^= hash << 4;\n   hash += hash >> 17;\n   hash ^= hash << 25;\n   hash += hash >> 6;\n   return hash;\n}\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\n#define stbiw__ZHASH   16384\n\n#endif // STBIW_ZLIB_COMPRESS\n\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\n   return STBIW_ZLIB_COMPRESS(data, data_len, out_len, quality);\n#else // use builtin\n   static 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 };\n   static 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 };\n   static 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 };\n   static 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 };\n   unsigned int bitbuf=0;\n   int i,j, bitcount=0;\n   unsigned char *out = NULL;\n   unsigned char ***hash_table = (unsigned char***) STBIW_MALLOC(stbiw__ZHASH * sizeof(unsigned char**));\n   if (hash_table == NULL)\n      return NULL;\n   if (quality < 5) quality = 5;\n\n   stbiw__sbpush(out, 0x78);   // DEFLATE 32K window\n   stbiw__sbpush(out, 0x5e);   // FLEVEL = 1\n   stbiw__zlib_add(1,1);  // BFINAL = 1\n   stbiw__zlib_add(1,2);  // BTYPE = 1 -- fixed huffman\n\n   for (i=0; i < stbiw__ZHASH; ++i)\n      hash_table[i] = NULL;\n\n   i=0;\n   while (i < data_len-3) {\n      // hash next 3 bytes of data to be compressed\n      int h = stbiw__zhash(data+i)&(stbiw__ZHASH-1), best=3;\n      unsigned char *bestloc = 0;\n      unsigned char **hlist = hash_table[h];\n      int n = stbiw__sbcount(hlist);\n      for (j=0; j < n; ++j) {\n         if (hlist[j]-data > i-32768) { // if entry lies within window\n            int d = stbiw__zlib_countm(hlist[j], data+i, data_len-i);\n            if (d >= best) { best=d; bestloc=hlist[j]; }\n         }\n      }\n      // when hash table entry is too long, delete half the entries\n      if (hash_table[h] && stbiw__sbn(hash_table[h]) == 2*quality) {\n         STBIW_MEMMOVE(hash_table[h], hash_table[h]+quality, sizeof(hash_table[h][0])*quality);\n         stbiw__sbn(hash_table[h]) = quality;\n      }\n      stbiw__sbpush(hash_table[h],data+i);\n\n      if (bestloc) {\n         // \"lazy matching\" - check match at *next* byte, and if it's better, do cur byte as literal\n         h = stbiw__zhash(data+i+1)&(stbiw__ZHASH-1);\n         hlist = hash_table[h];\n         n = stbiw__sbcount(hlist);\n         for (j=0; j < n; ++j) {\n            if (hlist[j]-data > i-32767) {\n               int e = stbiw__zlib_countm(hlist[j], data+i+1, data_len-i-1);\n               if (e > best) { // if next match is better, bail on current match\n                  bestloc = NULL;\n                  break;\n               }\n            }\n         }\n      }\n\n      if (bestloc) {\n         int d = (int) (data+i - bestloc); // distance back\n         STBIW_ASSERT(d <= 32767 && best <= 258);\n         for (j=0; best > lengthc[j+1]-1; ++j);\n         stbiw__zlib_huff(j+257);\n         if (lengtheb[j]) stbiw__zlib_add(best - lengthc[j], lengtheb[j]);\n         for (j=0; d > distc[j+1]-1; ++j);\n         stbiw__zlib_add(stbiw__zlib_bitrev(j,5),5);\n         if (disteb[j]) stbiw__zlib_add(d - distc[j], disteb[j]);\n         i += best;\n      } else {\n         stbiw__zlib_huffb(data[i]);\n         ++i;\n      }\n   }\n   // write out final bytes\n   for (;i < data_len; ++i)\n      stbiw__zlib_huffb(data[i]);\n   stbiw__zlib_huff(256); // end of block\n   // pad with 0 bits to byte boundary\n   while (bitcount)\n      stbiw__zlib_add(0,1);\n\n   for (i=0; i < stbiw__ZHASH; ++i)\n      (void) stbiw__sbfree(hash_table[i]);\n   STBIW_FREE(hash_table);\n\n   {\n      // compute adler32 on input\n      unsigned int s1=1, s2=0;\n      int blocklen = (int) (data_len % 5552);\n      j=0;\n      while (j < data_len) {\n         for (i=0; i < blocklen; ++i) { s1 += data[j+i]; s2 += s1; }\n         s1 %= 65521; s2 %= 65521;\n         j += blocklen;\n         blocklen = 5552;\n      }\n      stbiw__sbpush(out, STBIW_UCHAR(s2 >> 8));\n      stbiw__sbpush(out, STBIW_UCHAR(s2));\n      stbiw__sbpush(out, STBIW_UCHAR(s1 >> 8));\n      stbiw__sbpush(out, STBIW_UCHAR(s1));\n   }\n   *out_len = stbiw__sbn(out);\n   // make returned pointer freeable\n   STBIW_MEMMOVE(stbiw__sbraw(out), out, *out_len);\n   return (unsigned char *) stbiw__sbraw(out);\n#endif // STBIW_ZLIB_COMPRESS\n}\n\nstatic unsigned int stbiw__crc32(unsigned char *buffer, int len)\n{\n#ifdef STBIW_CRC32\n    return STBIW_CRC32(buffer, len);\n#else\n   static unsigned int crc_table[256] =\n   {\n      0x00000000, 0x77073096, 0xEE0E612C, 0x990951BA, 0x076DC419, 0x706AF48F, 0xE963A535, 0x9E6495A3,\n      0x0eDB8832, 0x79DCB8A4, 0xE0D5E91E, 0x97D2D988, 0x09B64C2B, 0x7EB17CBD, 0xE7B82D07, 0x90BF1D91,\n      0x1DB71064, 0x6AB020F2, 0xF3B97148, 0x84BE41DE, 0x1ADAD47D, 0x6DDDE4EB, 0xF4D4B551, 0x83D385C7,\n      0x136C9856, 0x646BA8C0, 0xFD62F97A, 0x8A65C9EC, 0x14015C4F, 0x63066CD9, 0xFA0F3D63, 0x8D080DF5,\n      0x3B6E20C8, 0x4C69105E, 0xD56041E4, 0xA2677172, 0x3C03E4D1, 0x4B04D447, 0xD20D85FD, 0xA50AB56B,\n      0x35B5A8FA, 0x42B2986C, 0xDBBBC9D6, 0xACBCF940, 0x32D86CE3, 0x45DF5C75, 0xDCD60DCF, 0xABD13D59,\n      0x26D930AC, 0x51DE003A, 0xC8D75180, 0xBFD06116, 0x21B4F4B5, 0x56B3C423, 0xCFBA9599, 0xB8BDA50F,\n      0x2802B89E, 0x5F058808, 0xC60CD9B2, 0xB10BE924, 0x2F6F7C87, 0x58684C11, 0xC1611DAB, 0xB6662D3D,\n      0x76DC4190, 0x01DB7106, 0x98D220BC, 0xEFD5102A, 0x71B18589, 0x06B6B51F, 0x9FBFE4A5, 0xE8B8D433,\n      0x7807C9A2, 0x0F00F934, 0x9609A88E, 0xE10E9818, 0x7F6A0DBB, 0x086D3D2D, 0x91646C97, 0xE6635C01,\n      0x6B6B51F4, 0x1C6C6162, 0x856530D8, 0xF262004E, 0x6C0695ED, 0x1B01A57B, 0x8208F4C1, 0xF50FC457,\n      0x65B0D9C6, 0x12B7E950, 0x8BBEB8EA, 0xFCB9887C, 0x62DD1DDF, 0x15DA2D49, 0x8CD37CF3, 0xFBD44C65,\n      0x4DB26158, 0x3AB551CE, 0xA3BC0074, 0xD4BB30E2, 0x4ADFA541, 0x3DD895D7, 0xA4D1C46D, 0xD3D6F4FB,\n      0x4369E96A, 0x346ED9FC, 0xAD678846, 0xDA60B8D0, 0x44042D73, 0x33031DE5, 0xAA0A4C5F, 0xDD0D7CC9,\n      0x5005713C, 0x270241AA, 0xBE0B1010, 0xC90C2086, 0x5768B525, 0x206F85B3, 0xB966D409, 0xCE61E49F,\n      0x5EDEF90E, 0x29D9C998, 0xB0D09822, 0xC7D7A8B4, 0x59B33D17, 0x2EB40D81, 0xB7BD5C3B, 0xC0BA6CAD,\n      0xEDB88320, 0x9ABFB3B6, 0x03B6E20C, 0x74B1D29A, 0xEAD54739, 0x9DD277AF, 0x04DB2615, 0x73DC1683,\n      0xE3630B12, 0x94643B84, 0x0D6D6A3E, 0x7A6A5AA8, 0xE40ECF0B, 0x9309FF9D, 0x0A00AE27, 0x7D079EB1,\n      0xF00F9344, 0x8708A3D2, 0x1E01F268, 0x6906C2FE, 0xF762575D, 0x806567CB, 0x196C3671, 0x6E6B06E7,\n      0xFED41B76, 0x89D32BE0, 0x10DA7A5A, 0x67DD4ACC, 0xF9B9DF6F, 0x8EBEEFF9, 0x17B7BE43, 0x60B08ED5,\n      0xD6D6A3E8, 0xA1D1937E, 0x38D8C2C4, 0x4FDFF252, 0xD1BB67F1, 0xA6BC5767, 0x3FB506DD, 0x48B2364B,\n      0xD80D2BDA, 0xAF0A1B4C, 0x36034AF6, 0x41047A60, 0xDF60EFC3, 0xA867DF55, 0x316E8EEF, 0x4669BE79,\n      0xCB61B38C, 0xBC66831A, 0x256FD2A0, 0x5268E236, 0xCC0C7795, 0xBB0B4703, 0x220216B9, 0x5505262F,\n      0xC5BA3BBE, 0xB2BD0B28, 0x2BB45A92, 0x5CB36A04, 0xC2D7FFA7, 0xB5D0CF31, 0x2CD99E8B, 0x5BDEAE1D,\n      0x9B64C2B0, 0xEC63F226, 0x756AA39C, 0x026D930A, 0x9C0906A9, 0xEB0E363F, 0x72076785, 0x05005713,\n      0x95BF4A82, 0xE2B87A14, 0x7BB12BAE, 0x0CB61B38, 0x92D28E9B, 0xE5D5BE0D, 0x7CDCEFB7, 0x0BDBDF21,\n      0x86D3D2D4, 0xF1D4E242, 0x68DDB3F8, 0x1FDA836E, 0x81BE16CD, 0xF6B9265B, 0x6FB077E1, 0x18B74777,\n      0x88085AE6, 0xFF0F6A70, 0x66063BCA, 0x11010B5C, 0x8F659EFF, 0xF862AE69, 0x616BFFD3, 0x166CCF45,\n      0xA00AE278, 0xD70DD2EE, 0x4E048354, 0x3903B3C2, 0xA7672661, 0xD06016F7, 0x4969474D, 0x3E6E77DB,\n      0xAED16A4A, 0xD9D65ADC, 0x40DF0B66, 0x37D83BF0, 0xA9BCAE53, 0xDEBB9EC5, 0x47B2CF7F, 0x30B5FFE9,\n      0xBDBDF21C, 0xCABAC28A, 0x53B39330, 0x24B4A3A6, 0xBAD03605, 0xCDD70693, 0x54DE5729, 0x23D967BF,\n      0xB3667A2E, 0xC4614AB8, 0x5D681B02, 0x2A6F2B94, 0xB40BBE37, 0xC30C8EA1, 0x5A05DF1B, 0x2D02EF8D\n   };\n\n   unsigned int crc = ~0u;\n   int i;\n   for (i=0; i < len; ++i)\n      crc = (crc >> 8) ^ crc_table[buffer[i] ^ (crc & 0xff)];\n   return ~crc;\n#endif\n}\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])\n\nstatic void stbiw__wpcrc(unsigned char **data, int len)\n{\n   unsigned int crc = stbiw__crc32(*data - len - 4, len+4);\n   stbiw__wp32(*data, crc);\n}\n\nstatic unsigned char stbiw__paeth(int a, int b, int c)\n{\n   int p = a + b - c, pa = abs(p-a), pb = abs(p-b), pc = abs(p-c);\n   if (pa <= pb && pa <= pc) return STBIW_UCHAR(a);\n   if (pb <= pc) return STBIW_UCHAR(b);\n   return STBIW_UCHAR(c);\n}\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{\n   static int mapping[] = { 0,1,2,3,4 };\n   static int firstmap[] = { 0,1,0,5,6 };\n   int *mymap = (y != 0) ? mapping : firstmap;\n   int i;\n   int type = mymap[filter_type];\n   unsigned char *z = pixels + stride_bytes * (stbi__flip_vertically_on_write ? height-1-y : y);\n   int signed_stride = stbi__flip_vertically_on_write ? -stride_bytes : stride_bytes;\n\n   if (type==0) {\n      memcpy(line_buffer, z, width*n);\n      return;\n   }\n\n   // first loop isn't optimized since it's just one pixel    \n   for (i = 0; i < n; ++i) {\n      switch (type) {\n         case 1: line_buffer[i] = z[i]; break;\n         case 2: line_buffer[i] = z[i] - z[i-signed_stride]; break;\n         case 3: line_buffer[i] = z[i] - (z[i-signed_stride]>>1); break;\n         case 4: line_buffer[i] = (signed char) (z[i] - stbiw__paeth(0,z[i-signed_stride],0)); break;\n         case 5: line_buffer[i] = z[i]; break;\n         case 6: line_buffer[i] = z[i]; break;\n      }\n   }\n   switch (type) {\n      case 1: for (i=n; i < width*n; ++i) line_buffer[i] = z[i] - z[i-n]; break;\n      case 2: for (i=n; i < width*n; ++i) line_buffer[i] = z[i] - z[i-signed_stride]; break;\n      case 3: for (i=n; i < width*n; ++i) line_buffer[i] = z[i] - ((z[i-n] + z[i-signed_stride])>>1); break;\n      case 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;\n      case 5: for (i=n; i < width*n; ++i) line_buffer[i] = z[i] - (z[i-n]>>1); break;\n      case 6: for (i=n; i < width*n; ++i) line_buffer[i] = z[i] - stbiw__paeth(z[i-n], 0,0); break;\n   }\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{\n   int force_filter = stbi_write_force_png_filter;\n   int ctype[5] = { -1, 0, 4, 2, 6 };\n   unsigned char sig[8] = { 137,80,78,71,13,10,26,10 };\n   unsigned char *out,*o, *filt, *zlib;\n   signed char *line_buffer;\n   int j,zlen;\n\n   if (stride_bytes == 0)\n      stride_bytes = x * n;\n\n   if (force_filter >= 5) {\n      force_filter = -1;\n   }\n\n   filt = (unsigned char *) STBIW_MALLOC((x*n+1) * y); if (!filt) return 0;\n   line_buffer = (signed char *) STBIW_MALLOC(x * n); if (!line_buffer) { STBIW_FREE(filt); return 0; }\n   for (j=0; j < y; ++j) {\n      int filter_type;\n      if (force_filter > -1) {\n         filter_type = force_filter;\n         stbiw__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:\n         int best_filter = 0, best_filter_val = 0x7fffffff, est, i;\n         for (filter_type = 0; filter_type < 5; filter_type++) {\n            stbiw__encode_png_line((unsigned char*)(pixels), stride_bytes, x, y, j, n, filter_type, line_buffer);\n\n            // Estimate the entropy of the line using this filter; the less, the better.\n            est = 0;\n            for (i = 0; i < x*n; ++i) {\n               est += abs((signed char) line_buffer[i]);\n            }\n            if (est < best_filter_val) {\n               best_filter_val = est;\n               best_filter = filter_type;\n            }\n         }\n         if (filter_type != best_filter) {  // If the last iteration already got us the best filter, don't redo it\n            stbiw__encode_png_line((unsigned char*)(pixels), stride_bytes, x, y, j, n, best_filter, line_buffer);\n            filter_type = best_filter;\n         }\n      }\n      // when we get here, filter_type contains the filter type, and line_buffer contains the data\n      filt[j*(x*n+1)] = (unsigned char) filter_type;\n      STBIW_MEMMOVE(filt+j*(x*n+1)+1, line_buffer, x*n);\n   }\n   STBIW_FREE(line_buffer);\n   zlib = stbi_zlib_compress(filt, y*( x*n+1), &zlen, stbi_write_png_compression_level);\n   STBIW_FREE(filt);\n   if (!zlib) return 0;\n\n   // each tag requires 12 bytes of overhead\n   out = (unsigned char *) STBIW_MALLOC(8 + 12+13 + 12+zlen + 12);\n   if (!out) return 0;\n   *out_len = 8 + 12+13 + 12+zlen + 12;\n\n   o=out;\n   STBIW_MEMMOVE(o,sig,8); o+= 8;\n   stbiw__wp32(o, 13); // header length\n   stbiw__wptag(o, \"IHDR\");\n   stbiw__wp32(o, x);\n   stbiw__wp32(o, y);\n   *o++ = 8;\n   *o++ = STBIW_UCHAR(ctype[n]);\n   *o++ = 0;\n   *o++ = 0;\n   *o++ = 0;\n   stbiw__wpcrc(&o,13);\n\n   stbiw__wp32(o, zlen);\n   stbiw__wptag(o, \"IDAT\");\n   STBIW_MEMMOVE(o, zlib, zlen);\n   o += zlen;\n   STBIW_FREE(zlib);\n   stbiw__wpcrc(&o, zlen);\n\n   stbiw__wp32(o,0);\n   stbiw__wptag(o, \"IEND\");\n   stbiw__wpcrc(&o,0);\n\n   STBIW_ASSERT(o == out + *out_len);\n\n   return out;\n}\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{\n   FILE *f;\n   int len;\n   unsigned char *png = stbi_write_png_to_mem((const unsigned char *) data, stride_bytes, x, y, comp, &len);\n   if (png == NULL) return 0;\n\n   f = stbiw__fopen(filename, \"wb\");\n   if (!f) { STBIW_FREE(png); return 0; }\n   fwrite(png, 1, len, f);\n   fclose(f);\n   STBIW_FREE(png);\n   return 1;\n}\n#endif\n\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{\n   int len;\n   unsigned char *png = stbi_write_png_to_mem((const unsigned char *) data, stride_bytes, x, y, comp, &len);\n   if (png == NULL) return 0;\n   func(context, png, len);\n   STBIW_FREE(png);\n   return 1;\n}\n\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 */\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,\n      24,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 };\n\nstatic void stbiw__jpg_writeBits(stbi__write_context *s, int *bitBufP, int *bitCntP, const unsigned short *bs) {\n   int bitBuf = *bitBufP, bitCnt = *bitCntP;\n   bitCnt += bs[1];\n   bitBuf |= bs[0] << (24 - bitCnt);\n   while(bitCnt >= 8) {\n      unsigned char c = (bitBuf >> 16) & 255;\n      stbiw__putc(s, c);\n      if(c == 255) {\n         stbiw__putc(s, 0);\n      }\n      bitBuf <<= 8;\n      bitCnt -= 8;\n   }\n   *bitBufP = bitBuf;\n   *bitCntP = bitCnt;\n}\n\nstatic void stbiw__jpg_DCT(float *d0p, float *d1p, float *d2p, float *d3p, float *d4p, float *d5p, float *d6p, float *d7p) {\n   float d0 = *d0p, d1 = *d1p, d2 = *d2p, d3 = *d3p, d4 = *d4p, d5 = *d5p, d6 = *d6p, d7 = *d7p;\n   float z1, z2, z3, z4, z5, z11, z13;\n\n   float tmp0 = d0 + d7;\n   float tmp7 = d0 - d7;\n   float tmp1 = d1 + d6;\n   float tmp6 = d1 - d6;\n   float tmp2 = d2 + d5;\n   float tmp5 = d2 - d5;\n   float tmp3 = d3 + d4;\n   float tmp4 = d3 - d4;\n\n   // Even part\n   float tmp10 = tmp0 + tmp3;   // phase 2\n   float tmp13 = tmp0 - tmp3;\n   float tmp11 = tmp1 + tmp2;\n   float tmp12 = tmp1 - tmp2;\n\n   d0 = tmp10 + tmp11;       // phase 3\n   d4 = tmp10 - tmp11;\n\n   z1 = (tmp12 + tmp13) * 0.707106781f; // c4\n   d2 = tmp13 + z1;       // phase 5\n   d6 = tmp13 - z1;\n\n   // Odd part\n   tmp10 = tmp4 + tmp5;       // phase 2\n   tmp11 = tmp5 + tmp6;\n   tmp12 = tmp6 + tmp7;\n\n   // The rotator is modified from fig 4-8 to avoid extra negations.\n   z5 = (tmp10 - tmp12) * 0.382683433f; // c6\n   z2 = tmp10 * 0.541196100f + z5; // c2-c6\n   z4 = tmp12 * 1.306562965f + z5; // c2+c6\n   z3 = tmp11 * 0.707106781f; // c4\n\n   z11 = tmp7 + z3;      // phase 5\n   z13 = tmp7 - z3;\n\n   *d5p = z13 + z2;         // phase 6\n   *d3p = z13 - z2;\n   *d1p = z11 + z4;\n   *d7p = z11 - z4;\n\n   *d0p = d0;  *d2p = d2;  *d4p = d4;  *d6p = d6;\n}\n\nstatic void stbiw__jpg_calcBits(int val, unsigned short bits[2]) {\n   int tmp1 = val < 0 ? -val : val;\n   val = val < 0 ? val-1 : val;\n   bits[1] = 1;\n   while(tmp1 >>= 1) {\n      ++bits[1];\n   }\n   bits[0] = val & ((1<<bits[1])-1);\n}\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]) {\n   const unsigned short EOB[2] = { HTAC[0x00][0], HTAC[0x00][1] };\n   const unsigned short M16zeroes[2] = { HTAC[0xF0][0], HTAC[0xF0][1] };\n   int dataOff, i, diff, end0pos;\n   int DU[64];\n\n   // DCT rows\n   for(dataOff=0; dataOff<64; dataOff+=8) {\n      stbiw__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\n   for(dataOff=0; dataOff<8; ++dataOff) {\n      stbiw__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\n   for(i=0; i<64; ++i) {\n      float 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?\n      DU[stbiw__jpg_ZigZag[i]] = (int)(v < 0 ? v - 0.5f : v + 0.5f);\n   }\n\n   // Encode DC\n   diff = DU[0] - DC;\n   if (diff == 0) {\n      stbiw__jpg_writeBits(s, bitBuf, bitCnt, HTDC[0]);\n   } else {\n      unsigned short bits[2];\n      stbiw__jpg_calcBits(diff, bits);\n      stbiw__jpg_writeBits(s, bitBuf, bitCnt, HTDC[bits[1]]);\n      stbiw__jpg_writeBits(s, bitBuf, bitCnt, bits);\n   }\n   // Encode ACs\n   end0pos = 63;\n   for(; (end0pos>0)&&(DU[end0pos]==0); --end0pos) {\n   }\n   // end0pos = first element in reverse order !=0\n   if(end0pos == 0) {\n      stbiw__jpg_writeBits(s, bitBuf, bitCnt, EOB);\n      return DU[0];\n   }\n   for(i = 1; i <= end0pos; ++i) {\n      int startpos = i;\n      int nrzeroes;\n      unsigned short bits[2];\n      for (; DU[i]==0 && i<=end0pos; ++i) {\n      }\n      nrzeroes = i-startpos;\n      if ( nrzeroes >= 16 ) {\n         int lng = nrzeroes>>4;\n         int nrmarker;\n         for (nrmarker=1; nrmarker <= lng; ++nrmarker)\n            stbiw__jpg_writeBits(s, bitBuf, bitCnt, M16zeroes);\n         nrzeroes &= 15;\n      }\n      stbiw__jpg_calcBits(DU[i], bits);\n      stbiw__jpg_writeBits(s, bitBuf, bitCnt, HTAC[(nrzeroes<<4)+bits[1]]);\n      stbiw__jpg_writeBits(s, bitBuf, bitCnt, bits);\n   }\n   if(end0pos != 63) {\n      stbiw__jpg_writeBits(s, bitBuf, bitCnt, EOB);\n   }\n   return DU[0];\n}\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\n   static const unsigned char std_dc_luminance_nrcodes[] = {0,0,1,5,1,1,1,1,1,1,0,0,0,0,0,0,0};\n   static const unsigned char std_dc_luminance_values[] = {0,1,2,3,4,5,6,7,8,9,10,11};\n   static const unsigned char std_ac_luminance_nrcodes[] = {0,0,2,1,3,3,2,4,3,5,5,4,4,0,0,1,0x7d};\n   static const unsigned char std_ac_luminance_values[] = {\n      0x01,0x02,0x03,0x00,0x04,0x11,0x05,0x12,0x21,0x31,0x41,0x06,0x13,0x51,0x61,0x07,0x22,0x71,0x14,0x32,0x81,0x91,0xa1,0x08,\n      0x23,0x42,0xb1,0xc1,0x15,0x52,0xd1,0xf0,0x24,0x33,0x62,0x72,0x82,0x09,0x0a,0x16,0x17,0x18,0x19,0x1a,0x25,0x26,0x27,0x28,\n      0x29,0x2a,0x34,0x35,0x36,0x37,0x38,0x39,0x3a,0x43,0x44,0x45,0x46,0x47,0x48,0x49,0x4a,0x53,0x54,0x55,0x56,0x57,0x58,0x59,\n      0x5a,0x63,0x64,0x65,0x66,0x67,0x68,0x69,0x6a,0x73,0x74,0x75,0x76,0x77,0x78,0x79,0x7a,0x83,0x84,0x85,0x86,0x87,0x88,0x89,\n      0x8a,0x92,0x93,0x94,0x95,0x96,0x97,0x98,0x99,0x9a,0xa2,0xa3,0xa4,0xa5,0xa6,0xa7,0xa8,0xa9,0xaa,0xb2,0xb3,0xb4,0xb5,0xb6,\n      0xb7,0xb8,0xb9,0xba,0xc2,0xc3,0xc4,0xc5,0xc6,0xc7,0xc8,0xc9,0xca,0xd2,0xd3,0xd4,0xd5,0xd6,0xd7,0xd8,0xd9,0xda,0xe1,0xe2,\n      0xe3,0xe4,0xe5,0xe6,0xe7,0xe8,0xe9,0xea,0xf1,0xf2,0xf3,0xf4,0xf5,0xf6,0xf7,0xf8,0xf9,0xfa\n   };\n   static const unsigned char std_dc_chrominance_nrcodes[] = {0,0,3,1,1,1,1,1,1,1,1,1,0,0,0,0,0};\n   static const unsigned char std_dc_chrominance_values[] = {0,1,2,3,4,5,6,7,8,9,10,11};\n   static const unsigned char std_ac_chrominance_nrcodes[] = {0,0,2,1,2,4,4,3,4,7,5,4,4,0,1,2,0x77};\n   static const unsigned char std_ac_chrominance_values[] = {\n      0x00,0x01,0x02,0x03,0x11,0x04,0x05,0x21,0x31,0x06,0x12,0x41,0x51,0x07,0x61,0x71,0x13,0x22,0x32,0x81,0x08,0x14,0x42,0x91,\n      0xa1,0xb1,0xc1,0x09,0x23,0x33,0x52,0xf0,0x15,0x62,0x72,0xd1,0x0a,0x16,0x24,0x34,0xe1,0x25,0xf1,0x17,0x18,0x19,0x1a,0x26,\n      0x27,0x28,0x29,0x2a,0x35,0x36,0x37,0x38,0x39,0x3a,0x43,0x44,0x45,0x46,0x47,0x48,0x49,0x4a,0x53,0x54,0x55,0x56,0x57,0x58,\n      0x59,0x5a,0x63,0x64,0x65,0x66,0x67,0x68,0x69,0x6a,0x73,0x74,0x75,0x76,0x77,0x78,0x79,0x7a,0x82,0x83,0x84,0x85,0x86,0x87,\n      0x88,0x89,0x8a,0x92,0x93,0x94,0x95,0x96,0x97,0x98,0x99,0x9a,0xa2,0xa3,0xa4,0xa5,0xa6,0xa7,0xa8,0xa9,0xaa,0xb2,0xb3,0xb4,\n      0xb5,0xb6,0xb7,0xb8,0xb9,0xba,0xc2,0xc3,0xc4,0xc5,0xc6,0xc7,0xc8,0xc9,0xca,0xd2,0xd3,0xd4,0xd5,0xd6,0xd7,0xd8,0xd9,0xda,\n      0xe2,0xe3,0xe4,0xe5,0xe6,0xe7,0xe8,0xe9,0xea,0xf2,0xf3,0xf4,0xf5,0xf6,0xf7,0xf8,0xf9,0xfa\n   };\n   // Huffman tables\n   static 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}};\n   static 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}};\n   static 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   };\n   static 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   };\n   static 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,\n                             37,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};\n   static 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,\n                              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,99};\n   static const float aasf[] = { 1.0f * 2.828427125f, 1.387039845f * 2.828427125f, 1.306562965f * 2.828427125f, 1.175875602f * 2.828427125f, \n                                 1.0f * 2.828427125f, 0.785694958f * 2.828427125f, 0.541196100f * 2.828427125f, 0.275899379f * 2.828427125f };\n\n   int row, col, i, k;\n   float fdtbl_Y[64], fdtbl_UV[64];\n   unsigned char YTable[64], UVTable[64];\n\n   if(!data || !width || !height || comp > 4 || comp < 1) {\n      return 0;\n   }\n\n   quality = quality ? quality : 90;\n   quality = quality < 1 ? 1 : quality > 100 ? 100 : quality;\n   quality = quality < 50 ? 5000 / quality : 200 - quality * 2;\n\n   for(i = 0; i < 64; ++i) {\n      int uvti, yti = (YQT[i]*quality+50)/100;\n      YTable[stbiw__jpg_ZigZag[i]] = (unsigned char) (yti < 1 ? 1 : yti > 255 ? 255 : yti);\n      uvti = (UVQT[i]*quality+50)/100;\n      UVTable[stbiw__jpg_ZigZag[i]] = (unsigned char) (uvti < 1 ? 1 : uvti > 255 ? 255 : uvti);\n   }\n\n   for(row = 0, k = 0; row < 8; ++row) {\n      for(col = 0; col < 8; ++col, ++k) {\n         fdtbl_Y[k]  = 1 / (YTable [stbiw__jpg_ZigZag[k]] * aasf[row] * aasf[col]);\n         fdtbl_UV[k] = 1 / (UVTable[stbiw__jpg_ZigZag[k]] * aasf[row] * aasf[col]);\n      }\n   }\n\n   // Write Headers\n   {\n      static 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 };\n      static const unsigned char head2[] = { 0xFF,0xDA,0,0xC,3,1,0,2,0x11,3,0x11,0,0x3F,0 };\n      const unsigned char head1[] = { 0xFF,0xC0,0,0x11,8,(unsigned char)(height>>8),STBIW_UCHAR(height),(unsigned char)(width>>8),STBIW_UCHAR(width),\n                                      3,1,0x11,0,2,0x11,1,3,0x11,1,0xFF,0xC4,0x01,0xA2,0 };\n      s->func(s->context, (void*)head0, sizeof(head0));\n      s->func(s->context, (void*)YTable, sizeof(YTable));\n      stbiw__putc(s, 1);\n      s->func(s->context, UVTable, sizeof(UVTable));\n      s->func(s->context, (void*)head1, sizeof(head1));\n      s->func(s->context, (void*)(std_dc_luminance_nrcodes+1), sizeof(std_dc_luminance_nrcodes)-1);\n      s->func(s->context, (void*)std_dc_luminance_values, sizeof(std_dc_luminance_values));\n      stbiw__putc(s, 0x10); // HTYACinfo\n      s->func(s->context, (void*)(std_ac_luminance_nrcodes+1), sizeof(std_ac_luminance_nrcodes)-1);\n      s->func(s->context, (void*)std_ac_luminance_values, sizeof(std_ac_luminance_values));\n      stbiw__putc(s, 1); // HTUDCinfo\n      s->func(s->context, (void*)(std_dc_chrominance_nrcodes+1), sizeof(std_dc_chrominance_nrcodes)-1);\n      s->func(s->context, (void*)std_dc_chrominance_values, sizeof(std_dc_chrominance_values));\n      stbiw__putc(s, 0x11); // HTUACinfo\n      s->func(s->context, (void*)(std_ac_chrominance_nrcodes+1), sizeof(std_ac_chrominance_nrcodes)-1);\n      s->func(s->context, (void*)std_ac_chrominance_values, sizeof(std_ac_chrominance_values));\n      s->func(s->context, (void*)head2, sizeof(head2));\n   }\n\n   // Encode 8x8 macroblocks\n   {\n      static const unsigned short fillBits[] = {0x7F, 7};\n      const unsigned char *imageData = (const unsigned char *)data;\n      int DCY=0, DCU=0, DCV=0;\n      int bitBuf=0, bitCnt=0;\n      // comp == 2 is grey+alpha (alpha is ignored)\n      int ofsG = comp > 2 ? 1 : 0, ofsB = comp > 2 ? 2 : 0;\n      int x, y, pos;\n      for(y = 0; y < height; y += 8) {\n         for(x = 0; x < width; x += 8) {\n            float YDU[64], UDU[64], VDU[64];\n            for(row = y, pos = 0; row < y+8; ++row) {\n               // row >= height => use last input row\n               int clamped_row = (row < height) ? row : height - 1;\n               int base_p = (stbi__flip_vertically_on_write ? (height-1-clamped_row) : clamped_row)*width*comp;\n               for(col = x; col < x+8; ++col, ++pos) {\n                  float r, g, b;\n                  // if col >= width => use pixel from last input column\n                  int p = base_p + ((col < width) ? col : (width-1))*comp;\n\n                  r = imageData[p+0];\n                  g = imageData[p+ofsG];\n                  b = imageData[p+ofsB];\n                  YDU[pos]=+0.29900f*r+0.58700f*g+0.11400f*b-128;\n                  UDU[pos]=-0.16874f*r-0.33126f*g+0.50000f*b;\n                  VDU[pos]=+0.50000f*r-0.41869f*g-0.08131f*b;\n               }\n            }\n\n            DCY = stbiw__jpg_processDU(s, &bitBuf, &bitCnt, YDU, fdtbl_Y, DCY, YDC_HT, YAC_HT);\n            DCU = stbiw__jpg_processDU(s, &bitBuf, &bitCnt, UDU, fdtbl_UV, DCU, UVDC_HT, UVAC_HT);\n            DCV = stbiw__jpg_processDU(s, &bitBuf, &bitCnt, VDU, fdtbl_UV, DCV, UVDC_HT, UVAC_HT);\n         }\n      }\n\n      // Do the bit alignment of the EOI marker\n      stbiw__jpg_writeBits(s, &bitBuf, &bitCnt, fillBits);\n   }\n\n   // EOI\n   stbiw__putc(s, 0xFF);\n   stbiw__putc(s, 0xD9);\n\n   return 1;\n}\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{\n   stbi__write_context s;\n   stbi__start_write_callbacks(&s, func, context);\n   return stbi_write_jpg_core(&s, x, y, comp, (void *) data, quality);\n}\n\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{\n   stbi__write_context s;\n   if (stbi__start_write_file(&s,filename)) {\n      int r = stbi_write_jpg_core(&s, x, y, comp, data, quality);\n      stbi__end_write_file(&s);\n      return r;\n   } else\n      return 0;\n}\n#endif\n\n#endif // STB_IMAGE_WRITE_IMPLEMENTATION\n\n/* Revision history\n      1.11  (2019-08-11)\n\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/*\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

  • #include \"robot_dart/robots/a1.hpp\"
  • #include \"robot_dart/robot_dart_simu.hpp\"
"},{"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\"\n\nnamespace robot_dart {\n    namespace robots {\n        A1::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        {\n            set_color_mode(\"material\");\n            set_self_collision(true);\n            set_position_enforced(true);\n\n            // put above ground\n            set_base_pose(robot_dart::make_vector({0., 0., 0., 0., 0., 0.5}));\n\n            // standing pose\n            auto names = dof_names(true, true, true);\n            names = std::vector<std::string>(names.begin() + 6, names.end());\n            set_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\n        void A1::reset()\n        {\n            Robot::reset();\n\n            // put above ground\n            set_base_pose(robot_dart::make_vector({0., 0., 0., 0., 0., 0.5}));\n\n            // standing pose\n            auto names = dof_names(true, true, true);\n            names = std::vector<std::string>(names.begin() + 6, names.end());\n            set_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

  • #include \"robot_dart/robot.hpp\"
  • #include \"robot_dart/sensor/imu.hpp\"
"},{"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\n#include \"robot_dart/robot.hpp\"\n#include \"robot_dart/sensor/imu.hpp\"\n\nnamespace robot_dart {\n    namespace robots {\n        class A1 : public Robot {\n        public:\n            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'));\n\n            void reset() override;\n\n            const sensor::IMU& imu() const { return *_imu; }\n\n        protected:\n            std::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

  • #include \"robot_dart/robot.hpp\"
"},{"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\n#include \"robot_dart/robot.hpp\"\n\nnamespace robot_dart {\n    namespace robots {\n        class Arm : public Robot {\n        public:\n            Arm(const std::string& urdf = \"arm.urdf\") : Robot(urdf)\n            {\n                fix_to_world();\n                set_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

  • #include \"robot_dart/robots/franka.hpp\"
  • #include \"robot_dart/robot_dart_simu.hpp\"
"},{"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\"\n\nnamespace robot_dart {\n    namespace robots {\n        Franka::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        {\n            fix_to_world();\n            set_position_enforced(true);\n            set_color_mode(\"material\");\n        }\n\n        void Franka::_post_addition(RobotDARTSimu* simu)\n        {\n            // We do not want to add sensors if we are a ghost robot\n            if (ghost())\n                return;\n            simu->add_sensor(_ft_wrist);\n        }\n\n        void Franka::_post_removal(RobotDARTSimu* simu)\n        {\n            simu->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

  • #include \"robot_dart/robot.hpp\"
  • #include \"robot_dart/sensor/force_torque.hpp\"
"},{"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\n#include \"robot_dart/robot.hpp\"\n#include \"robot_dart/sensor/force_torque.hpp\"\n\nnamespace robot_dart {\n    namespace robots {\n        class Franka : public Robot {\n        public:\n            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'));\n\n            const sensor::ForceTorque& ft_wrist() const { return *_ft_wrist; }\n\n        protected:\n            std::shared_ptr<sensor::ForceTorque> _ft_wrist;\n            void _post_addition(RobotDARTSimu* simu) override;\n            void _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

  • #include \"robot_dart/robot.hpp\"
"},{"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\n#include \"robot_dart/robot.hpp\"\n\nnamespace robot_dart {\n    namespace robots {\n        class Hexapod : public Robot {\n        public:\n            Hexapod(const std::string& urdf = \"pexod.urdf\") : Robot(urdf)\n            {\n                set_position_enforced(true);\n                skeleton()->enableSelfCollisionCheck();\n                set_base_pose(robot_dart::make_vector({0., 0., 0., 0., 0., 0.2}));\n            }\n\n            void reset() override\n            {\n                Robot::reset();\n                set_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

  • #include \"robot_dart/robots/icub.hpp\"
  • #include \"robot_dart/robot_dart_simu.hpp\"
"},{"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\"\n\nnamespace robot_dart {\n    namespace robots {\n        ICub::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        {\n            set_color_mode(\"material\");\n\n            set_position_enforced(true);\n\n            // position iCub\n            set_base_pose(robot_dart::make_vector({0., 0., M_PI / 2., 0., 0., 0.46}));\n        }\n\n        void ICub::reset()\n        {\n            Robot::reset();\n\n            // position iCub\n            set_base_pose(robot_dart::make_vector({0., 0., M_PI / 2., 0., 0., 0.46}));\n        }\n\n        void ICub::_post_addition(RobotDARTSimu* simu)\n        {\n            // We do not want to add sensors if we are a ghost robot\n            if (ghost())\n                return;\n            simu->add_sensor(_imu);\n            simu->add_sensor(_ft_foot_left);\n            simu->add_sensor(_ft_foot_right);\n        }\n\n        void ICub::_post_removal(RobotDARTSimu* simu)\n        {\n            simu->remove_sensor(_imu);\n            simu->remove_sensor(_ft_foot_left);\n            simu->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

  • #include \"robot_dart/robot.hpp\"
  • #include \"robot_dart/sensor/force_torque.hpp\"
  • #include \"robot_dart/sensor/imu.hpp\"
"},{"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\n#include \"robot_dart/robot.hpp\"\n#include \"robot_dart/sensor/force_torque.hpp\"\n#include \"robot_dart/sensor/imu.hpp\"\n\nnamespace robot_dart {\n    namespace robots {\n        class ICub : public Robot {\n        public:\n            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'));\n\n            void reset() override;\n\n            const sensor::IMU& imu() const { return *_imu; }\n            const sensor::ForceTorque& ft_foot_left() const { return *_ft_foot_left; }\n            const sensor::ForceTorque& ft_foot_right() const { return *_ft_foot_right; }\n\n        protected:\n            std::shared_ptr<sensor::IMU> _imu;\n            std::shared_ptr<sensor::ForceTorque> _ft_foot_left;\n            std::shared_ptr<sensor::ForceTorque> _ft_foot_right;\n\n            void _post_addition(RobotDARTSimu* simu) override;\n            void _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

  • #include \"robot_dart/robots/iiwa.hpp\"
  • #include \"robot_dart/robot_dart_simu.hpp\"
"},{"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\"\n\nnamespace robot_dart {\n    namespace robots {\n        Iiwa::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        {\n            fix_to_world();\n            set_position_enforced(true);\n        }\n\n        void Iiwa::_post_addition(RobotDARTSimu* simu)\n        {\n            // We do not want to add sensors if we are a ghost robot\n            if (ghost())\n                return;\n            simu->add_sensor(_ft_wrist);\n        }\n\n        void Iiwa::_post_removal(RobotDARTSimu* simu)\n        {\n            simu->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

  • #include \"robot_dart/robot.hpp\"
  • #include \"robot_dart/sensor/force_torque.hpp\"
"},{"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\n#include \"robot_dart/robot.hpp\"\n#include \"robot_dart/sensor/force_torque.hpp\"\n\nnamespace robot_dart {\n    namespace robots {\n        class Iiwa : public Robot {\n        public:\n            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'));\n\n            const sensor::ForceTorque& ft_wrist() const { return *_ft_wrist; }\n\n        protected:\n            std::shared_ptr<sensor::ForceTorque> _ft_wrist;\n            void _post_addition(RobotDARTSimu* simu) override;\n            void _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

  • #include \"robot_dart/robot.hpp\"
"},{"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\n#include \"robot_dart/robot.hpp\"\n\nnamespace robot_dart {\n    namespace robots {\n        class Pendulum : public Robot {\n        public:\n            Pendulum(const std::string& urdf = \"pendulum.urdf\") : Robot(urdf)\n            {\n                fix_to_world();\n                set_position_enforced(true);\n                set_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

  • #include \"robot_dart/robots/talos.hpp\"
  • #include \"robot_dart/robot_dart_simu.hpp\"
"},{"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\"\n\nnamespace robot_dart {\n    namespace robots {\n        Talos::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\n            set_position_enforced(true);\n\n            // position Talos\n            set_base_pose(robot_dart::make_vector({0., 0., M_PI / 2., 0., 0., 1.1}));\n        }\n\n        void Talos::reset()\n        {\n            Robot::reset();\n\n            // position Talos\n            set_base_pose(robot_dart::make_vector({0., 0., M_PI / 2., 0., 0., 1.1}));\n        }\n\n        void Talos::_post_addition(RobotDARTSimu* simu)\n        {\n            // We do not want to add sensors if we are a ghost robot\n            if (ghost())\n                return;\n            simu->add_sensor(_imu);\n\n            simu->add_sensor(_ft_foot_left);\n            simu->add_sensor(_ft_foot_right);\n            simu->add_sensor(_ft_wrist_left);\n            simu->add_sensor(_ft_wrist_right);\n\n            // torques sensors\n            std::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\n            };\n            for (auto& s : joints) {\n                auto t = std::make_shared<sensor::Torque>(joint(s), _frequency);\n                _torques[s] = t;\n                simu->add_sensor(t);\n            }\n        }\n\n        void Talos::_post_removal(RobotDARTSimu* simu)\n        {\n            simu->remove_sensor(_imu);\n\n            simu->remove_sensor(_ft_foot_left);\n            simu->remove_sensor(_ft_foot_right);\n            simu->remove_sensor(_ft_wrist_left);\n            simu->remove_sensor(_ft_wrist_right);\n\n            for (auto& t : _torques) {\n                simu->remove_sensor(t.second);\n            }\n        }\n\n        void TalosFastCollision::_post_addition(RobotDARTSimu* simu)\n        {\n            Talos::_post_addition(simu);\n            auto vec = TalosFastCollision::collision_vec();\n            for (auto& t : vec) {\n                simu->set_collision_masks(simu->robots().size() - 1, std::get<0>(t), std::get<1>(t), std::get<2>(t));\n            }\n        }\n\n        std::vector<std::tuple<std::string, uint32_t, uint32_t>> TalosFastCollision::collision_vec()\n        {\n            std::vector<std::tuple<std::string, uint32_t, uint32_t>> vec;\n            vec.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));\n            vec.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));\n            vec.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));\n            vec.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));\n            vec.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));\n            vec.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));\n            vec.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));\n            vec.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));\n            vec.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));\n            vec.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));\n            vec.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));\n            vec.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));\n            vec.push_back(std::make_tuple(\"torso_2_link\", 0x1000, 0x1 | 0x2 | 0x4 | 0x8 | 0x10 | 0x20 | 0x40 | 0x80 | 0x100 | 0x200 | 0x800 | 0x1000 | 0x4000 | 0x8000));\n            vec.push_back(std::make_tuple(\"base_link\", 0x2000, 0x1 | 0x2 | 0x4 | 0x8 | 0x10 | 0x20 | 0x40 | 0x80 | 0x100 | 0x200 | 0x800 | 0x2000 | 0x10000));\n            vec.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));\n            vec.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));\n            vec.push_back(std::make_tuple(\"head_2_link\", 0x10000, 0x1 | 0x2 | 0x4 | 0x8 | 0x10 | 0x20 | 0x40 | 0x80 | 0x100 | 0x200 | 0x800 | 0x2000 | 0x4000 | 0x8000 | 0x10000));\n            return 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

  • #include \"robot_dart/robot.hpp\"
  • #include \"robot_dart/sensor/force_torque.hpp\"
  • #include \"robot_dart/sensor/imu.hpp\"
  • #include \"robot_dart/sensor/torque.hpp\"
"},{"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\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\"\n\nnamespace robot_dart {\n    namespace robots {\n        class Talos : public Robot {\n        public:\n            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'));\n\n            void reset() override;\n\n            const sensor::IMU& imu() const { return *_imu; }\n            const sensor::ForceTorque& ft_foot_left() const { return *_ft_foot_left; }\n            const sensor::ForceTorque& ft_foot_right() const { return *_ft_foot_right; }\n            const sensor::ForceTorque& ft_wrist_left() const { return *_ft_wrist_left; }\n            const sensor::ForceTorque& ft_wrist_right() const { return *_ft_wrist_right; }\n\n            using torque_map_t = std::unordered_map<std::string, std::shared_ptr<sensor::Torque>>;\n            const torque_map_t& torques() const { return _torques; }\n\n        protected:\n            std::shared_ptr<sensor::IMU> _imu;\n            std::shared_ptr<sensor::ForceTorque> _ft_foot_left;\n            std::shared_ptr<sensor::ForceTorque> _ft_foot_right;\n            std::shared_ptr<sensor::ForceTorque> _ft_wrist_left;\n            std::shared_ptr<sensor::ForceTorque> _ft_wrist_right;\n            torque_map_t _torques;\n            size_t _frequency;\n\n            void _post_addition(RobotDARTSimu* simu) override;\n            void _post_removal(RobotDARTSimu* simu) override;\n        };\n\n        class TalosLight : public Talos {\n        public:\n            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')) : Talos(frequency, urdf, packages) {}\n        };\n\n        // for talos_fast_collision.urdf or talos_box.urdf which have simple box collision shapes\n        class TalosFastCollision : public Talos {\n        public:\n            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')) : Talos(frequency, urdf, packages) { set_self_collision(); }\n            static std::vector<std::tuple<std::string, uint32_t, uint32_t>> collision_vec();\n\n        protected:\n            void _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

  • #include \"robot_dart/robots/tiago.hpp\"
  • #include \"robot_dart/robot_dart_simu.hpp\"
"},{"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\"\n\nnamespace robot_dart {\n    namespace robots {\n        Tiago::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        {\n            set_position_enforced(true);\n            // We use servo actuators, but not for the caster joints\n            set_actuator_types(\"servo\");\n\n            // position Tiago\n            set_base_pose(robot_dart::make_vector({0., 0., M_PI / 2., 0., 0., 0.}));\n        }\n\n        void Tiago::reset()\n        {\n            Robot::reset();\n\n            // position Tiago\n            set_base_pose(robot_dart::make_vector({0., 0., M_PI / 2., 0., 0., 0.}));\n        }\n\n        void 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        {\n            auto jt = joint_names;\n            if (!override_caster) {\n                if (joint_names.size() == 0)\n                    jt = Robot::joint_names();\n                for (const auto& jnt : caster_joints()) {\n                    auto it = std::find(jt.begin(), jt.end(), jnt);\n                    if (it != jt.end()) {\n                        jt.erase(it);\n                    }\n                }\n            }\n            Robot::set_actuator_types(type, jt, override_mimic, override_base);\n        }\n\n        void Tiago::set_actuator_type(const std::string& type, const std::string& joint_name, bool override_mimic, bool override_base, bool override_caster)\n        {\n            set_actuator_types(type, {joint_name}, override_mimic, override_base, override_caster);\n        }\n\n        void Tiago::_post_addition(RobotDARTSimu* simu)\n        {\n            // We do not want to add sensors if we are a ghost robot\n            if (ghost())\n                return;\n            simu->add_sensor(_ft_wrist);\n        }\n\n        void Tiago::_post_removal(RobotDARTSimu* simu)\n        {\n            simu->remove_sensor(_ft_wrist);\n        }\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

  • #include \"robot_dart/robot.hpp\"
  • #include \"robot_dart/sensor/force_torque.hpp\"
"},{"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\n#include \"robot_dart/robot.hpp\"\n#include \"robot_dart/sensor/force_torque.hpp\"\n\nnamespace robot_dart {\n    namespace robots {\n        class Tiago : public Robot {\n        public:\n            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'));\n\n            void reset() override;\n\n            const sensor::ForceTorque& ft_wrist() const { return *_ft_wrist; }\n\n            std::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\"}; }\n\n            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);\n            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);\n\n        protected:\n            std::shared_ptr<sensor::ForceTorque> _ft_wrist;\n            void _post_addition(RobotDARTSimu* simu) override;\n            void _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

  • #include \"robot_dart/robots/ur3e.hpp\"
  • #include \"robot_dart/robot_dart_simu.hpp\"
"},{"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\"\n\nnamespace robot_dart {\n    namespace robots {\n        Ur3e::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        {\n            fix_to_world();\n            set_position_enforced(true);\n            set_color_mode(\"material\");\n        }\n\n        void Ur3e::_post_addition(RobotDARTSimu* simu)\n        {\n            // We do not want to add sensors if we are a ghost robot\n            if (ghost())\n                return;\n            simu->add_sensor(_ft_wrist);\n        }\n\n        void Ur3e::_post_removal(RobotDARTSimu* simu)\n        {\n            simu->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

  • #include \"robot_dart/robot.hpp\"
  • #include \"robot_dart/sensor/force_torque.hpp\"
"},{"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\n#include \"robot_dart/robot.hpp\"\n#include \"robot_dart/sensor/force_torque.hpp\"\n\nnamespace robot_dart {\n    namespace robots {\n        class Ur3e : public Robot {\n        public:\n            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'));\n\n            const sensor::ForceTorque& ft_wrist() const { return *_ft_wrist; }\n\n        protected:\n            std::shared_ptr<sensor::ForceTorque> _ft_wrist;\n            void _post_addition(RobotDARTSimu* simu) override;\n            void _post_removal(RobotDARTSimu* simu) override;\n        };\n\n        class Ur3eHand : public Ur3e {\n        public:\n            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')) : 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

  • #include \"robot_dart/robot.hpp\"
"},{"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\n#include \"robot_dart/robot.hpp\"\n\nnamespace robot_dart {\n    namespace robots {\n        class Vx300 : public Robot {\n        public:\n            Vx300(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            {\n                fix_to_world();\n                set_position_enforced(true);\n                set_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

  • #include \"force_torque.hpp\"
  • #include <robot_dart/utils_headers_dart_dynamics.hpp>
"},{"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\n#include <robot_dart/utils_headers_dart_dynamics.hpp>\n\nnamespace robot_dart {\n    namespace sensor {\n        ForceTorque::ForceTorque(dart::dynamics::Joint* joint, size_t frequency, const std::string& direction) : Sensor(frequency), _direction(direction)\n        {\n            attach_to_joint(joint, Eigen::Isometry3d::Identity());\n        }\n\n        void ForceTorque::init()\n        {\n            _wrench.setZero();\n\n            attach_to_joint(_joint_attached, Eigen::Isometry3d::Identity());\n            _active = true;\n        }\n\n        void ForceTorque::calculate(double)\n        {\n            if (!_attached_to_joint)\n                return; // cannot compute anything if not attached to a joint\n\n            Eigen::Vector6d wrench = Eigen::Vector6d::Zero();\n            auto child_body = _joint_attached->getChildBodyNode();\n            ROBOT_DART_ASSERT(child_body != nullptr, \"Child BodyNode is nullptr\", );\n\n            wrench = -dart::math::dAdT(_joint_attached->getTransformFromChildBodyNode(), child_body->getBodyForce());\n\n            // We always compute things in SENSOR frame (aka joint frame)\n            if (_direction == \"parent_to_child\") {\n                _wrench = wrench;\n            }\n            else // \"child_to_parent\" (default)\n            {\n                _wrench = -wrench;\n            }\n        }\n\n        std::string ForceTorque::type() const { return \"ft\"; }\n\n        Eigen::Vector3d ForceTorque::force() const\n        {\n            return _wrench.tail(3);\n        }\n\n        Eigen::Vector3d ForceTorque::torque() const\n        {\n            return _wrench.head(3);\n        }\n\n        const Eigen::Vector6d& ForceTorque::wrench() const\n        {\n            return _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

  • #include <robot_dart/sensor/sensor.hpp>
"},{"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\n#include <robot_dart/sensor/sensor.hpp>\n\nnamespace robot_dart {\n    namespace sensor {\n        class ForceTorque : public Sensor {\n        public:\n            ForceTorque(dart::dynamics::Joint* joint, size_t frequency = 1000, const std::string& direction = \"child_to_parent\");\n            ForceTorque(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) {}\n\n            void init() override;\n\n            void calculate(double) override;\n\n            std::string type() const override;\n\n            Eigen::Vector3d force() const;\n            Eigen::Vector3d torque() const;\n            const Eigen::Vector6d& wrench() const;\n\n            void attach_to_body(dart::dynamics::BodyNode*, const Eigen::Isometry3d&) override\n            {\n                ROBOT_DART_WARNING(true, \"You cannot attach a force/torque sensor to a body!\");\n            }\n\n        protected:\n            std::string _direction;\n\n            Eigen::Vector6d _wrench;\n        };\n    } // namespace sensor\n} // namespace robot_dart\n\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

  • #include \"imu.hpp\"
  • #include <robot_dart/robot_dart_simu.hpp>
  • #include <robot_dart/utils_headers_dart_dynamics.hpp>
"},{"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\n#include <robot_dart/robot_dart_simu.hpp>\n#include <robot_dart/utils_headers_dart_dynamics.hpp>\n\nnamespace robot_dart {\n    namespace sensor {\n        IMU::IMU(const IMUConfig& config) : Sensor(config.frequency), _config(config) {}\n\n        void IMU::init()\n        {\n            _angular_vel.setZero();\n            _linear_accel.setZero();\n\n            attach_to_body(_config.body, Eigen::Isometry3d::Identity());\n            if (_simu)\n                _active = true;\n        }\n\n        void IMU::calculate(double)\n        {\n            if (!_attached_to_body)\n                return; // cannot compute anything if not attached to a link\n            ROBOT_DART_EXCEPTION_ASSERT(_simu, \"Simulation pointer is null!\");\n\n            Eigen::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\n            // add biases\n            _angular_vel += _config.gyro_bias;\n            _linear_accel += _config.accel_bias;\n\n            // add gravity to acceleration\n            _linear_accel -= _world_pose.linear().transpose() * _simu->gravity();\n        }\n\n        std::string IMU::type() const { return \"imu\"; }\n\n        const Eigen::AngleAxisd& IMU::angular_position() const\n        {\n            return _angular_pos;\n        }\n\n        Eigen::Vector3d IMU::angular_position_vec() const\n        {\n            return _angular_pos.angle() * _angular_pos.axis();\n        }\n\n        const Eigen::Vector3d& IMU::angular_velocity() const\n        {\n            return _angular_vel;\n        }\n\n        const Eigen::Vector3d& IMU::linear_acceleration() const\n        {\n            return _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

  • #include <robot_dart/sensor/sensor.hpp>
"},{"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\n#include <robot_dart/sensor/sensor.hpp>\n\nnamespace robot_dart {\n    namespace sensor {\n        // TO-DO: Implement some noise models (e.g., https://github.com/ethz-asl/kalibr/wiki/IMU-Noise-Model)\n        struct IMUConfig {\n            IMUConfig(dart::dynamics::BodyNode* b, size_t f) : gyro_bias(Eigen::Vector3d::Zero()), accel_bias(Eigen::Vector3d::Zero()), body(b), frequency(f){};\n            IMUConfig(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){};\n            IMUConfig() : gyro_bias(Eigen::Vector3d::Zero()), accel_bias(Eigen::Vector3d::Zero()), body(nullptr), frequency(200) {}\n\n            // We assume fixed bias; TO-DO: Make this time-dependent\n            Eigen::Vector3d gyro_bias = Eigen::Vector3d::Zero();\n            Eigen::Vector3d accel_bias = Eigen::Vector3d::Zero();\n\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\n            // BodyNode/Link attached to\n            dart::dynamics::BodyNode* body = nullptr;\n            // Eigen::Isometry3d _tf = Eigen::Isometry3d::Identity();\n\n            // Frequency\n            size_t frequency = 200;\n        };\n\n        class IMU : public Sensor {\n        public:\n            IMU(const IMUConfig& config);\n\n            void init() override;\n\n            void calculate(double) override;\n\n            std::string type() const override;\n\n            const Eigen::AngleAxisd& angular_position() const;\n            Eigen::Vector3d angular_position_vec() const;\n            const Eigen::Vector3d& angular_velocity() const;\n            const Eigen::Vector3d& linear_acceleration() const;\n\n            void attach_to_joint(dart::dynamics::Joint*, const Eigen::Isometry3d&) override\n            {\n                ROBOT_DART_WARNING(true, \"You cannot attach an IMU sensor to a joint!\");\n            }\n\n        protected:\n            // double _prev_time = 0.;\n            IMUConfig _config;\n\n            Eigen::AngleAxisd _angular_pos; // TO-DO: Check how to do this as close as possible to real sensors\n            Eigen::Vector3d _angular_vel;\n            Eigen::Vector3d _linear_accel;\n        };\n    } // namespace sensor\n} // namespace robot_dart\n\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

  • #include \"sensor.hpp\"
  • #include \"robot_dart/robot_dart_simu.hpp\"
  • #include \"robot_dart/utils.hpp\"
  • #include \"robot_dart/utils_headers_dart_dynamics.hpp\"
"},{"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\"\n\nnamespace robot_dart {\n    namespace sensor {\n        Sensor::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) {}\n\n        void Sensor::activate(bool enable)\n        {\n            _active = false;\n            if (enable) {\n                init();\n            }\n        }\n\n        bool Sensor::active() const\n        {\n            return _active;\n        }\n\n        void Sensor::set_simu(RobotDARTSimu* simu)\n        {\n            ROBOT_DART_EXCEPTION_ASSERT(simu, \"Simulation pointer is null!\");\n            _simu = simu;\n            bool check = static_cast<int>(_frequency) > simu->physics_freq();\n            ROBOT_DART_WARNING(check, \"Sensor frequency is bigger than simulation physics. Setting it to simulation rate!\");\n            if (check)\n                _frequency = simu->physics_freq();\n        }\n\n        const RobotDARTSimu* Sensor::simu() const\n        {\n            return _simu;\n        }\n\n        size_t Sensor::frequency() const { return _frequency; }\n        void Sensor::set_frequency(size_t freq) { _frequency = freq; }\n\n        void Sensor::set_pose(const Eigen::Isometry3d& tf) { _world_pose = tf; }\n        const Eigen::Isometry3d& Sensor::pose() const { return _world_pose; }\n\n        void 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        }\n\n        void Sensor::refresh(double t)\n        {\n            if (!_active)\n                return;\n            if (_attaching_to_body && !_attached_to_body) {\n                attach_to_body(_body_attached, _attached_tf);\n            }\n            else if (_attaching_to_joint && !_attached_to_joint) {\n                attach_to_joint(_joint_attached, _attached_tf);\n            }\n\n            if (_attached_to_body && _body_attached) {\n                _world_pose = _body_attached->getWorldTransform() * _attached_tf;\n            }\n            else if (_attached_to_joint && _joint_attached) {\n                dart::dynamics::BodyNode* body = nullptr;\n                Eigen::Isometry3d tf = Eigen::Isometry3d::Identity();\n\n                if (_joint_attached->getParentBodyNode()) {\n                    body = _joint_attached->getParentBodyNode();\n                    tf = _joint_attached->getTransformFromParentBodyNode();\n                }\n                else if (_joint_attached->getChildBodyNode()) {\n                    body = _joint_attached->getChildBodyNode();\n                    tf = _joint_attached->getTransformFromChildBodyNode();\n                }\n\n                if (body)\n                    _world_pose = body->getWorldTransform() * tf * _attached_tf;\n            }\n            calculate(t);\n        }\n\n        void Sensor::attach_to_body(dart::dynamics::BodyNode* body, const Eigen::Isometry3d& tf)\n        {\n            _body_attached = body;\n            _attached_tf = tf;\n\n            if (_body_attached) {\n                _attaching_to_body = false;\n                _attached_to_body = true;\n\n                _attaching_to_joint = false;\n                _attached_to_joint = false;\n                _joint_attached = nullptr;\n            }\n            else { // we cannot keep attaching to a null BodyNode\n                _attaching_to_body = false;\n                _attached_to_body = false;\n            }\n        }\n\n        void Sensor::attach_to_joint(dart::dynamics::Joint* joint, const Eigen::Isometry3d& tf)\n        {\n            _joint_attached = joint;\n            _attached_tf = tf;\n\n            if (_joint_attached) {\n                _attaching_to_joint = false;\n                _attached_to_joint = true;\n\n                _attaching_to_body = false;\n                _attached_to_body = false;\n            }\n            else { // we cannot keep attaching to a null Joint\n                _attaching_to_joint = false;\n                _attached_to_joint = false;\n            }\n        }\n        const std::string& Sensor::attached_to() const\n        {\n            ROBOT_DART_EXCEPTION_ASSERT(_attached_to_body || _attached_to_joint, \"Joint is not attached to anything\");\n            if (_attached_to_body)\n                return _body_attached->getName();\n            // attached to joint\n            return _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

  • #include <robot_dart/robot.hpp>
  • #include <robot_dart/utils.hpp>
  • #include <memory>
  • #include <vector>
"},{"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\n#include <robot_dart/robot.hpp>\n#include <robot_dart/utils.hpp>\n\n#include <memory>\n#include <vector>\n\nnamespace dart {\n    namespace dynamics {\n        class BodyNode;\n        class Joint;\n    } // namespace dynamics\n} // namespace dart\n\nnamespace robot_dart {\n    class RobotDARTSimu;\n\n    namespace sensor {\n        class Sensor {\n        public:\n            Sensor(size_t freq = 40);\n            virtual ~Sensor() {}\n\n            void activate(bool enable = true);\n            bool active() const;\n\n            void set_simu(RobotDARTSimu* simu);\n            const RobotDARTSimu* simu() const;\n\n            size_t frequency() const;\n            void set_frequency(size_t freq);\n\n            void set_pose(const Eigen::Isometry3d& tf);\n            const Eigen::Isometry3d& pose() const;\n\n            void refresh(double t);\n\n            virtual void init() = 0;\n            // TO-DO: Maybe make this const?\n            virtual void calculate(double) = 0;\n\n            virtual std::string type() const = 0;\n\n            virtual void attach_to_body(dart::dynamics::BodyNode* body, const Eigen::Isometry3d& tf = Eigen::Isometry3d::Identity());\n            void 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); }\n\n            virtual void attach_to_joint(dart::dynamics::Joint* joint, const Eigen::Isometry3d& tf = Eigen::Isometry3d::Identity());\n            void 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); }\n\n            void detach();\n            const std::string& attached_to() const;\n\n        protected:\n            RobotDARTSimu* _simu = nullptr;\n            bool _active;\n            size_t _frequency;\n\n            Eigen::Isometry3d _world_pose;\n\n            bool _attaching_to_body = false, _attached_to_body = false;\n            bool _attaching_to_joint = false, _attached_to_joint = false;\n            Eigen::Isometry3d _attached_tf;\n            dart::dynamics::BodyNode* _body_attached;\n            dart::dynamics::Joint* _joint_attached;\n        };\n    } // namespace sensor\n} // namespace robot_dart\n\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

  • #include \"torque.hpp\"
  • #include <robot_dart/robot_dart_simu.hpp>
  • #include <robot_dart/utils_headers_dart_dynamics.hpp>
"},{"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\n#include <robot_dart/robot_dart_simu.hpp>\n#include <robot_dart/utils_headers_dart_dynamics.hpp>\n\nnamespace robot_dart {\n    namespace sensor {\n        Torque::Torque(dart::dynamics::Joint* joint, size_t frequency) : Sensor(frequency), _torques(joint->getNumDofs())\n        {\n            attach_to_joint(joint, Eigen::Isometry3d::Identity());\n        }\n\n        void Torque::init()\n        {\n            _torques.setZero();\n\n            attach_to_joint(_joint_attached, Eigen::Isometry3d::Identity());\n            _active = true;\n        }\n\n        void Torque::calculate(double)\n        {\n            if (!_attached_to_joint)\n                return; // cannot compute anything if not attached to a joint\n\n            Eigen::Vector6d wrench = Eigen::Vector6d::Zero();\n            auto child_body = _joint_attached->getChildBodyNode();\n            ROBOT_DART_ASSERT(child_body != nullptr, \"Child BodyNode is nullptr\", );\n\n            wrench = child_body->getBodyForce();\n\n            // get forces for only the only degrees of freedom in this joint\n            _torques = _joint_attached->getRelativeJacobian().transpose() * wrench;\n        }\n\n        std::string Torque::type() const { return \"t\"; }\n\n        const Eigen::VectorXd& Torque::torques() const\n        {\n            return _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

  • #include <robot_dart/sensor/sensor.hpp>
"},{"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\n#include <robot_dart/sensor/sensor.hpp>\n\nnamespace robot_dart {\n    namespace sensor {\n        class Torque : public Sensor {\n        public:\n            Torque(dart::dynamics::Joint* joint, size_t frequency = 1000);\n            Torque(const std::shared_ptr<Robot>& robot, const std::string& joint_name, size_t frequency = 1000) : Torque(robot->joint(joint_name), frequency) {}\n\n            void init() override;\n\n            void calculate(double) override;\n\n            std::string type() const override;\n\n            const Eigen::VectorXd& torques() const;\n\n            void attach_to_body(dart::dynamics::BodyNode*, const Eigen::Isometry3d&) override\n            {\n                ROBOT_DART_WARNING(true, \"You cannot attach a torque sensor to a body!\");\n            }\n\n        protected:\n            Eigen::VectorXd _torques;\n        };\n    } // namespace sensor\n} // namespace robot_dart\n\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

  • #include \"robot_dart_simu.hpp\"
  • #include \"gui_data.hpp\"
  • #include \"utils.hpp\"
  • #include \"utils_headers_dart_collision.hpp\"
  • #include \"utils_headers_dart_dynamics.hpp\"
  • #include <sstream>
"},{"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\n#include <sstream>\n\nnamespace robot_dart {\n    namespace 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\n        class BitmaskContactFilter : public dart::collision::BodyNodeCollisionFilter {\n        public:\n            using DartCollisionConstPtr = const dart::collision::CollisionObject*;\n            using DartShapeConstPtr = const dart::dynamics::ShapeNode*;\n\n            struct Masks {\n                uint32_t collision_mask = 0xffffffff;\n                uint32_t category_mask = 0xffffffff;\n            };\n\n            virtual ~BitmaskContactFilter() = default;\n\n            // This function follows DART's coding style as it needs to override a function\n            bool ignoresCollision(DartCollisionConstPtr object1, DartCollisionConstPtr object2) const override\n            {\n                auto shape_node1 = object1->getShapeFrame()->asShapeNode();\n                auto shape_node2 = object2->getShapeFrame()->asShapeNode();\n\n                if (dart::collision::BodyNodeCollisionFilter::ignoresCollision(object1, object2))\n                    return true;\n\n                auto shape1_iter = _bitmask_map.find(shape_node1);\n                auto shape2_iter = _bitmask_map.find(shape_node2);\n                if (shape1_iter != _bitmask_map.end() && shape2_iter != _bitmask_map.end()) {\n                    auto col_mask1 = shape1_iter->second.collision_mask;\n                    auto cat_mask1 = shape1_iter->second.category_mask;\n\n                    auto col_mask2 = shape2_iter->second.collision_mask;\n                    auto cat_mask2 = shape2_iter->second.category_mask;\n\n                    if ((col_mask1 & cat_mask2) == 0 && (col_mask2 & cat_mask1) == 0)\n                        return true;\n                }\n\n                return false;\n            }\n\n            void add_to_map(DartShapeConstPtr shape, uint32_t col_mask, uint32_t cat_mask)\n            {\n                _bitmask_map[shape] = {col_mask, cat_mask};\n            }\n\n            void add_to_map(dart::dynamics::SkeletonPtr skel, uint32_t col_mask, uint32_t cat_mask)\n            {\n                for (std::size_t i = 0; i < skel->getNumShapeNodes(); ++i) {\n                    auto shape = skel->getShapeNode(i);\n                    this->add_to_map(shape, col_mask, cat_mask);\n                }\n            }\n\n            void remove_from_map(DartShapeConstPtr shape)\n            {\n                auto shape_iter = _bitmask_map.find(shape);\n                if (shape_iter != _bitmask_map.end())\n                    _bitmask_map.erase(shape_iter);\n            }\n\n            void remove_from_map(dart::dynamics::SkeletonPtr skel)\n            {\n                for (std::size_t i = 0; i < skel->getNumShapeNodes(); ++i) {\n                    auto shape = skel->getShapeNode(i);\n                    this->remove_from_map(shape);\n                }\n            }\n\n            void clear_all() { _bitmask_map.clear(); }\n\n            Masks mask(DartShapeConstPtr shape) const\n            {\n                auto shape_iter = _bitmask_map.find(shape);\n                if (shape_iter != _bitmask_map.end())\n                    return shape_iter->second;\n                return {0xffffffff, 0xffffffff};\n            }\n\n        private:\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\n            std::unordered_map<DartShapeConstPtr, Masks> _bitmask_map;\n        };\n    } // namespace collision_filter\n\n    RobotDARTSimu::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\n        _gui_data.reset(new simu::GUIData());\n    }\n\n    RobotDARTSimu::~RobotDARTSimu()\n    {\n        _robots.clear();\n        _sensors.clear();\n    }\n\n    void RobotDARTSimu::run(double max_duration, bool reset_commands, bool force_position_bounds)\n    {\n        _break = false;\n        double old_time = _world->getTime();\n        double factor = _world->getTimeStep() / 2.;\n\n        while ((_world->getTime() - old_time - max_duration) < -factor) {\n            if (step(reset_commands, force_position_bounds))\n                break;\n        }\n    }\n\n    bool RobotDARTSimu::step_world(bool reset_commands, bool force_position_bounds)\n    {\n        if (_scheduler(_physics_freq)) {\n            _world->step(reset_commands);\n            if (force_position_bounds)\n                for (auto& r : _robots)\n                    r->force_position_bounds();\n        }\n\n        // Update graphics\n        if (_scheduler(_graphics_freq)) {\n            // Update default texts\n            if (_text_panel) { // Need to re-transform as the size of the window might have changed\n                Eigen::Affine2d tf = Eigen::Affine2d::Identity();\n                tf.translate(Eigen::Vector2d(-static_cast<double>(_graphics->width()) / 2., _graphics->height() / 2.));\n                // tf.translate(Eigen::Vector2d(-static_cast<double>(_graphics->width()) / 2., 0.));\n                _text_panel->transformation = tf;\n            }\n            if (_status_bar) {\n                _status_bar->text = status_bar_text(); // this is dynamic text (timings)\n                Eigen::Affine2d tf = Eigen::Affine2d::Identity();\n                tf.translate(Eigen::Vector2d(-static_cast<double>(_graphics->width()) / 2., -static_cast<double>(_graphics->height() / 2.)));\n                // tf.translate(Eigen::Vector2d(-static_cast<double>(_graphics->width()) / 2., 0.));\n                _status_bar->transformation = tf;\n            }\n\n            // Update robot-specific GUI data\n            for (auto& robot : _robots) {\n                _gui_data->update_robot(robot);\n            }\n\n            _graphics->refresh();\n        }\n\n        // update sensors\n        for (auto& sensor : _sensors) {\n            if (sensor->active() && _scheduler(sensor->frequency())) {\n                sensor->refresh(_world->getTime());\n            }\n        }\n\n        _old_index++;\n        _scheduler.step();\n\n        return _break || _graphics->done();\n    }\n\n    bool RobotDARTSimu::step(bool reset_commands, bool force_position_bounds)\n    {\n        if (_scheduler(_control_freq)) {\n            for (auto& robot : _robots) {\n                robot->update(_world->getTime());\n            }\n        }\n\n        return step_world(reset_commands, force_position_bounds);\n    }\n\n    std::shared_ptr<gui::Base> RobotDARTSimu::graphics() const\n    {\n        return _graphics;\n    }\n\n    void 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    }\n\n    dart::simulation::WorldPtr RobotDARTSimu::world()\n    {\n        return _world;\n    }\n\n    void RobotDARTSimu::add_sensor(const std::shared_ptr<sensor::Sensor>& sensor)\n    {\n        _sensors.push_back(sensor);\n        sensor->set_simu(this);\n        sensor->init();\n    }\n\n    std::vector<std::shared_ptr<sensor::Sensor>> RobotDARTSimu::sensors() const\n    {\n        return _sensors;\n    }\n\n    std::shared_ptr<sensor::Sensor> RobotDARTSimu::sensor(size_t index) const\n    {\n        ROBOT_DART_ASSERT(index < _sensors.size(), \"Sensor index out of bounds\", nullptr);\n        return _sensors[index];\n    }\n\n    void RobotDARTSimu::remove_sensor(const std::shared_ptr<sensor::Sensor>& sensor)\n    {\n        auto it = std::find(_sensors.begin(), _sensors.end(), sensor);\n        if (it != _sensors.end()) {\n            _sensors.erase(it);\n        }\n    }\n\n    void RobotDARTSimu::remove_sensor(size_t index)\n    {\n        ROBOT_DART_ASSERT(index < _sensors.size(), \"Sensor index out of bounds\", );\n        _sensors.erase(_sensors.begin() + index);\n    }\n\n    void RobotDARTSimu::remove_sensors(const std::string& type)\n    {\n        for (int i = 0; i < static_cast<int>(_sensors.size()); i++) {\n            auto& sensor = _sensors[i];\n            if (sensor->type() == type) {\n                _sensors.erase(_sensors.begin() + i);\n                i--;\n            }\n        }\n    }\n\n    void RobotDARTSimu::clear_sensors()\n    {\n        _sensors.clear();\n    }\n\n    double RobotDARTSimu::timestep() const\n    {\n        return _world->getTimeStep();\n    }\n\n    void RobotDARTSimu::set_timestep(double timestep, bool update_control_freq)\n    {\n        _world->setTimeStep(timestep);\n        _physics_freq = std::round(1. / timestep);\n        if (update_control_freq)\n            _control_freq = _physics_freq;\n\n        _scheduler.reset(timestep, _scheduler.sync(), _scheduler.current_time(), _scheduler.real_time());\n    }\n\n    Eigen::Vector3d RobotDARTSimu::gravity() const\n    {\n        return _world->getGravity();\n    }\n\n    void RobotDARTSimu::set_gravity(const Eigen::Vector3d& gravity)\n    {\n        _world->setGravity(gravity);\n    }\n\n    void RobotDARTSimu::stop_sim(bool disable)\n    {\n        _break = disable;\n    }\n\n    bool RobotDARTSimu::halted_sim() const\n    {\n        return _break;\n    }\n\n    size_t RobotDARTSimu::num_robots() const\n    {\n        return _robots.size();\n    }\n\n    const std::vector<std::shared_ptr<Robot>>& RobotDARTSimu::robots() const\n    {\n        return _robots;\n    }\n\n    std::shared_ptr<Robot> RobotDARTSimu::robot(size_t index) const\n    {\n        ROBOT_DART_ASSERT(index < _robots.size(), \"Robot index out of bounds\", nullptr);\n        return _robots[index];\n    }\n\n    int RobotDARTSimu::robot_index(const std::shared_ptr<Robot>& robot) const\n    {\n        auto it = std::find(_robots.begin(), _robots.end(), robot);\n        ROBOT_DART_ASSERT(it != _robots.end(), \"Robot index out of bounds\", -1);\n        return std::distance(_robots.begin(), it);\n    }\n\n    void RobotDARTSimu::add_robot(const std::shared_ptr<Robot>& robot)\n    {\n        if (robot->skeleton()) {\n            _robots.push_back(robot);\n            _world->addSkeleton(robot->skeleton());\n\n            robot->_post_addition(this);\n\n            _gui_data->update_robot(robot);\n        }\n    }\n\n    void RobotDARTSimu::add_visual_robot(const std::shared_ptr<Robot>& robot)\n    {\n        if (robot->skeleton()) {\n            // make robot a pure visual one -- assuming that the color is already set\n            // visual robots do not do physics updates\n            robot->skeleton()->setMobile(false);\n            for (auto& bd : robot->skeleton()->getBodyNodes()) {\n#if DART_VERSION_AT_LEAST(6, 13, 0)\n                // visual robots do not have collisions\n                bd->eachShapeNodeWith<dart::dynamics::CollisionAspect>([](dart::dynamics::ShapeNode* shape) {\n                    shape->removeAspect<dart::dynamics::CollisionAspect>();\n                });\n#else\n                auto& collision_shapes = bd->getShapeNodesWith<dart::dynamics::CollisionAspect>();\n                for (auto& shape : collision_shapes) {\n                    shape->removeAspect<dart::dynamics::CollisionAspect>();\n                }\n#endif\n            }\n\n            // visual robots, by default, use the color from the VisualAspect\n            robot->set_color_mode(\"aspect\");\n\n            // visual robots do not cast shadows\n            robot->set_cast_shadows(false);\n            // set the ghost/visual flag\n            robot->set_ghost(true);\n            robot->_post_addition(this);\n\n            _robots.push_back(robot);\n            _world->addSkeleton(robot->skeleton());\n\n            _gui_data->update_robot(robot);\n        }\n    }\n\n    void RobotDARTSimu::remove_robot(const std::shared_ptr<Robot>& robot)\n    {\n        auto it = std::find(_robots.begin(), _robots.end(), robot);\n        if (it != _robots.end()) {\n            robot->_post_removal(this);\n            _gui_data->remove_robot(robot);\n            _world->removeSkeleton(robot->skeleton());\n            _robots.erase(it);\n        }\n    }\n\n    void RobotDARTSimu::remove_robot(size_t index)\n    {\n        ROBOT_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    }\n\n    void RobotDARTSimu::clear_robots()\n    {\n        for (auto& robot : _robots) {\n            robot->_post_removal(this);\n            _gui_data->remove_robot(robot);\n            _world->removeSkeleton(robot->skeleton());\n        }\n        _robots.clear();\n    }\n\n    simu::GUIData* RobotDARTSimu::gui_data() { return &(*_gui_data); }\n\n    void RobotDARTSimu::enable_text_panel(bool enable, double font_size)\n    {\n        _enable(_text_panel, enable, font_size);\n        if (enable) {\n            _text_panel->alignment = 3 << 2; // alignment of status bar should be LineTop; TO-DO: Check how to get types automatically from Magnum?\n            // _text_panel->draw_background = true; // we want to draw a background\n            // _text_panel->background_color = Eigen::Vector4d(0, 0, 0, 0.75); // black-transparent bar\n        }\n    }\n\n    void RobotDARTSimu::enable_status_bar(bool enable, double font_size)\n    {\n        _enable(_status_bar, enable, font_size);\n        if (enable) {\n            _status_bar->alignment = 1 << 2; // alignment of status bar should be LineBottom; TO-DO: Check how to get types automatically from Magnum?\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    }\n\n    void RobotDARTSimu::_enable(std::shared_ptr<simu::TextData>& text, bool enable, double font_size)\n    {\n        if (!text && enable) {\n            text = add_text(\"\");\n        }\n        else if (!enable) {\n            if (text)\n                _gui_data->remove_text(text);\n            text = nullptr;\n        }\n        if (text && font_size > 0)\n            text->font_size = font_size;\n    }\n\n    void RobotDARTSimu::set_text_panel(const std::string& str)\n    {\n        ROBOT_DART_ASSERT(_text_panel, \"Panel text object not created. Use enable_text_panel() to create it.\", );\n        _text_panel->text = str;\n    }\n\n    std::string RobotDARTSimu::text_panel_text() const\n    {\n        ROBOT_DART_ASSERT(_text_panel, \"Panel text object not created. Returning empty string.\", \"\");\n        return _text_panel->text;\n    }\n\n    std::string RobotDARTSimu::status_bar_text() const\n    {\n        std::ostringstream out;\n        out.precision(3);\n        double rt = _scheduler.real_time();\n\n        out << std::fixed << \"[simulation time: \" << _world->getTime()\n            << \"s ] [\"\n            << \"wall time: \" << rt << \"s] [\";\n        out.precision(1);\n        out << _scheduler.real_time_factor() << \"x]\";\n        out << \" [it: \" << _scheduler.it_duration() * 1e3 << \" ms]\";\n        out << (_scheduler.sync() ? \" [sync]\" : \" [no-sync]\");\n\n        return out.str();\n    }\n\n    std::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    {\n        return _gui_data->add_text(text, tf, color, alignment, draw_bg, bg_color, font_size);\n    }\n\n    std::shared_ptr<Robot> RobotDARTSimu::add_floor(double floor_width, double floor_height, const Eigen::Isometry3d& tf, const std::string& floor_name)\n    {\n        ROBOT_DART_ASSERT((_world->getSkeleton(floor_name) == nullptr), \"We cannot have 2 floors with the name '\" + floor_name + \"'\", nullptr);\n        ROBOT_DART_ASSERT((floor_width > 0. && floor_height > 0.), \"Floor dimensions should be bigger than zero!\", nullptr);\n\n        dart::dynamics::SkeletonPtr floor_skel = dart::dynamics::Skeleton::create(floor_name);\n\n        // Give the floor a body\n        dart::dynamics::BodyNodePtr body = floor_skel->createJointAndBodyNodePair<dart::dynamics::WeldJoint>(nullptr).second;\n\n        // Give the body a shape\n        auto box = std::make_shared<dart::dynamics::BoxShape>(Eigen::Vector3d(floor_width, floor_width, floor_height));\n        auto box_node = body->createShapeNodeWith<dart::dynamics::VisualAspect, dart::dynamics::CollisionAspect, dart::dynamics::DynamicsAspect>(box);\n        box_node->getVisualAspect()->setColor(dart::Color::Gray());\n\n        // Put the body into position\n        Eigen::Isometry3d new_tf = tf;\n        new_tf.translate(Eigen::Vector3d(0., 0., -floor_height / 2.0));\n        body->getParentJoint()->setTransformFromParentBodyNode(new_tf);\n\n        auto floor_robot = std::make_shared<Robot>(floor_skel, floor_name);\n        add_robot(floor_robot);\n        return floor_robot;\n    }\n\n    std::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    {\n        ROBOT_DART_ASSERT((_world->getSkeleton(floor_name) == nullptr), \"We cannot have 2 floors with the name '\" + floor_name + \"'\", nullptr);\n        ROBOT_DART_ASSERT((floor_width > 0. && floor_height > 0. && size > 0.), \"Floor dimensions should be bigger than zero!\", nullptr);\n\n        // Add main floor skeleton\n        dart::dynamics::SkeletonPtr main_floor_skel = dart::dynamics::Skeleton::create(floor_name + \"_main\");\n\n        // Give the floor a body\n        dart::dynamics::BodyNodePtr main_body = main_floor_skel->createJointAndBodyNodePair<dart::dynamics::WeldJoint>(nullptr).second;\n\n        // Give the body a shape\n        auto 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\n        main_body->createShapeNodeWith<dart::dynamics::CollisionAspect, dart::dynamics::DynamicsAspect>(box);\n\n        // Put the body into position\n        Eigen::Isometry3d new_tf = tf;\n        new_tf.translate(Eigen::Vector3d(0., 0., -floor_height / 2.0));\n        main_body->getParentJoint()->setTransformFromParentBodyNode(new_tf);\n\n        // Add visual bodies just for visualization\n        int step = std::ceil(floor_width / size);\n        int c = 0;\n        for (int i = 0; i < step; i++) {\n            c = i;\n            for (int j = 0; j < step; j++) {\n                Eigen::Vector3d init_pose;\n                init_pose << -floor_width / 2. + size / 2 + i * size, -floor_width / 2. + size / 2 + j * size, 0.;\n                int id = i * step + j;\n\n                dart::dynamics::WeldJoint::Properties properties;\n                properties.mName = \"joint_\" + std::to_string(id);\n                dart::dynamics::BodyNode::Properties bd_properties;\n                bd_properties.mName = \"body_\" + std::to_string(id);\n                dart::dynamics::BodyNodePtr body = main_body->createChildJointAndBodyNodePair<dart::dynamics::WeldJoint>(properties, bd_properties).second;\n\n                auto box = std::make_shared<dart::dynamics::BoxShape>(Eigen::Vector3d(size, size, floor_height));\n                // no collision/dynamics for these ones; only visual shape\n                auto box_node = body->createShapeNodeWith<dart::dynamics::VisualAspect>(box);\n                if (c % 2 == 0)\n                    box_node->getVisualAspect()->setColor(second_color);\n                else\n                    box_node->getVisualAspect()->setColor(first_color);\n\n                // Put the body into position\n                Eigen::Isometry3d tf(Eigen::Isometry3d::Identity());\n                tf.translation() = init_pose;\n                body->getParentJoint()->setTransformFromParentBodyNode(tf);\n\n                c++;\n            }\n        }\n\n        auto floor_robot = std::make_shared<Robot>(main_floor_skel, floor_name);\n        add_robot(floor_robot);\n        return floor_robot;\n    }\n\n    void RobotDARTSimu::set_collision_detector(const std::string& collision_detector)\n    {\n        std::string coll = collision_detector;\n        for (auto& c : coll)\n            c = tolower(c);\n\n        if (coll == \"dart\")\n            _world->getConstraintSolver()->setCollisionDetector(dart::collision::DARTCollisionDetector::create());\n        else if (coll == \"fcl\")\n            _world->getConstraintSolver()->setCollisionDetector(dart::collision::FCLCollisionDetector::create());\n        else if (coll == \"bullet\") {\n#if (HAVE_BULLET == 1)\n            _world->getConstraintSolver()->setCollisionDetector(dart::collision::BulletCollisionDetector::create());\n#else\n            ROBOT_DART_WARNING(true, \"DART is not installed with Bullet! Cannot set BulletCollisionDetector!\");\n#endif\n        }\n        else if (coll == \"ode\") {\n#if (HAVE_ODE == 1)\n            _world->getConstraintSolver()->setCollisionDetector(dart::collision::OdeCollisionDetector::create());\n#else\n            ROBOT_DART_WARNING(true, \"DART is not installed with ODE! Cannot set OdeCollisionDetector!\");\n#endif\n        }\n    }\n\n    const std::string& RobotDARTSimu::collision_detector() const { return _world->getConstraintSolver()->getCollisionDetector()->getType(); }\n\n    void RobotDARTSimu::set_collision_masks(size_t robot_index, uint32_t category_mask, uint32_t collision_mask)\n    {\n        ROBOT_DART_ASSERT(robot_index < _robots.size(), \"Robot index out of bounds\", );\n        auto coll_filter = std::static_pointer_cast<collision_filter::BitmaskContactFilter>(_world->getConstraintSolver()->getCollisionOption().collisionFilter);\n        coll_filter->add_to_map(_robots[robot_index]->skeleton(), collision_mask, category_mask);\n    }\n\n    void RobotDARTSimu::set_collision_masks(size_t robot_index, const std::string& body_name, uint32_t category_mask, uint32_t collision_mask)\n    {\n        ROBOT_DART_ASSERT(robot_index < _robots.size(), \"Robot index out of bounds\", );\n        auto bd = _robots[robot_index]->skeleton()->getBodyNode(body_name);\n        ROBOT_DART_ASSERT(bd != nullptr, \"BodyNode does not exist in skeleton!\", );\n        auto coll_filter = std::static_pointer_cast<collision_filter::BitmaskContactFilter>(_world->getConstraintSolver()->getCollisionOption().collisionFilter);\n#if DART_VERSION_AT_LEAST(6, 13, 0)\n        bd->eachShapeNode([coll_filter, collision_mask, category_mask](dart::dynamics::ShapeNode* shape) { coll_filter->add_to_map(shape, collision_mask, category_mask); });\n#else\n        for (auto& shape : bd->getShapeNodes())\n            coll_filter->add_to_map(shape, collision_mask, category_mask);\n#endif\n    }\n\n    void RobotDARTSimu::set_collision_masks(size_t robot_index, size_t body_index, uint32_t category_mask, uint32_t collision_mask)\n    {\n        ROBOT_DART_ASSERT(robot_index < _robots.size(), \"Robot index out of bounds\", );\n        auto skel = _robots[robot_index]->skeleton();\n        ROBOT_DART_ASSERT(body_index < skel->getNumBodyNodes(), \"BodyNode index out of bounds\", );\n        auto bd = skel->getBodyNode(body_index);\n        auto coll_filter = std::static_pointer_cast<collision_filter::BitmaskContactFilter>(_world->getConstraintSolver()->getCollisionOption().collisionFilter);\n#if DART_VERSION_AT_LEAST(6, 13, 0)\n        bd->eachShapeNode([coll_filter, collision_mask, category_mask](dart::dynamics::ShapeNode* shape) { coll_filter->add_to_map(shape, collision_mask, category_mask); });\n#else\n        for (auto& shape : bd->getShapeNodes())\n            coll_filter->add_to_map(shape, collision_mask, category_mask);\n#endif\n    }\n\n    uint32_t RobotDARTSimu::collision_mask(size_t robot_index, const std::string& body_name)\n    {\n        ROBOT_DART_ASSERT(robot_index < _robots.size(), \"Robot index out of bounds\", 0xffffffff);\n        auto bd = _robots[robot_index]->skeleton()->getBodyNode(body_name);\n        ROBOT_DART_ASSERT(bd != nullptr, \"BodyNode does not exist in skeleton!\", 0xffffffff);\n        auto coll_filter = std::static_pointer_cast<collision_filter::BitmaskContactFilter>(_world->getConstraintSolver()->getCollisionOption().collisionFilter);\n\n        uint32_t mask = 0xffffffff;\n#if DART_VERSION_AT_LEAST(6, 13, 0)\n        bd->eachShapeNode([coll_filter, &mask](dart::dynamics::ShapeNode* shape) { mask &= coll_filter->mask(shape).collision_mask; });\n#else\n        for (auto& shape : bd->getShapeNodes())\n            mask &= coll_filter->mask(shape).collision_mask;\n#endif\n\n        return mask;\n    }\n\n    uint32_t RobotDARTSimu::collision_mask(size_t robot_index, size_t body_index)\n    {\n        ROBOT_DART_ASSERT(robot_index < _robots.size(), \"Robot index out of bounds\", 0xffffffff);\n        auto skel = _robots[robot_index]->skeleton();\n        ROBOT_DART_ASSERT(body_index < skel->getNumBodyNodes(), \"BodyNode index out of bounds\", 0xffffffff);\n        auto bd = skel->getBodyNode(body_index);\n        auto coll_filter = std::static_pointer_cast<collision_filter::BitmaskContactFilter>(_world->getConstraintSolver()->getCollisionOption().collisionFilter);\n\n        uint32_t mask = 0xffffffff;\n#if DART_VERSION_AT_LEAST(6, 13, 0)\n        bd->eachShapeNode([coll_filter, &mask](dart::dynamics::ShapeNode* shape) { mask &= coll_filter->mask(shape).collision_mask; });\n#else\n        for (auto& shape : bd->getShapeNodes())\n            mask &= coll_filter->mask(shape).collision_mask;\n#endif\n\n        return mask;\n    }\n\n    uint32_t RobotDARTSimu::collision_category(size_t robot_index, const std::string& body_name)\n    {\n        ROBOT_DART_ASSERT(robot_index < _robots.size(), \"Robot index out of bounds\", 0xffffffff);\n        auto bd = _robots[robot_index]->skeleton()->getBodyNode(body_name);\n        ROBOT_DART_ASSERT(bd != nullptr, \"BodyNode does not exist in skeleton!\", 0xffffffff);\n        auto coll_filter = std::static_pointer_cast<collision_filter::BitmaskContactFilter>(_world->getConstraintSolver()->getCollisionOption().collisionFilter);\n\n        uint32_t mask = 0xffffffff;\n#if DART_VERSION_AT_LEAST(6, 13, 0)\n        bd->eachShapeNode([coll_filter, &mask](dart::dynamics::ShapeNode* shape) { mask &= coll_filter->mask(shape).category_mask; });\n#else\n        for (auto& shape : bd->getShapeNodes())\n            mask &= coll_filter->mask(shape).category_mask;\n#endif\n\n        return mask;\n    }\n\n    uint32_t RobotDARTSimu::collision_category(size_t robot_index, size_t body_index)\n    {\n        ROBOT_DART_ASSERT(robot_index < _robots.size(), \"Robot index out of bounds\", 0xffffffff);\n        auto skel = _robots[robot_index]->skeleton();\n        ROBOT_DART_ASSERT(body_index < skel->getNumBodyNodes(), \"BodyNode index out of bounds\", 0xffffffff);\n        auto bd = skel->getBodyNode(body_index);\n        auto coll_filter = std::static_pointer_cast<collision_filter::BitmaskContactFilter>(_world->getConstraintSolver()->getCollisionOption().collisionFilter);\n\n        uint32_t mask = 0xffffffff;\n#if DART_VERSION_AT_LEAST(6, 13, 0)\n        bd->eachShapeNode([coll_filter, &mask](dart::dynamics::ShapeNode* shape) { mask &= coll_filter->mask(shape).category_mask; });\n#else\n        for (auto& shape : bd->getShapeNodes())\n            mask &= coll_filter->mask(shape).category_mask;\n#endif\n\n        return mask;\n    }\n\n    std::pair<uint32_t, uint32_t> RobotDARTSimu::collision_masks(size_t robot_index, const std::string& body_name)\n    {\n        std::pair<uint32_t, uint32_t> mask = {0xffffffff, 0xffffffff};\n        ROBOT_DART_ASSERT(robot_index < _robots.size(), \"Robot index out of bounds\", mask);\n        auto bd = _robots[robot_index]->skeleton()->getBodyNode(body_name);\n        ROBOT_DART_ASSERT(bd != nullptr, \"BodyNode does not exist in skeleton!\", mask);\n        auto coll_filter = std::static_pointer_cast<collision_filter::BitmaskContactFilter>(_world->getConstraintSolver()->getCollisionOption().collisionFilter);\n\n#if DART_VERSION_AT_LEAST(6, 13, 0)\n        bd->eachShapeNode([coll_filter, &mask](dart::dynamics::ShapeNode* shape) {\n            mask.first &= coll_filter->mask(shape).collision_mask;\n            mask.second &= coll_filter->mask(shape).category_mask;\n        });\n#else\n        for (auto& shape : bd->getShapeNodes()) {\n            mask.first &= coll_filter->mask(shape).collision_mask;\n            mask.second &= coll_filter->mask(shape).category_mask;\n        }\n#endif\n\n        return mask;\n    }\n\n    std::pair<uint32_t, uint32_t> RobotDARTSimu::collision_masks(size_t robot_index, size_t body_index)\n    {\n        std::pair<uint32_t, uint32_t> mask = {0xffffffff, 0xffffffff};\n        ROBOT_DART_ASSERT(robot_index < _robots.size(), \"Robot index out of bounds\", mask);\n        auto skel = _robots[robot_index]->skeleton();\n        ROBOT_DART_ASSERT(body_index < skel->getNumBodyNodes(), \"BodyNode index out of bounds\", mask);\n        auto bd = skel->getBodyNode(body_index);\n        auto coll_filter = std::static_pointer_cast<collision_filter::BitmaskContactFilter>(_world->getConstraintSolver()->getCollisionOption().collisionFilter);\n\n#if DART_VERSION_AT_LEAST(6, 13, 0)\n        bd->eachShapeNode([coll_filter, &mask](dart::dynamics::ShapeNode* shape) {\n            mask.first &= coll_filter->mask(shape).collision_mask;\n            mask.second &= coll_filter->mask(shape).category_mask;\n        });\n#else\n        for (auto& shape : bd->getShapeNodes()) {\n            mask.first &= coll_filter->mask(shape).collision_mask;\n            mask.second &= coll_filter->mask(shape).category_mask;\n        }\n#endif\n\n        return mask;\n    }\n\n    void RobotDARTSimu::remove_collision_masks(size_t robot_index)\n    {\n        ROBOT_DART_ASSERT(robot_index < _robots.size(), \"Robot index out of bounds\", );\n        auto coll_filter = std::static_pointer_cast<collision_filter::BitmaskContactFilter>(_world->getConstraintSolver()->getCollisionOption().collisionFilter);\n        coll_filter->remove_from_map(_robots[robot_index]->skeleton());\n    }\n\n    void RobotDARTSimu::remove_collision_masks(size_t robot_index, const std::string& body_name)\n    {\n        ROBOT_DART_ASSERT(robot_index < _robots.size(), \"Robot index out of bounds\", );\n        auto bd = _robots[robot_index]->skeleton()->getBodyNode(body_name);\n        ROBOT_DART_ASSERT(bd != nullptr, \"BodyNode does not exist in skeleton!\", );\n        auto coll_filter = std::static_pointer_cast<collision_filter::BitmaskContactFilter>(_world->getConstraintSolver()->getCollisionOption().collisionFilter);\n#if DART_VERSION_AT_LEAST(6, 13, 0)\n        bd->eachShapeNode([coll_filter](dart::dynamics::ShapeNode* shape) { coll_filter->remove_from_map(shape); });\n#else\n        for (auto& shape : bd->getShapeNodes())\n            coll_filter->remove_from_map(shape);\n#endif\n    }\n\n    void RobotDARTSimu::remove_collision_masks(size_t robot_index, size_t body_index)\n    {\n        ROBOT_DART_ASSERT(robot_index < _robots.size(), \"Robot index out of bounds\", );\n        auto skel = _robots[robot_index]->skeleton();\n        ROBOT_DART_ASSERT(body_index < skel->getNumBodyNodes(), \"BodyNode index out of bounds\", );\n        auto bd = skel->getBodyNode(body_index);\n        auto coll_filter = std::static_pointer_cast<collision_filter::BitmaskContactFilter>(_world->getConstraintSolver()->getCollisionOption().collisionFilter);\n#if DART_VERSION_AT_LEAST(6, 13, 0)\n        bd->eachShapeNode([coll_filter](dart::dynamics::ShapeNode* shape) { coll_filter->remove_from_map(shape); });\n#else\n        for (auto& shape : bd->getShapeNodes())\n            coll_filter->remove_from_map(shape);\n#endif\n    }\n\n    void RobotDARTSimu::remove_all_collision_masks()\n    {\n        auto coll_filter = std::static_pointer_cast<collision_filter::BitmaskContactFilter>(_world->getConstraintSolver()->getCollisionOption().collisionFilter);\n        coll_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

  • #include <robot_dart/gui/base.hpp>
  • #include <robot_dart/robot.hpp>
  • #include <robot_dart/scheduler.hpp>
  • #include <robot_dart/sensor/sensor.hpp>
"},{"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\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>\n\nnamespace robot_dart {\n    namespace simu {\n        struct GUIData;\n\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\n        struct TextData {\n            std::string text;\n            Eigen::Affine2d transformation;\n            Eigen::Vector4d color;\n            std::uint8_t alignment;\n            bool draw_background;\n            Eigen::Vector4d background_color;\n            double font_size = 28.;\n        };\n    } // namespace simu\n\n    class RobotDARTSimu {\n    public:\n        using robot_t = std::shared_ptr<Robot>;\n\n        RobotDARTSimu(double timestep = 0.015);\n\n        ~RobotDARTSimu();\n\n        void run(double max_duration = 5.0, bool reset_commands = false, bool force_position_bounds = true);\n        bool step_world(bool reset_commands = false, bool force_position_bounds = true);\n        bool step(bool reset_commands = false, bool force_position_bounds = true);\n\n        Scheduler& scheduler() { return _scheduler; }\n        const Scheduler& scheduler() const { return _scheduler; }\n        bool schedule(int freq) { return _scheduler(freq); }\n\n        int physics_freq() const { return _physics_freq; }\n        int control_freq() const { return _control_freq; }\n\n        void set_control_freq(int frequency)\n        {\n            ROBOT_DART_EXCEPTION_INTERNAL_ASSERT(\n                frequency <= _physics_freq && \"Control frequency needs to be less than physics frequency\");\n            _control_freq = frequency;\n        }\n\n        int graphics_freq() const { return _graphics_freq; }\n\n        void set_graphics_freq(int frequency)\n        {\n            ROBOT_DART_EXCEPTION_INTERNAL_ASSERT(\n                frequency <= _physics_freq && \"Graphics frequency needs to be less than physics frequency\");\n            _graphics_freq = frequency;\n            _graphics->set_fps(_graphics_freq);\n        }\n\n        std::shared_ptr<gui::Base> graphics() const;\n        void set_graphics(const std::shared_ptr<gui::Base>& graphics);\n\n        dart::simulation::WorldPtr world();\n\n        template <typename T, typename... Args>\n        std::shared_ptr<T> add_sensor(Args&&... args)\n        {\n            add_sensor(std::make_shared<T>(std::forward<Args>(args)...));\n            return std::static_pointer_cast<T>(_sensors.back());\n        }\n\n        void add_sensor(const std::shared_ptr<sensor::Sensor>& sensor);\n        std::vector<std::shared_ptr<sensor::Sensor>> sensors() const;\n        std::shared_ptr<sensor::Sensor> sensor(size_t index) const;\n\n        void remove_sensor(const std::shared_ptr<sensor::Sensor>& sensor);\n        void remove_sensor(size_t index);\n        void remove_sensors(const std::string& type);\n        void clear_sensors();\n\n        double timestep() const;\n        void set_timestep(double timestep, bool update_control_freq = true);\n\n        Eigen::Vector3d gravity() const;\n        void set_gravity(const Eigen::Vector3d& gravity);\n\n        void stop_sim(bool disable = true);\n        bool halted_sim() const;\n\n        size_t num_robots() const;\n        const std::vector<robot_t>& robots() const;\n        robot_t robot(size_t index) const;\n        int robot_index(const robot_t& robot) const;\n\n        void add_robot(const robot_t& robot);\n        void add_visual_robot(const robot_t& robot);\n        void remove_robot(const robot_t& robot);\n        void remove_robot(size_t index);\n        void clear_robots();\n\n        simu::GUIData* gui_data();\n\n        void enable_text_panel(bool enable = true, double font_size = -1);\n        std::string text_panel_text() const;\n        void set_text_panel(const std::string& str);\n\n        void enable_status_bar(bool enable = true, double font_size = -1);\n        std::string status_bar_text() const;\n\n        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 = 2 << 2, bool draw_bg = false, Eigen::Vector4d bg_color = Eigen::Vector4d(0, 0, 0, 0.75), double font_size = 28);\n\n        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\");\n        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.));\n\n        void set_collision_detector(const std::string& collision_detector); // collision_detector can be \"DART\", \"FCL\", \"Ode\" or \"Bullet\" (case does not matter)\n        const std::string& collision_detector() const;\n\n        // Bitmask collision filtering\n        void set_collision_masks(size_t robot_index, uint32_t category_mask, uint32_t collision_mask);\n        void set_collision_masks(size_t robot_index, const std::string& body_name, uint32_t category_mask, uint32_t collision_mask);\n        void set_collision_masks(size_t robot_index, size_t body_index, uint32_t category_mask, uint32_t collision_mask);\n\n        uint32_t collision_mask(size_t robot_index, const std::string& body_name);\n        uint32_t collision_mask(size_t robot_index, size_t body_index);\n\n        uint32_t collision_category(size_t robot_index, const std::string& body_name);\n        uint32_t collision_category(size_t robot_index, size_t body_index);\n\n        std::pair<uint32_t, uint32_t> collision_masks(size_t robot_index, const std::string& body_name);\n        std::pair<uint32_t, uint32_t> collision_masks(size_t robot_index, size_t body_index);\n\n        void remove_collision_masks(size_t robot_index);\n        void remove_collision_masks(size_t robot_index, const std::string& body_name);\n        void remove_collision_masks(size_t robot_index, size_t body_index);\n\n        void remove_all_collision_masks();\n\n    protected:\n        void _enable(std::shared_ptr<simu::TextData>& text, bool enable, double font_size);\n\n        dart::simulation::WorldPtr _world;\n        size_t _old_index;\n        bool _break;\n\n        std::vector<std::shared_ptr<sensor::Sensor>> _sensors;\n        std::vector<robot_t> _robots;\n        std::shared_ptr<gui::Base> _graphics;\n        std::unique_ptr<simu::GUIData> _gui_data;\n        std::shared_ptr<simu::TextData> _text_panel = nullptr;\n        std::shared_ptr<simu::TextData> _status_bar = nullptr;\n\n        Scheduler _scheduler;\n        int _physics_freq = -1, _control_freq = -1, _graphics_freq = 40;\n    };\n} // namespace robot_dart\n\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

  • #include <robot_dart/robot_pool.hpp>
"},{"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>\n\nnamespace robot_dart {\n    RobotPool::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    {\n        if (_verbose) {\n            std::cout << \"Creating a pool of \" << pool_size << \" robots: \";\n            std::cout.flush();\n        }\n\n        for (size_t i = 0; i < _pool_size; ++i) {\n            if (_verbose) {\n                std::cout << \"[\" << i << \"]\";\n                std::cout.flush();\n            }\n            auto robot = robot_creator();\n            _model_filename = robot->model_filename();\n            _reset_robot(robot);\n            _skeletons.push_back(robot->skeleton());\n        }\n        for (size_t i = 0; i < _pool_size; i++)\n            _free.push_back(true);\n\n        if (_verbose)\n            std::cout << std::endl;\n    }\n\n    std::shared_ptr<Robot> RobotPool::get_robot(const std::string& name)\n    {\n        while (true) {\n            std::lock_guard<std::mutex> lock(_skeleton_mutex);\n            for (size_t i = 0; i < _pool_size; i++)\n                if (_free[i]) {\n                    _free[i] = false;\n                    return std::make_shared<Robot>(_skeletons[i], name);\n                }\n        }\n    }\n\n    void RobotPool::free_robot(const std::shared_ptr<Robot>& robot)\n    {\n        std::lock_guard<std::mutex> lock(_skeleton_mutex);\n        for (size_t i = 0; i < _pool_size; i++) {\n            if (_skeletons[i] == robot->skeleton()) {\n                _reset_robot(robot);\n                _free[i] = true;\n                break;\n            }\n        }\n    }\n\n    void RobotPool::_reset_robot(const std::shared_ptr<Robot>& robot)\n    {\n        robot->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

  • #include <functional>
  • #include <memory>
  • #include <mutex>
  • #include <vector>
  • #include <robot_dart/robot.hpp>
"},{"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\n#include <functional>\n#include <memory>\n#include <mutex>\n#include <vector>\n\n#include <robot_dart/robot.hpp>\n\nnamespace robot_dart {\n    class RobotPool {\n    public:\n        using robot_creator_t = std::function<std::shared_ptr<Robot>()>;\n\n        RobotPool(const robot_creator_t& robot_creator, size_t pool_size = 32, bool verbose = true);\n        virtual ~RobotPool() {}\n\n        RobotPool(const RobotPool&) = delete;\n        void operator=(const RobotPool&) = delete;\n\n        virtual std::shared_ptr<Robot> get_robot(const std::string& name = \"robot\");\n        virtual void free_robot(const std::shared_ptr<Robot>& robot);\n\n        const std::string& model_filename() const { return _model_filename; }\n\n    protected:\n        robot_creator_t _robot_creator;\n        size_t _pool_size;\n        bool _verbose;\n        std::vector<dart::dynamics::SkeletonPtr> _skeletons;\n        std::vector<bool> _free;\n        std::mutex _skeleton_mutex;\n        std::string _model_filename;\n\n        virtual void _reset_robot(const std::shared_ptr<Robot>& robot);\n    };\n} // namespace robot_dart\n\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

  • #include <robot_dart/scheduler.hpp>
"},{"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>\n\nnamespace robot_dart {\n    bool Scheduler::schedule(int frequency)\n    {\n        if (_max_frequency == -1) {\n            _start_time = clock_t::now();\n            _last_iteration_time = _start_time;\n        }\n\n        _max_frequency = std::max(_max_frequency, frequency);\n        double period = std::round((1. / frequency) / _dt);\n\n        ROBOT_DART_EXCEPTION_INTERNAL_ASSERT(\n            period >= 1. && \"Time-step is too big for required frequency.\");\n\n        if (_current_step % int(period) == 0)\n            return true;\n\n        return false;\n    }\n\n    void Scheduler::reset(double dt, bool sync, double current_time, double real_time)\n    {\n        ROBOT_DART_EXCEPTION_INTERNAL_ASSERT(dt > 0. && \"Time-step needs to be bigger than zero.\");\n\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\n        _dt = dt;\n        _sync = sync;\n    }\n\n    double Scheduler::step()\n    {\n        _current_time += _dt;\n        _current_step += 1;\n\n        auto 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;\n        std::chrono::duration<double, std::micro> real = end - _start_time;\n        if (_sync) {\n            auto expected = std::chrono::microseconds(int(_current_time * 1e6));\n            std::chrono::duration<double, std::micro> adjust = expected - real;\n            if (adjust.count() > 0)\n                std::this_thread::sleep_for(adjust);\n        }\n\n        _real_time = real.count() * 1e-6;\n        return _real_start_time + _real_time;\n    }\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

  • #include <robot_dart/utils.hpp>
  • #include <chrono>
  • #include <thread>
"},{"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\n#include <robot_dart/utils.hpp>\n\n#include <chrono>\n#include <thread>\n\nnamespace robot_dart {\n    class Scheduler {\n    protected:\n        using clock_t = std::chrono::high_resolution_clock;\n\n    public:\n        Scheduler(double dt, bool sync = false) : _dt(dt), _sync(sync)\n        {\n            ROBOT_DART_EXCEPTION_INTERNAL_ASSERT(_dt > 0. && \"Time-step needs to be bigger than zero.\");\n        }\n\n        bool operator()(int frequency) { return schedule(frequency); };\n        bool schedule(int frequency);\n\n        double step();\n\n        void reset(double dt, bool sync = false, double current_time = 0., double real_time = 0.);\n\n        void set_sync(bool enable) { _sync = enable; }\n        bool sync() const { return _sync; }\n\n        double current_time() const { return _simu_start_time + _current_time; }\n        double next_time() const { return _simu_start_time + _current_time + _dt; }\n        double real_time() const { return _real_start_time + _real_time; }\n        double dt() const { return _dt; }\n        // 0.8x => we are simulating at 80% of real time\n        double real_time_factor() const { return _dt / it_duration(); }\n        // time for a single iteration (wall-clock)\n        double it_duration() const { return _average_it_duration * 1e-6; }\n        // time of the last iteration (wall-clock)\n        double last_it_duration() const { return _it_duration * 1e-6; }\n\n    protected:\n        double _current_time = 0., _simu_start_time = 0., _real_time = 0., _real_start_time = 0., _it_duration = 0.;\n        double _average_it_duration = 0.;\n        double _dt;\n        int _current_step = 0;\n        bool _sync;\n        int _max_frequency = -1;\n        clock_t::time_point _start_time;\n        clock_t::time_point _last_iteration_time;\n    };\n} // namespace robot_dart\n\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

  • #include <exception>
  • #include <iostream>
  • #include <robot_dart/utils_headers_external.hpp>
"},{"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 (\n    condition,\n    message,\n    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
"},{"location":"api/utils_8hpp/#define-robot_dart_exception_assert","title":"define ROBOT_DART_EXCEPTION_ASSERT","text":"
#define ROBOT_DART_EXCEPTION_ASSERT (\n    condition,\n    message\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 (\n    condition\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 (\n    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
"},{"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 (\n    var\n) (void)(var)\n
"},{"location":"api/utils_8hpp/#define-robot_dart_warning","title":"define ROBOT_DART_WARNING","text":"
#define ROBOT_DART_WARNING (\n    condition,\n    message\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\n#include <exception>\n#include <iostream>\n\n#include <robot_dart/utils_headers_external.hpp>\n\n#ifndef ROBOT_DART_SHOW_WARNINGS\n#define ROBOT_DART_SHOW_WARNINGS true\n#endif\n\n#ifndef M_PIf\n#define M_PIf static_cast<float>(M_PI)\n#endif\n\nnamespace robot_dart {\n\n    inline Eigen::VectorXd make_vector(std::initializer_list<double> args)\n    {\n        return Eigen::VectorXd::Map(args.begin(), args.size());\n    }\n\n    inline Eigen::Isometry3d make_tf(const Eigen::Matrix3d& R, const Eigen::Vector3d& t)\n    {\n        Eigen::Isometry3d tf = Eigen::Isometry3d::Identity();\n        tf.linear().matrix() = R;\n        tf.translation() = t;\n\n        return tf;\n    }\n\n    inline Eigen::Isometry3d make_tf(const Eigen::Matrix3d& R)\n    {\n        Eigen::Isometry3d tf = Eigen::Isometry3d::Identity();\n        tf.linear().matrix() = R;\n\n        return tf;\n    }\n\n    inline Eigen::Isometry3d make_tf(const Eigen::Vector3d& t)\n    {\n        Eigen::Isometry3d tf = Eigen::Isometry3d::Identity();\n        tf.translation() = t;\n\n        return tf;\n    }\n\n    inline Eigen::Isometry3d make_tf(std::initializer_list<double> args)\n    {\n        Eigen::Isometry3d tf = Eigen::Isometry3d::Identity();\n        tf.translation() = make_vector(args);\n\n        return tf;\n    }\n\n    class Assertion : public std::exception {\n    public:\n        Assertion(const std::string& msg = \"\") : _msg(_make_message(msg)) {}\n\n        const char* what() const throw()\n        {\n            return _msg.c_str();\n        }\n\n    private:\n        std::string _msg;\n\n        std::string _make_message(const std::string& msg) const\n        {\n            std::string message = \"robot_dart assertion failed\";\n            if (msg != \"\")\n                message += \": '\" + msg + \"'\";\n            return message;\n        }\n    };\n} // namespace robot_dart\n\n#define ROBOT_DART_UNUSED_VARIABLE(var) (void)(var)\n\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\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\n#define ROBOT_DART_EXCEPTION_ASSERT(condition, message) \\\n    do {                                                \\\n        if (!(condition)) {                             \\\n            throw robot_dart::Assertion(message);       \\\n        }                                               \\\n    } while (false)\n\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\n#define ROBOT_DART_EXCEPTION_INTERNAL_ASSERT(condition) \\\n    do {                                                \\\n        if (!(condition)) {                             \\\n            throw robot_dart::Assertion(#condition);    \\\n        }                                               \\\n    } while (false)\n\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

  • #include <dart/config.hpp>
  • #include <dart/collision/CollisionFilter.hpp>
  • #include <dart/collision/CollisionObject.hpp>
  • #include <dart/collision/dart/DARTCollisionDetector.hpp>
  • #include <dart/collision/fcl/FCLCollisionDetector.hpp>
  • #include <dart/constraint/ConstraintSolver.hpp>

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\n#pragma GCC system_header\n\n#include <dart/config.hpp>\n\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\n#if (HAVE_BULLET == 1)\n#include <dart/collision/bullet/BulletCollisionDetector.hpp>\n#endif\n\n#if (HAVE_ODE == 1)\n#include <dart/collision/ode/OdeCollisionDetector.hpp>\n#endif\n\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

  • #include <dart/dynamics/BallJoint.hpp>
  • #include <dart/dynamics/BodyNode.hpp>
  • #include <dart/dynamics/BoxShape.hpp>
  • #include <dart/dynamics/DegreeOfFreedom.hpp>
  • #include <dart/dynamics/EllipsoidShape.hpp>
  • #include <dart/dynamics/EulerJoint.hpp>
  • #include <dart/dynamics/FreeJoint.hpp>
  • #include <dart/dynamics/MeshShape.hpp>
  • #include <dart/dynamics/RevoluteJoint.hpp>
  • #include <dart/dynamics/ShapeNode.hpp>
  • #include <dart/dynamics/SoftBodyNode.hpp>
  • #include <dart/dynamics/SoftMeshShape.hpp>
  • #include <dart/dynamics/WeldJoint.hpp>

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\n#pragma GCC system_header\n\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\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

  • #include <dart/config.hpp>
  • #include <dart/utils/SkelParser.hpp>
  • #include <dart/utils/sdf/SdfParser.hpp>
  • #include <dart/utils/urdf/urdf.hpp>
"},{"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\n#pragma GCC system_header\n\n#include <dart/config.hpp>\n\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\n// namespace alias for compatibility\nnamespace dart {\n    namespace io = utils;\n}\n#endif\n\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

  • #include <Eigen/Core>
  • #include <Eigen/Geometry>
  • #include <dart/config.hpp>
  • #include <dart/dynamics/MeshShape.hpp>
  • #include <dart/dynamics/Skeleton.hpp>
  • #include <dart/simulation/World.hpp>

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\n#pragma GCC system_header\n\n#include <Eigen/Core>\n#include <Eigen/Geometry>\n\n#include <dart/config.hpp>\n#include <dart/dynamics/MeshShape.hpp>\n#include <dart/dynamics/Skeleton.hpp>\n#include <dart/simulation/World.hpp>\n\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

  • #include <robot_dart/utils_headers_external.hpp>
  • #include <Magnum/DartIntegration/World.h>

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\n#pragma GCC system_header\n\n#include <robot_dart/utils_headers_external.hpp>\n\n#include <Magnum/DartIntegration/World.h>\n\n#endif\n
"},{"location":"api/namespaces/","title":"Namespace List","text":"

Here is a list of all namespaces with brief descriptions:

  • namespace Magnum
    • namespace GL
    • namespace Platform
    • namespace SceneGraph
    • namespace Shaders
      • namespace Implementation
  • namespace TinyProcessLib
  • namespace dart
    • namespace collision
    • namespace dynamics
  • namespace robot_dart
    • namespace collision_filter
    • namespace control
    • namespace detail
    • namespace gui
      • namespace magnum
        • namespace gs
        • namespace sensor
    • namespace robots
    • namespace sensor
    • namespace simu
  • namespace gs
  • namespace std
"},{"location":"api/classes/","title":"Class Index","text":""},{"location":"api/classes/#a","title":"a","text":"
  • A1 (robot_dart::robots)
  • Arm (robot_dart::robots)
  • Assertion (robot_dart)
"},{"location":"api/classes/#b","title":"b","text":"
  • Base (robot_dart::gui)
  • BaseApplication (robot_dart::gui::magnum)
  • BaseGraphics (robot_dart::gui::magnum)
  • BitmaskContactFilter (robot_dart::collision_filter)
"},{"location":"api/classes/#c","title":"c","text":"
  • Camera (robot_dart::gui::magnum::gs)
  • Camera (robot_dart::gui::magnum::sensor)
  • CubeMap (robot_dart::gui::magnum::gs)
  • CubeMapColor (robot_dart::gui::magnum::gs)
  • CubeMapShadowedColorObject (robot_dart::gui::magnum)
  • CubeMapShadowedObject (robot_dart::gui::magnum)
"},{"location":"api/classes/#d","title":"d","text":"
  • DebugDrawData (robot_dart::gui::magnum)
  • DepthImage (robot_dart::gui)
  • DrawableObject (robot_dart::gui::magnum)
"},{"location":"api/classes/#f","title":"f","text":"
  • ForceTorque (robot_dart::sensor)
  • Franka (robot_dart::robots)
"},{"location":"api/classes/#g","title":"g","text":"
  • GlfwApplication (robot_dart::gui::magnum)
  • GlobalData (robot_dart::gui::magnum)
  • Graphics (robot_dart::gui::magnum)
  • GraphicsConfiguration (robot_dart::gui::magnum)
  • GrayscaleImage (robot_dart::gui)
  • GUIData (robot_dart::simu)
"},{"location":"api/classes/#h","title":"h","text":"
  • Hexapod (robot_dart::robots)
"},{"location":"api/classes/#i","title":"i","text":"
  • ICub (robot_dart::robots)
  • Iiwa (robot_dart::robots)
  • Image (robot_dart::gui)
  • IMU (robot_dart::sensor)
  • IMUConfig (robot_dart::sensor)
"},{"location":"api/classes/#l","title":"l","text":"
  • Light (robot_dart::gui::magnum::gs)
"},{"location":"api/classes/#m","title":"m","text":"
  • Masks (robot_dart::collision_filter::BitmaskContactFilter)
  • Material (robot_dart::gui::magnum::gs)
"},{"location":"api/classes/#o","title":"o","text":"
  • ObjectStruct (robot_dart::gui::magnum)
"},{"location":"api/classes/#p","title":"p","text":"
  • PDControl (robot_dart::control)
  • Pendulum (robot_dart::robots)
  • PhongMultiLight (robot_dart::gui::magnum::gs)
  • PolicyControl (robot_dart::control)
"},{"location":"api/classes/#r","title":"r","text":"
  • Robot (robot_dart)
  • RobotControl (robot_dart::control)
  • RobotDARTSimu (robot_dart)
  • RobotData
  • RobotPool (robot_dart)
"},{"location":"api/classes/#s","title":"s","text":"
  • Scheduler (robot_dart)
  • Sensor (robot_dart::sensor)
  • ShadowData (robot_dart::gui::magnum)
  • ShadowedColorObject (robot_dart::gui::magnum)
  • ShadowedObject (robot_dart::gui::magnum)
  • ShadowMap (robot_dart::gui::magnum::gs)
  • ShadowMapColor (robot_dart::gui::magnum::gs)
  • SimpleControl (robot_dart::control)
"},{"location":"api/classes/#t","title":"t","text":"
  • Talos (robot_dart::robots)
  • TalosFastCollision (robot_dart::robots)
  • TalosLight (robot_dart::robots)
  • TextData (robot_dart::simu)
  • Tiago (robot_dart::robots)
  • Torque (robot_dart::sensor)
"},{"location":"api/classes/#u","title":"u","text":"
  • Ur3e (robot_dart::robots)
  • Ur3eHand (robot_dart::robots)
"},{"location":"api/classes/#v","title":"v","text":"
  • Vx300 (robot_dart::robots)
"},{"location":"api/classes/#w","title":"w","text":"
  • WindowlessGLApplication (robot_dart::gui::magnum)
  • WindowlessGraphics (robot_dart::gui::magnum)
"},{"location":"api/hierarchy/","title":"Class Hierarchy","text":"

This inheritance list is sorted roughly, but not completely, alphabetically:

  • class robot_dart::RobotDARTSimu
  • class robot_dart::RobotPool
  • class robot_dart::Scheduler
  • class robot_dart::control::RobotControl
    • class robot_dart::control::PDControl
    • class robot_dart::control::PolicyControl
    • class robot_dart::control::SimpleControl
  • class robot_dart::gui::Base
    • class robot_dart::gui::magnum::BaseGraphics
    • class robot_dart::gui::magnum::BaseGraphics
    • class robot_dart::gui::magnum::BaseGraphics
  • class robot_dart::gui::magnum::BaseApplication
    • class robot_dart::gui::magnum::GlfwApplication
    • class robot_dart::gui::magnum::WindowlessGLApplication
  • class robot_dart::gui::magnum::Light
  • class robot_dart::gui::magnum::Material
  • class robot_dart::sensor::Sensor
    • class robot_dart::gui::magnum::sensor::Camera
    • class robot_dart::sensor::ForceTorque
    • class robot_dart::sensor::IMU
    • class robot_dart::sensor::Torque
  • struct robot_dart::collision_filter::BitmaskContactFilter::Masks
  • struct robot_dart::gui::DepthImage
  • struct robot_dart::gui::GrayscaleImage
  • struct robot_dart::gui::Image
  • struct robot_dart::gui::magnum::DebugDrawData
  • struct robot_dart::gui::magnum::GlobalData
  • struct robot_dart::gui::magnum::GraphicsConfiguration
  • struct robot_dart::gui::magnum::ObjectStruct
  • struct robot_dart::gui::magnum::ShadowData
  • struct robot_dart::sensor::IMUConfig
  • struct robot_dart::simu::GUIData
  • struct robot_dart::simu::TextData
  • struct robot_dart::simu::GUIData::RobotData
  • class std::exception
    • class robot_dart::Assertion
  • class std::enable_shared_from_this< Robot >
    • class robot_dart::Robot
      • class robot_dart::robots::A1
      • class robot_dart::robots::Arm
      • class robot_dart::robots::Franka
      • class robot_dart::robots::Hexapod
      • class robot_dart::robots::ICub
      • class robot_dart::robots::Iiwa
      • class robot_dart::robots::Pendulum
      • class robot_dart::robots::Talos datasheet: https://pal-robotics.com/wp-content/uploads/2019/07/Datasheet_TALOS.pdf __
        • class robot_dart::robots::TalosFastCollision
        • class robot_dart::robots::TalosLight
      • class robot_dart::robots::Tiago datasheet: https://pal-robotics.com/wp-content/uploads/2021/07/Datasheet-complete_TIAGo-2021.pdf __
      • class robot_dart::robots::Ur3e
        • class robot_dart::robots::Ur3eHand
      • class robot_dart::robots::Vx300
    • class robot_dart::Robot
      • class robot_dart::robots::A1
      • class robot_dart::robots::Arm
      • class robot_dart::robots::Franka
      • class robot_dart::robots::Hexapod
      • class robot_dart::robots::ICub
      • class robot_dart::robots::Iiwa
      • class robot_dart::robots::Pendulum
      • class robot_dart::robots::Talos datasheet: https://pal-robotics.com/wp-content/uploads/2019/07/Datasheet_TALOS.pdf __
        • class robot_dart::robots::TalosFastCollision
        • class robot_dart::robots::TalosLight
      • class robot_dart::robots::Tiago datasheet: https://pal-robotics.com/wp-content/uploads/2021/07/Datasheet-complete_TIAGo-2021.pdf __
      • class robot_dart::robots::Ur3e
        • class robot_dart::robots::Ur3eHand
      • class robot_dart::robots::Vx300
    • class robot_dart::Robot
      • class robot_dart::robots::A1
      • class robot_dart::robots::Arm
      • class robot_dart::robots::Franka
      • class robot_dart::robots::Hexapod
      • class robot_dart::robots::ICub
      • class robot_dart::robots::Iiwa
      • class robot_dart::robots::Pendulum
      • class robot_dart::robots::Talos datasheet: https://pal-robotics.com/wp-content/uploads/2019/07/Datasheet_TALOS.pdf __
        • class robot_dart::robots::TalosFastCollision
        • class robot_dart::robots::TalosLight
      • class robot_dart::robots::Tiago datasheet: https://pal-robotics.com/wp-content/uploads/2021/07/Datasheet-complete_TIAGo-2021.pdf __
      • class robot_dart::robots::Ur3e
        • class robot_dart::robots::Ur3eHand
      • class robot_dart::robots::Vx300
    • class robot_dart::Robot
      • class robot_dart::robots::A1
      • class robot_dart::robots::Arm
      • class robot_dart::robots::Franka
      • class robot_dart::robots::Hexapod
      • class robot_dart::robots::ICub
      • class robot_dart::robots::Iiwa
      • class robot_dart::robots::Pendulum
      • class robot_dart::robots::Talos datasheet: https://pal-robotics.com/wp-content/uploads/2019/07/Datasheet_TALOS.pdf __
        • class robot_dart::robots::TalosFastCollision
        • class robot_dart::robots::TalosLight
      • class robot_dart::robots::Tiago datasheet: https://pal-robotics.com/wp-content/uploads/2021/07/Datasheet-complete_TIAGo-2021.pdf __
      • class robot_dart::robots::Ur3e
        • class robot_dart::robots::Ur3eHand
      • class robot_dart::robots::Vx300
    • class robot_dart::Robot
      • class robot_dart::robots::A1
      • class robot_dart::robots::Arm
      • class robot_dart::robots::Franka
      • class robot_dart::robots::Hexapod
      • class robot_dart::robots::ICub
      • class robot_dart::robots::Iiwa
      • class robot_dart::robots::Pendulum
      • class robot_dart::robots::Talos datasheet: https://pal-robotics.com/wp-content/uploads/2019/07/Datasheet_TALOS.pdf __
        • class robot_dart::robots::TalosFastCollision
        • class robot_dart::robots::TalosLight
      • class robot_dart::robots::Tiago datasheet: https://pal-robotics.com/wp-content/uploads/2021/07/Datasheet-complete_TIAGo-2021.pdf __
      • class robot_dart::robots::Ur3e
        • class robot_dart::robots::Ur3eHand
      • class robot_dart::robots::Vx300
    • class robot_dart::Robot
      • class robot_dart::robots::A1
      • class robot_dart::robots::Arm
      • class robot_dart::robots::Franka
      • class robot_dart::robots::Hexapod
      • class robot_dart::robots::ICub
      • class robot_dart::robots::Iiwa
      • class robot_dart::robots::Pendulum
      • class robot_dart::robots::Talos datasheet: https://pal-robotics.com/wp-content/uploads/2019/07/Datasheet_TALOS.pdf __
        • class robot_dart::robots::TalosFastCollision
        • class robot_dart::robots::TalosLight
      • class robot_dart::robots::Tiago datasheet: https://pal-robotics.com/wp-content/uploads/2021/07/Datasheet-complete_TIAGo-2021.pdf __
      • class robot_dart::robots::Ur3e
        • class robot_dart::robots::Ur3eHand
      • class robot_dart::robots::Vx300
    • class robot_dart::Robot
      • class robot_dart::robots::A1
      • class robot_dart::robots::Arm
      • class robot_dart::robots::Franka
      • class robot_dart::robots::Hexapod
      • class robot_dart::robots::ICub
      • class robot_dart::robots::Iiwa
      • class robot_dart::robots::Pendulum
      • class robot_dart::robots::Talos datasheet: https://pal-robotics.com/wp-content/uploads/2019/07/Datasheet_TALOS.pdf __
        • class robot_dart::robots::TalosFastCollision
        • class robot_dart::robots::TalosLight
      • class robot_dart::robots::Tiago datasheet: https://pal-robotics.com/wp-content/uploads/2021/07/Datasheet-complete_TIAGo-2021.pdf __
      • class robot_dart::robots::Ur3e
        • class robot_dart::robots::Ur3eHand
      • class robot_dart::robots::Vx300
    • class robot_dart::Robot
      • class robot_dart::robots::A1
      • class robot_dart::robots::Arm
      • class robot_dart::robots::Franka
      • class robot_dart::robots::Hexapod
      • class robot_dart::robots::ICub
      • class robot_dart::robots::Iiwa
      • class robot_dart::robots::Pendulum
      • class robot_dart::robots::Talos datasheet: https://pal-robotics.com/wp-content/uploads/2019/07/Datasheet_TALOS.pdf __
        • class robot_dart::robots::TalosFastCollision
        • class robot_dart::robots::TalosLight
      • class robot_dart::robots::Tiago datasheet: https://pal-robotics.com/wp-content/uploads/2021/07/Datasheet-complete_TIAGo-2021.pdf __
      • class robot_dart::robots::Ur3e
        • class robot_dart::robots::Ur3eHand
      • class robot_dart::robots::Vx300
    • class robot_dart::Robot
      • class robot_dart::robots::A1
      • class robot_dart::robots::Arm
      • class robot_dart::robots::Franka
      • class robot_dart::robots::Hexapod
      • class robot_dart::robots::ICub
      • class robot_dart::robots::Iiwa
      • class robot_dart::robots::Pendulum
      • class robot_dart::robots::Talos datasheet: https://pal-robotics.com/wp-content/uploads/2019/07/Datasheet_TALOS.pdf __
        • class robot_dart::robots::TalosFastCollision
        • class robot_dart::robots::TalosLight
      • class robot_dart::robots::Tiago datasheet: https://pal-robotics.com/wp-content/uploads/2021/07/Datasheet-complete_TIAGo-2021.pdf __
      • class robot_dart::robots::Ur3e
        • class robot_dart::robots::Ur3eHand
      • class robot_dart::robots::Vx300
    • class robot_dart::Robot
      • class robot_dart::robots::A1
      • class robot_dart::robots::Arm
      • class robot_dart::robots::Franka
      • class robot_dart::robots::Hexapod
      • class robot_dart::robots::ICub
      • class robot_dart::robots::Iiwa
      • class robot_dart::robots::Pendulum
      • class robot_dart::robots::Talos datasheet: https://pal-robotics.com/wp-content/uploads/2019/07/Datasheet_TALOS.pdf __
        • class robot_dart::robots::TalosFastCollision
        • class robot_dart::robots::TalosLight
      • class robot_dart::robots::Tiago datasheet: https://pal-robotics.com/wp-content/uploads/2021/07/Datasheet-complete_TIAGo-2021.pdf __
      • class robot_dart::robots::Ur3e
        • class robot_dart::robots::Ur3eHand
      • class robot_dart::robots::Vx300
    • class robot_dart::Robot
      • class robot_dart::robots::A1
      • class robot_dart::robots::Arm
      • class robot_dart::robots::Franka
      • class robot_dart::robots::Hexapod
      • class robot_dart::robots::ICub
      • class robot_dart::robots::Iiwa
      • class robot_dart::robots::Pendulum
      • class robot_dart::robots::Talos datasheet: https://pal-robotics.com/wp-content/uploads/2019/07/Datasheet_TALOS.pdf __
        • class robot_dart::robots::TalosFastCollision
        • class robot_dart::robots::TalosLight
      • class robot_dart::robots::Tiago datasheet: https://pal-robotics.com/wp-content/uploads/2021/07/Datasheet-complete_TIAGo-2021.pdf __
      • class robot_dart::robots::Ur3e
        • class robot_dart::robots::Ur3eHand
      • class robot_dart::robots::Vx300
    • class robot_dart::Robot
      • class robot_dart::robots::A1
      • class robot_dart::robots::Arm
      • class robot_dart::robots::Franka
      • class robot_dart::robots::Hexapod
      • class robot_dart::robots::ICub
      • class robot_dart::robots::Iiwa
      • class robot_dart::robots::Pendulum
      • class robot_dart::robots::Talos datasheet: https://pal-robotics.com/wp-content/uploads/2019/07/Datasheet_TALOS.pdf __
        • class robot_dart::robots::TalosFastCollision
        • class robot_dart::robots::TalosLight
      • class robot_dart::robots::Tiago datasheet: https://pal-robotics.com/wp-content/uploads/2021/07/Datasheet-complete_TIAGo-2021.pdf __
      • class robot_dart::robots::Ur3e
        • class robot_dart::robots::Ur3eHand
      • class robot_dart::robots::Vx300
    • class robot_dart::Robot
      • class robot_dart::robots::A1
      • class robot_dart::robots::Arm
      • class robot_dart::robots::Franka
      • class robot_dart::robots::Hexapod
      • class robot_dart::robots::ICub
      • class robot_dart::robots::Iiwa
      • class robot_dart::robots::Pendulum
      • class robot_dart::robots::Talos datasheet: https://pal-robotics.com/wp-content/uploads/2019/07/Datasheet_TALOS.pdf __
        • class robot_dart::robots::TalosFastCollision
        • class robot_dart::robots::TalosLight
      • class robot_dart::robots::Tiago datasheet: https://pal-robotics.com/wp-content/uploads/2021/07/Datasheet-complete_TIAGo-2021.pdf __
      • class robot_dart::robots::Ur3e
        • class robot_dart::robots::Ur3eHand
      • class robot_dart::robots::Vx300
    • class robot_dart::Robot
      • class robot_dart::robots::A1
      • class robot_dart::robots::Arm
      • class robot_dart::robots::Franka
      • class robot_dart::robots::Hexapod
      • class robot_dart::robots::ICub
      • class robot_dart::robots::Iiwa
      • class robot_dart::robots::Pendulum
      • class robot_dart::robots::Talos datasheet: https://pal-robotics.com/wp-content/uploads/2019/07/Datasheet_TALOS.pdf __
        • class robot_dart::robots::TalosFastCollision
        • class robot_dart::robots::TalosLight
      • class robot_dart::robots::Tiago datasheet: https://pal-robotics.com/wp-content/uploads/2021/07/Datasheet-complete_TIAGo-2021.pdf __
      • class robot_dart::robots::Ur3e
        • class robot_dart::robots::Ur3eHand
      • class robot_dart::robots::Vx300
    • class robot_dart::Robot
      • class robot_dart::robots::A1
      • class robot_dart::robots::Arm
      • class robot_dart::robots::Franka
      • class robot_dart::robots::Hexapod
      • class robot_dart::robots::ICub
      • class robot_dart::robots::Iiwa
      • class robot_dart::robots::Pendulum
      • class robot_dart::robots::Talos datasheet: https://pal-robotics.com/wp-content/uploads/2019/07/Datasheet_TALOS.pdf __
        • class robot_dart::robots::TalosFastCollision
        • class robot_dart::robots::TalosLight
      • class robot_dart::robots::Tiago datasheet: https://pal-robotics.com/wp-content/uploads/2021/07/Datasheet-complete_TIAGo-2021.pdf __
      • class robot_dart::robots::Ur3e
        • class robot_dart::robots::Ur3eHand
      • class robot_dart::robots::Vx300
  • class dart::BodyNodeCollisionFilter
    • class robot_dart::collision_filter::BitmaskContactFilter
  • class Object3D
    • class robot_dart::gui::magnum::CubeMapShadowedColorObject
    • class robot_dart::gui::magnum::CubeMapShadowedObject
    • class robot_dart::gui::magnum::DrawableObject
    • class robot_dart::gui::magnum::ShadowedColorObject
    • class robot_dart::gui::magnum::ShadowedObject
    • class robot_dart::gui::magnum::Camera
  • class Magnum::SceneGraph::Drawable3D
    • class robot_dart::gui::magnum::CubeMapShadowedColorObject
    • class robot_dart::gui::magnum::CubeMapShadowedObject
    • class robot_dart::gui::magnum::DrawableObject
    • class robot_dart::gui::magnum::ShadowedColorObject
    • class robot_dart::gui::magnum::ShadowedObject
  • class Magnum::Platform::Application
    • class robot_dart::gui::magnum::GlfwApplication
  • class Magnum::Platform::WindowlessApplication
    • class robot_dart::gui::magnum::WindowlessGLApplication
  • class Magnum::GL::AbstractShaderProgram
    • class robot_dart::gui::magnum::CubeMap
    • class robot_dart::gui::magnum::CubeMapColor
    • class robot_dart::gui::magnum::PhongMultiLight
    • class robot_dart::gui::magnum::ShadowMap
    • class robot_dart::gui::magnum::ShadowMapColor
"},{"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":"
  • Assertion (robot_dart::Assertion)
  • acceleration_lower_limits (robot_dart::Robot)
  • acceleration_upper_limits (robot_dart::Robot)
  • accelerations (robot_dart::Robot)
  • active_controllers (robot_dart::Robot)
  • actuator_type (robot_dart::Robot)
  • actuator_types (robot_dart::Robot)
  • add_body_mass (robot_dart::Robot)
  • add_controller (robot_dart::Robot)
  • add_external_force (robot_dart::Robot)
  • add_external_torque (robot_dart::Robot)
  • adjacent_colliding (robot_dart::Robot)
  • aug_mass_matrix (robot_dart::Robot)
  • add_checkerboard_floor (robot_dart::RobotDARTSimu)
  • add_floor (robot_dart::RobotDARTSimu)
  • add_robot (robot_dart::RobotDARTSimu)
  • add_sensor (robot_dart::RobotDARTSimu)
  • add_text (robot_dart::RobotDARTSimu, robot_dart::simu::GUIData)
  • add_visual_robot (robot_dart::RobotDARTSimu)
  • add_to_map (robot_dart::collision_filter::BitmaskContactFilter)
  • activate (robot_dart::control::RobotControl, robot_dart::sensor::Sensor)
  • active (robot_dart::control::RobotControl, robot_dart::sensor::Sensor)
  • add_light (robot_dart::gui::magnum::BaseApplication, robot_dart::gui::magnum::BaseGraphics)
  • attach_camera (robot_dart::gui::magnum::BaseApplication)
  • axes_mesh (robot_dart::gui::magnum::DebugDrawData)
  • axes_shader (robot_dart::gui::magnum::DebugDrawData)
  • attenuation (robot_dart::gui::magnum::Light)
  • ambient_color (robot_dart::gui::magnum::Material)
  • ambient_texture (robot_dart::gui::magnum::Material)
  • attach_to_body (robot_dart::gui::magnum::sensor::Camera, robot_dart::sensor::ForceTorque, robot_dart::sensor::Sensor, robot_dart::sensor::Torque)
  • attach_to_joint (robot_dart::gui::magnum::sensor::Camera, robot_dart::sensor::IMU, robot_dart::sensor::Sensor)
  • A1 (robot_dart::robots::A1)
  • Arm (robot_dart::robots::Arm)
  • angular_position (robot_dart::sensor::IMU)
  • angular_position_vec (robot_dart::sensor::IMU)
  • angular_velocity (robot_dart::sensor::IMU)
  • accel_bias (robot_dart::sensor::IMUConfig)
  • attached_to (robot_dart::sensor::Sensor)
  • alignment (robot_dart::simu::TextData)
"},{"location":"api/class_members/#b","title":"b","text":"
  • base_pose (robot_dart::Robot)
  • base_pose_vec (robot_dart::Robot)
  • body_acceleration (robot_dart::Robot)
  • body_index (robot_dart::Robot)
  • body_mass (robot_dart::Robot)
  • body_name (robot_dart::Robot)
  • body_names (robot_dart::Robot)
  • body_node (robot_dart::Robot)
  • body_pose (robot_dart::Robot)
  • body_pose_vec (robot_dart::Robot)
  • body_velocity (robot_dart::Robot)
  • Base (robot_dart::gui::Base)
  • BaseApplication (robot_dart::gui::magnum::BaseApplication)
  • BaseGraphics (robot_dart::gui::magnum::BaseGraphics)
  • background_mesh (robot_dart::gui::magnum::DebugDrawData)
  • background_shader (robot_dart::gui::magnum::DebugDrawData)
  • bg_color (robot_dart::gui::magnum::GraphicsConfiguration)
  • bind_cube_map_texture (robot_dart::gui::magnum::CubeMapColor, robot_dart::gui::magnum::PhongMultiLight)
  • bind_cube_map_color_texture (robot_dart::gui::magnum::PhongMultiLight)
  • bind_shadow_color_texture (robot_dart::gui::magnum::PhongMultiLight)
  • bind_shadow_texture (robot_dart::gui::magnum::PhongMultiLight)
  • body (robot_dart::sensor::IMUConfig)
  • background_color (robot_dart::simu::TextData)
"},{"location":"api/class_members/#c","title":"c","text":"
  • cast_shadows (robot_dart::Robot, robot_dart::simu::GUIData)
  • clear_controllers (robot_dart::Robot)
  • clear_external_forces (robot_dart::Robot)
  • clear_internal_forces (robot_dart::Robot)
  • clone (robot_dart::Robot, robot_dart::control::PDControl, robot_dart::control::PolicyControl, robot_dart::control::RobotControl, robot_dart::control::SimpleControl)
  • clone_ghost (robot_dart::Robot)
  • com (robot_dart::Robot)
  • com_acceleration (robot_dart::Robot)
  • com_jacobian (robot_dart::Robot)
  • com_jacobian_deriv (robot_dart::Robot)
  • com_velocity (robot_dart::Robot)
  • commands (robot_dart::Robot)
  • constraint_forces (robot_dart::Robot)
  • controller (robot_dart::Robot)
  • controllers (robot_dart::Robot)
  • coriolis_forces (robot_dart::Robot)
  • coriolis_gravity_forces (robot_dart::Robot)
  • coulomb_coeffs (robot_dart::Robot)
  • create_box (robot_dart::Robot)
  • create_ellipsoid (robot_dart::Robot)
  • clear_robots (robot_dart::RobotDARTSimu)
  • clear_sensors (robot_dart::RobotDARTSimu)
  • collision_category (robot_dart::RobotDARTSimu)
  • collision_detector (robot_dart::RobotDARTSimu)
  • collision_mask (robot_dart::RobotDARTSimu, robot_dart::collision_filter::BitmaskContactFilter::Masks)
  • collision_masks (robot_dart::RobotDARTSimu)
  • control_freq (robot_dart::RobotDARTSimu)
  • clock_t (robot_dart::Scheduler)
  • current_time (robot_dart::Scheduler)
  • clear_all (robot_dart::collision_filter::BitmaskContactFilter)
  • category_mask (robot_dart::collision_filter::BitmaskContactFilter::Masks)
  • calculate (robot_dart::control::PDControl, robot_dart::control::PolicyControl, robot_dart::control::RobotControl, robot_dart::control::SimpleControl, robot_dart::gui::magnum::sensor::Camera, robot_dart::sensor::ForceTorque, robot_dart::sensor::IMU, robot_dart::sensor::Sensor, robot_dart::sensor::Torque)
  • configure (robot_dart::control::PDControl, robot_dart::control::PolicyControl, robot_dart::control::RobotControl, robot_dart::control::SimpleControl)
  • controllable_dofs (robot_dart::control::RobotControl)
  • channels (robot_dart::gui::Image)
  • camera (robot_dart::gui::magnum::BaseApplication, robot_dart::gui::magnum::BaseGraphics, robot_dart::gui::magnum::Camera, robot_dart::gui::magnum::sensor::Camera)
  • clear_lights (robot_dart::gui::magnum::BaseApplication, robot_dart::gui::magnum::BaseGraphics)
  • camera_extrinsic_matrix (robot_dart::gui::magnum::BaseGraphics, robot_dart::gui::magnum::sensor::Camera)
  • camera_intrinsic_matrix (robot_dart::gui::magnum::BaseGraphics, robot_dart::gui::magnum::sensor::Camera)
  • CubeMapShadowedColorObject (robot_dart::gui::magnum::CubeMapShadowedColorObject)
  • CubeMapShadowedObject (robot_dart::gui::magnum::CubeMapShadowedObject)
  • cache (robot_dart::gui::magnum::DebugDrawData)
  • cubemapped (robot_dart::gui::magnum::ObjectStruct)
  • cubemapped_color (robot_dart::gui::magnum::ObjectStruct)
  • Camera (robot_dart::gui::magnum::Camera, robot_dart::gui::magnum::sensor::Camera)
  • camera_object (robot_dart::gui::magnum::Camera)
  • CubeMap (robot_dart::gui::magnum::CubeMap)
  • CubeMapColor (robot_dart::gui::magnum::CubeMapColor)
  • casts_shadows (robot_dart::gui::magnum::Light)
  • collision_vec (robot_dart::robots::TalosFastCollision)
  • caster_joints (robot_dart::robots::Tiago)
  • color (robot_dart::simu::TextData)
  • casting_shadows (robot_dart::simu::GUIData::RobotData)
"},{"location":"api/class_members/#d","title":"d","text":"
  • damping_coeffs (robot_dart::Robot)
  • dof (robot_dart::Robot)
  • dof_index (robot_dart::Robot)
  • dof_map (robot_dart::Robot)
  • dof_name (robot_dart::Robot)
  • dof_names (robot_dart::Robot)
  • drawing_axes (robot_dart::Robot, robot_dart::simu::GUIData)
  • dt (robot_dart::Scheduler)
  • DartCollisionConstPtr (robot_dart::collision_filter::BitmaskContactFilter)
  • DartShapeConstPtr (robot_dart::collision_filter::BitmaskContactFilter)
  • depth_array (robot_dart::gui::Base, robot_dart::gui::magnum::BaseApplication, robot_dart::gui::magnum::BaseGraphics, robot_dart::gui::magnum::sensor::Camera)
  • depth_image (robot_dart::gui::Base, robot_dart::gui::magnum::BaseApplication, robot_dart::gui::magnum::BaseGraphics, robot_dart::gui::magnum::Camera, robot_dart::gui::magnum::sensor::Camera)
  • done (robot_dart::gui::Base, robot_dart::gui::magnum::BaseApplication, robot_dart::gui::magnum::BaseGraphics)
  • data (robot_dart::gui::DepthImage, robot_dart::gui::GrayscaleImage, robot_dart::gui::Image)
  • debug_draw_data (robot_dart::gui::magnum::BaseApplication)
  • drawables (robot_dart::gui::magnum::BaseApplication)
  • draw (robot_dart::gui::magnum::CubeMapShadowedColorObject, robot_dart::gui::magnum::CubeMapShadowedObject, robot_dart::gui::magnum::DrawableObject, robot_dart::gui::magnum::ShadowedColorObject, robot_dart::gui::magnum::ShadowedObject, robot_dart::gui::magnum::Camera)
  • DrawableObject (robot_dart::gui::magnum::DrawableObject)
  • drawEvent (robot_dart::gui::magnum::GlfwApplication)
  • default_configuration (robot_dart::gui::magnum::Graphics, robot_dart::gui::magnum::WindowlessGraphics)
  • draw_debug (robot_dart::gui::magnum::GraphicsConfiguration, robot_dart::gui::magnum::sensor::Camera)
  • draw_main_camera (robot_dart::gui::magnum::GraphicsConfiguration)
  • draw_text (robot_dart::gui::magnum::GraphicsConfiguration)
  • drawable (robot_dart::gui::magnum::ObjectStruct)
  • diffuse_color (robot_dart::gui::magnum::Material)
  • diffuse_texture (robot_dart::gui::magnum::Material)
  • drawing_debug (robot_dart::gui::magnum::sensor::Camera)
  • detach (robot_dart::sensor::Sensor)
  • drawing_texts (robot_dart::simu::GUIData)
  • draw_background (robot_dart::simu::TextData)
"},{"location":"api/class_members/#e","title":"e","text":"
  • external_forces (robot_dart::Robot)
  • enable_status_bar (robot_dart::RobotDARTSimu)
  • enable_text_panel (robot_dart::RobotDARTSimu)
  • enable_shadows (robot_dart::gui::magnum::BaseApplication, robot_dart::gui::magnum::BaseGraphics)
  • exitEvent (robot_dart::gui::magnum::GlfwApplication)
  • exec (robot_dart::gui::magnum::WindowlessGLApplication)
  • extrinsic_matrix (robot_dart::gui::magnum::Camera)
"},{"location":"api/class_members/#f","title":"f","text":"
  • fix_to_world (robot_dart::Robot)
  • fixed (robot_dart::Robot)
  • force_lower_limits (robot_dart::Robot)
  • force_position_bounds (robot_dart::Robot)
  • force_torque (robot_dart::Robot)
  • force_upper_limits (robot_dart::Robot)
  • forces (robot_dart::Robot)
  • free (robot_dart::Robot)
  • free_from_world (robot_dart::Robot)
  • friction_coeff (robot_dart::Robot)
  • friction_dir (robot_dart::Robot)
  • free_robot (robot_dart::RobotPool)
  • font (robot_dart::gui::magnum::DebugDrawData)
  • free_gl_context (robot_dart::gui::magnum::GlobalData)
  • far_plane (robot_dart::gui::magnum::Camera)
  • forward (robot_dart::gui::magnum::Camera)
  • fov (robot_dart::gui::magnum::Camera)
  • Flag (robot_dart::gui::magnum::CubeMap, robot_dart::gui::magnum::CubeMapColor, robot_dart::gui::magnum::PhongMultiLight, robot_dart::gui::magnum::ShadowMap, robot_dart::gui::magnum::ShadowMapColor)
  • Flags (robot_dart::gui::magnum::CubeMap, robot_dart::gui::magnum::CubeMapColor, robot_dart::gui::magnum::PhongMultiLight, robot_dart::gui::magnum::ShadowMap, robot_dart::gui::magnum::ShadowMapColor)
  • flags (robot_dart::gui::magnum::CubeMap, robot_dart::gui::magnum::CubeMapColor, robot_dart::gui::magnum::PhongMultiLight, robot_dart::gui::magnum::ShadowMap, robot_dart::gui::magnum::ShadowMapColor)
  • Franka (robot_dart::robots::Franka)
  • ft_wrist (robot_dart::robots::Franka, robot_dart::robots::Iiwa, robot_dart::robots::Tiago, robot_dart::robots::Ur3e)
  • ft_foot_left (robot_dart::robots::ICub, robot_dart::robots::Talos)
  • ft_foot_right (robot_dart::robots::ICub, robot_dart::robots::Talos)
  • ft_wrist_left (robot_dart::robots::Talos)
  • ft_wrist_right (robot_dart::robots::Talos)
  • ForceTorque (robot_dart::sensor::ForceTorque)
  • force (robot_dart::sensor::ForceTorque)
  • frequency (robot_dart::sensor::IMUConfig, robot_dart::sensor::Sensor)
  • font_size (robot_dart::simu::TextData)
"},{"location":"api/class_members/#g","title":"g","text":"
  • ghost (robot_dart::Robot, robot_dart::simu::GUIData)
  • gravity_forces (robot_dart::Robot)
  • graphics (robot_dart::RobotDARTSimu)
  • graphics_freq (robot_dart::RobotDARTSimu)
  • gravity (robot_dart::RobotDARTSimu)
  • gui_data (robot_dart::RobotDARTSimu)
  • get_robot (robot_dart::RobotPool)
  • GlfwApplication (robot_dart::gui::magnum::GlfwApplication)
  • GlobalData (robot_dart::gui::magnum::GlobalData)
  • gl_context (robot_dart::gui::magnum::GlobalData)
  • Graphics (robot_dart::gui::magnum::Graphics)
  • gyro_bias (robot_dart::sensor::IMUConfig)
"},{"location":"api/class_members/#h","title":"h","text":"
  • halted_sim (robot_dart::RobotDARTSimu)
  • h_params (robot_dart::control::PolicyControl)
  • height (robot_dart::gui::Base, robot_dart::gui::DepthImage, robot_dart::gui::GrayscaleImage, robot_dart::gui::Image, robot_dart::gui::magnum::BaseGraphics, robot_dart::gui::magnum::GraphicsConfiguration, robot_dart::gui::magnum::Camera)
  • has_ambient_texture (robot_dart::gui::magnum::Material)
  • has_diffuse_texture (robot_dart::gui::magnum::Material)
  • has_specular_texture (robot_dart::gui::magnum::Material)
  • Hexapod (robot_dart::robots::Hexapod)
"},{"location":"api/class_members/#i","title":"i","text":"
  • inv_aug_mass_matrix (robot_dart::Robot)
  • inv_mass_matrix (robot_dart::Robot)
  • it_duration (robot_dart::Scheduler)
  • ignoresCollision (robot_dart::collision_filter::BitmaskContactFilter)
  • init (robot_dart::control::RobotControl, robot_dart::gui::magnum::BaseApplication, robot_dart::gui::magnum::sensor::Camera, robot_dart::sensor::ForceTorque, robot_dart::sensor::IMU, robot_dart::sensor::Sensor, robot_dart::sensor::Torque)
  • image (robot_dart::gui::Base, robot_dart::gui::magnum::BaseApplication, robot_dart::gui::magnum::BaseGraphics, robot_dart::gui::magnum::Camera, robot_dart::gui::magnum::sensor::Camera)
  • instance (robot_dart::gui::magnum::GlobalData)
  • intrinsic_matrix (robot_dart::gui::magnum::Camera)
  • imu (robot_dart::robots::A1, robot_dart::robots::ICub, robot_dart::robots::Talos)
  • ICub (robot_dart::robots::ICub)
  • Iiwa (robot_dart::robots::Iiwa)
  • IMU (robot_dart::sensor::IMU)
  • IMUConfig (robot_dart::sensor::IMUConfig)
  • is_ghost (robot_dart::simu::GUIData::RobotData)
"},{"location":"api/class_members/#j","title":"j","text":"
  • jacobian (robot_dart::Robot)
  • jacobian_deriv (robot_dart::Robot)
  • joint (robot_dart::Robot)
  • joint_index (robot_dart::Robot)
  • joint_map (robot_dart::Robot)
  • joint_name (robot_dart::Robot)
  • joint_names (robot_dart::Robot)
"},{"location":"api/class_members/#k","title":"k","text":"
  • keyPressEvent (robot_dart::gui::magnum::GlfwApplication)
  • keyReleaseEvent (robot_dart::gui::magnum::GlfwApplication)
"},{"location":"api/class_members/#l","title":"l","text":"
  • locked_dof_names (robot_dart::Robot)
  • last_it_duration (robot_dart::Scheduler)
  • light (robot_dart::gui::magnum::BaseApplication, robot_dart::gui::magnum::BaseGraphics)
  • lights (robot_dart::gui::magnum::BaseApplication, robot_dart::gui::magnum::BaseGraphics)
  • look_at (robot_dart::gui::magnum::BaseApplication, robot_dart::gui::magnum::BaseGraphics, robot_dart::gui::magnum::Camera, robot_dart::gui::magnum::sensor::Camera)
  • Light (robot_dart::gui::magnum::Light)
  • linear_acceleration (robot_dart::sensor::IMU)
"},{"location":"api/class_members/#m","title":"m","text":"
  • mass_matrix (robot_dart::Robot)
  • mimic_dof_names (robot_dart::Robot)
  • model_filename (robot_dart::Robot, robot_dart::RobotPool)
  • model_packages (robot_dart::Robot)
  • mask (robot_dart::collision_filter::BitmaskContactFilter)
  • magnum_app (robot_dart::gui::magnum::BaseGraphics)
  • magnum_image (robot_dart::gui::magnum::BaseGraphics, robot_dart::gui::magnum::sensor::Camera)
  • materials (robot_dart::gui::magnum::DrawableObject)
  • mouseMoveEvent (robot_dart::gui::magnum::GlfwApplication)
  • mouseScrollEvent (robot_dart::gui::magnum::GlfwApplication)
  • max_lights (robot_dart::gui::magnum::GraphicsConfiguration, robot_dart::gui::magnum::PhongMultiLight)
  • move (robot_dart::gui::magnum::Camera)
  • material (robot_dart::gui::magnum::Light)
  • Material (robot_dart::gui::magnum::Material)
  • magnum_depth_image (robot_dart::gui::magnum::sensor::Camera)
"},{"location":"api/class_members/#n","title":"n","text":"
  • name (robot_dart::Robot)
  • num_bodies (robot_dart::Robot)
  • num_controllers (robot_dart::Robot)
  • num_dofs (robot_dart::Robot)
  • num_joints (robot_dart::Robot)
  • num_robots (robot_dart::RobotDARTSimu)
  • next_time (robot_dart::Scheduler)
  • num_lights (robot_dart::gui::magnum::BaseApplication, robot_dart::gui::magnum::BaseGraphics)
  • near_plane (robot_dart::gui::magnum::Camera)
  • Normal (robot_dart::gui::magnum::PhongMultiLight)
"},{"location":"api/class_members/#o","title":"o","text":"
  • operator= (robot_dart::RobotPool, robot_dart::gui::magnum::GlobalData)
  • operator() (robot_dart::Scheduler)
"},{"location":"api/class_members/#p","title":"p","text":"
  • passive_dof_names (robot_dart::Robot)
  • position_enforced (robot_dart::Robot)
  • position_lower_limits (robot_dart::Robot)
  • position_upper_limits (robot_dart::Robot)
  • positions (robot_dart::Robot)
  • physics_freq (robot_dart::RobotDARTSimu)
  • PDControl (robot_dart::control::PDControl)
  • pd (robot_dart::control::PDControl)
  • PolicyControl (robot_dart::control::PolicyControl)
  • parameters (robot_dart::control::RobotControl)
  • Position (robot_dart::gui::magnum::CubeMap, robot_dart::gui::magnum::CubeMapColor, robot_dart::gui::magnum::PhongMultiLight, robot_dart::gui::magnum::ShadowMap, robot_dart::gui::magnum::ShadowMapColor)
  • position (robot_dart::gui::magnum::Light)
  • PhongMultiLight (robot_dart::gui::magnum::PhongMultiLight)
  • Pendulum (robot_dart::robots::Pendulum)
  • pose (robot_dart::sensor::Sensor)
"},{"location":"api/class_members/#r","title":"r","text":"
  • Robot (robot_dart::Robot)
  • reinit_controllers (robot_dart::Robot)
  • remove_all_drawing_axis (robot_dart::Robot)
  • remove_controller (robot_dart::Robot)
  • reset (robot_dart::Robot, robot_dart::Scheduler, robot_dart::robots::A1, robot_dart::robots::Hexapod, robot_dart::robots::ICub, robot_dart::robots::Talos, robot_dart::robots::Tiago)
  • reset_commands (robot_dart::Robot)
  • restitution_coeff (robot_dart::Robot)
  • RobotDARTSimu (robot_dart::RobotDARTSimu)
  • remove_all_collision_masks (robot_dart::RobotDARTSimu)
  • remove_collision_masks (robot_dart::RobotDARTSimu)
  • remove_robot (robot_dart::RobotDARTSimu, robot_dart::simu::GUIData)
  • remove_sensor (robot_dart::RobotDARTSimu)
  • remove_sensors (robot_dart::RobotDARTSimu)
  • robot (robot_dart::RobotDARTSimu, robot_dart::control::RobotControl)
  • robot_index (robot_dart::RobotDARTSimu)
  • robot_t (robot_dart::RobotDARTSimu)
  • robots (robot_dart::RobotDARTSimu)
  • run (robot_dart::RobotDARTSimu)
  • RobotPool (robot_dart::RobotPool)
  • robot_creator_t (robot_dart::RobotPool)
  • real_time (robot_dart::Scheduler)
  • real_time_factor (robot_dart::Scheduler)
  • remove_from_map (robot_dart::collision_filter::BitmaskContactFilter)
  • RobotControl (robot_dart::control::RobotControl)
  • raw_depth_image (robot_dart::gui::Base, robot_dart::gui::magnum::BaseApplication, robot_dart::gui::magnum::BaseGraphics, robot_dart::gui::magnum::sensor::Camera)
  • refresh (robot_dart::gui::Base, robot_dart::gui::magnum::BaseGraphics, robot_dart::sensor::Sensor)
  • record_video (robot_dart::gui::magnum::BaseApplication, robot_dart::gui::magnum::BaseGraphics, robot_dart::gui::magnum::Camera, robot_dart::gui::magnum::sensor::Camera)
  • render (robot_dart::gui::magnum::BaseApplication, robot_dart::gui::magnum::GlfwApplication, robot_dart::gui::magnum::WindowlessGLApplication)
  • render_shadows (robot_dart::gui::magnum::BaseApplication)
  • record (robot_dart::gui::magnum::Camera)
  • recording (robot_dart::gui::magnum::Camera)
  • recording_depth (robot_dart::gui::magnum::Camera)
  • root_object (robot_dart::gui::magnum::Camera)
  • remove_text (robot_dart::simu::GUIData)
  • robot_axes (robot_dart::simu::GUIData)
  • robot_data (robot_dart::simu::GUIData)
"},{"location":"api/class_members/#s","title":"s","text":"
  • secondary_friction_coeff (robot_dart::Robot)
  • self_colliding (robot_dart::Robot)
  • set_acceleration_lower_limits (robot_dart::Robot)
  • set_acceleration_upper_limits (robot_dart::Robot)
  • set_accelerations (robot_dart::Robot)
  • set_actuator_type (robot_dart::Robot, robot_dart::robots::Tiago)
  • set_actuator_types (robot_dart::Robot, robot_dart::robots::Tiago)
  • set_base_pose (robot_dart::Robot)
  • set_body_mass (robot_dart::Robot)
  • set_body_name (robot_dart::Robot)
  • set_cast_shadows (robot_dart::Robot)
  • set_color_mode (robot_dart::Robot)
  • set_commands (robot_dart::Robot)
  • set_coulomb_coeffs (robot_dart::Robot)
  • set_damping_coeffs (robot_dart::Robot)
  • set_draw_axis (robot_dart::Robot)
  • set_external_force (robot_dart::Robot)
  • set_external_torque (robot_dart::Robot)
  • set_force_lower_limits (robot_dart::Robot)
  • set_force_upper_limits (robot_dart::Robot)
  • set_forces (robot_dart::Robot)
  • set_friction_coeff (robot_dart::Robot)
  • set_friction_coeffs (robot_dart::Robot)
  • set_friction_dir (robot_dart::Robot)
  • set_ghost (robot_dart::Robot)
  • set_joint_name (robot_dart::Robot)
  • set_mimic (robot_dart::Robot)
  • set_position_enforced (robot_dart::Robot)
  • set_position_lower_limits (robot_dart::Robot)
  • set_position_upper_limits (robot_dart::Robot)
  • set_positions (robot_dart::Robot)
  • set_restitution_coeff (robot_dart::Robot)
  • set_restitution_coeffs (robot_dart::Robot)
  • set_secondary_friction_coeff (robot_dart::Robot)
  • set_secondary_friction_coeffs (robot_dart::Robot)
  • set_self_collision (robot_dart::Robot)
  • set_spring_stiffnesses (robot_dart::Robot)
  • set_velocities (robot_dart::Robot)
  • set_velocity_lower_limits (robot_dart::Robot)
  • set_velocity_upper_limits (robot_dart::Robot)
  • skeleton (robot_dart::Robot)
  • spring_stiffnesses (robot_dart::Robot)
  • schedule (robot_dart::RobotDARTSimu, robot_dart::Scheduler)
  • scheduler (robot_dart::RobotDARTSimu)
  • sensor (robot_dart::RobotDARTSimu)
  • sensors (robot_dart::RobotDARTSimu)
  • set_collision_detector (robot_dart::RobotDARTSimu)
  • set_collision_masks (robot_dart::RobotDARTSimu)
  • set_control_freq (robot_dart::RobotDARTSimu)
  • set_graphics (robot_dart::RobotDARTSimu)
  • set_graphics_freq (robot_dart::RobotDARTSimu)
  • set_gravity (robot_dart::RobotDARTSimu)
  • set_text_panel (robot_dart::RobotDARTSimu)
  • set_timestep (robot_dart::RobotDARTSimu)
  • status_bar_text (robot_dart::RobotDARTSimu)
  • step (robot_dart::RobotDARTSimu, robot_dart::Scheduler)
  • step_world (robot_dart::RobotDARTSimu)
  • stop_sim (robot_dart::RobotDARTSimu)
  • Scheduler (robot_dart::Scheduler)
  • set_sync (robot_dart::Scheduler)
  • sync (robot_dart::Scheduler)
  • set_pd (robot_dart::control::PDControl)
  • set_use_angular_errors (robot_dart::control::PDControl)
  • set_h_params (robot_dart::control::PolicyControl)
  • set_parameters (robot_dart::control::RobotControl)
  • set_robot (robot_dart::control::RobotControl)
  • set_weight (robot_dart::control::RobotControl)
  • SimpleControl (robot_dart::control::SimpleControl)
  • set_enable (robot_dart::gui::Base, robot_dart::gui::magnum::BaseGraphics)
  • set_fps (robot_dart::gui::Base, robot_dart::gui::magnum::BaseGraphics)
  • set_render_period (robot_dart::gui::Base)
  • set_simu (robot_dart::gui::Base, robot_dart::gui::magnum::BaseGraphics, robot_dart::gui::magnum::Graphics, robot_dart::gui::magnum::WindowlessGraphics, robot_dart::sensor::Sensor)
  • simu (robot_dart::gui::Base, robot_dart::gui::magnum::CubeMapShadowedColorObject, robot_dart::gui::magnum::CubeMapShadowedObject, robot_dart::gui::magnum::DrawableObject, robot_dart::gui::magnum::ShadowedColorObject, robot_dart::gui::magnum::ShadowedObject, robot_dart::sensor::Sensor)
  • scene (robot_dart::gui::magnum::BaseApplication)
  • shadowed (robot_dart::gui::magnum::BaseApplication, robot_dart::gui::magnum::BaseGraphics, robot_dart::gui::magnum::GraphicsConfiguration, robot_dart::gui::magnum::ObjectStruct)
  • set_materials (robot_dart::gui::magnum::CubeMapShadowedColorObject, robot_dart::gui::magnum::CubeMapShadowedObject, robot_dart::gui::magnum::DrawableObject, robot_dart::gui::magnum::ShadowedColorObject, robot_dart::gui::magnum::ShadowedObject)
  • set_meshes (robot_dart::gui::magnum::CubeMapShadowedColorObject, robot_dart::gui::magnum::CubeMapShadowedObject, robot_dart::gui::magnum::DrawableObject, robot_dart::gui::magnum::ShadowedColorObject, robot_dart::gui::magnum::ShadowedObject)
  • set_scalings (robot_dart::gui::magnum::CubeMapShadowedColorObject, robot_dart::gui::magnum::CubeMapShadowedObject, robot_dart::gui::magnum::DrawableObject, robot_dart::gui::magnum::ShadowedColorObject, robot_dart::gui::magnum::ShadowedObject)
  • shape (robot_dart::gui::magnum::CubeMapShadowedColorObject, robot_dart::gui::magnum::CubeMapShadowedObject, robot_dart::gui::magnum::DrawableObject, robot_dart::gui::magnum::ShadowedColorObject, robot_dart::gui::magnum::ShadowedObject)
  • set_color_shader (robot_dart::gui::magnum::DrawableObject)
  • set_soft_bodies (robot_dart::gui::magnum::DrawableObject)
  • set_texture_shader (robot_dart::gui::magnum::DrawableObject)
  • set_transparent (robot_dart::gui::magnum::DrawableObject)
  • set_max_contexts (robot_dart::gui::magnum::GlobalData)
  • shadow_map_size (robot_dart::gui::magnum::GraphicsConfiguration)
  • specular_strength (robot_dart::gui::magnum::GraphicsConfiguration)
  • shadowed_color (robot_dart::gui::magnum::ObjectStruct)
  • shadow_color_framebuffer (robot_dart::gui::magnum::ShadowData)
  • shadow_framebuffer (robot_dart::gui::magnum::ShadowData)
  • ShadowedColorObject (robot_dart::gui::magnum::ShadowedColorObject)
  • ShadowedObject (robot_dart::gui::magnum::ShadowedObject)
  • set_camera_params (robot_dart::gui::magnum::Camera)
  • set_far_plane (robot_dart::gui::magnum::Camera, robot_dart::gui::magnum::CubeMap, robot_dart::gui::magnum::CubeMapColor, robot_dart::gui::magnum::PhongMultiLight)
  • set_fov (robot_dart::gui::magnum::Camera)
  • set_near_plane (robot_dart::gui::magnum::Camera)
  • set_speed (robot_dart::gui::magnum::Camera)
  • set_viewport (robot_dart::gui::magnum::Camera)
  • speed (robot_dart::gui::magnum::Camera)
  • strafe (robot_dart::gui::magnum::Camera)
  • set_light_index (robot_dart::gui::magnum::CubeMap, robot_dart::gui::magnum::CubeMapColor)
  • set_light_position (robot_dart::gui::magnum::CubeMap, robot_dart::gui::magnum::CubeMapColor)
  • set_material (robot_dart::gui::magnum::CubeMap, robot_dart::gui::magnum::CubeMapColor, robot_dart::gui::magnum::Light, robot_dart::gui::magnum::PhongMultiLight, robot_dart::gui::magnum::ShadowMap, robot_dart::gui::magnum::ShadowMapColor)
  • set_shadow_matrices (robot_dart::gui::magnum::CubeMap, robot_dart::gui::magnum::CubeMapColor)
  • set_transformation_matrix (robot_dart::gui::magnum::CubeMap, robot_dart::gui::magnum::CubeMapColor, robot_dart::gui::magnum::PhongMultiLight, robot_dart::gui::magnum::ShadowMap, robot_dart::gui::magnum::ShadowMapColor)
  • set_attenuation (robot_dart::gui::magnum::Light)
  • set_casts_shadows (robot_dart::gui::magnum::Light)
  • set_position (robot_dart::gui::magnum::Light)
  • set_shadow_matrix (robot_dart::gui::magnum::Light)
  • set_spot_cut_off (robot_dart::gui::magnum::Light)
  • set_spot_direction (robot_dart::gui::magnum::Light)
  • set_spot_exponent (robot_dart::gui::magnum::Light)
  • set_transformed_position (robot_dart::gui::magnum::Light)
  • set_transformed_spot_direction (robot_dart::gui::magnum::Light)
  • shadow_matrix (robot_dart::gui::magnum::Light)
  • spot_cut_off (robot_dart::gui::magnum::Light)
  • spot_direction (robot_dart::gui::magnum::Light)
  • spot_exponent (robot_dart::gui::magnum::Light)
  • set_ambient_color (robot_dart::gui::magnum::Material)
  • set_ambient_texture (robot_dart::gui::magnum::Material)
  • set_diffuse_color (robot_dart::gui::magnum::Material)
  • set_diffuse_texture (robot_dart::gui::magnum::Material)
  • set_shininess (robot_dart::gui::magnum::Material)
  • set_specular_color (robot_dart::gui::magnum::Material)
  • set_specular_texture (robot_dart::gui::magnum::Material)
  • shininess (robot_dart::gui::magnum::Material)
  • specular_color (robot_dart::gui::magnum::Material)
  • specular_texture (robot_dart::gui::magnum::Material)
  • set_camera_matrix (robot_dart::gui::magnum::PhongMultiLight)
  • set_is_shadowed (robot_dart::gui::magnum::PhongMultiLight)
  • set_light (robot_dart::gui::magnum::PhongMultiLight)
  • set_normal_matrix (robot_dart::gui::magnum::PhongMultiLight)
  • set_projection_matrix (robot_dart::gui::magnum::PhongMultiLight, robot_dart::gui::magnum::ShadowMap, robot_dart::gui::magnum::ShadowMapColor)
  • set_specular_strength (robot_dart::gui::magnum::PhongMultiLight)
  • set_transparent_shadows (robot_dart::gui::magnum::PhongMultiLight)
  • ShadowMap (robot_dart::gui::magnum::ShadowMap)
  • ShadowMapColor (robot_dart::gui::magnum::ShadowMapColor)
  • Sensor (robot_dart::sensor::Sensor)
  • set_frequency (robot_dart::sensor::Sensor)
  • set_pose (robot_dart::sensor::Sensor)
"},{"location":"api/class_members/#t","title":"t","text":"
  • text_panel_text (robot_dart::RobotDARTSimu)
  • timestep (robot_dart::RobotDARTSimu)
  • transparent_shadows (robot_dart::gui::magnum::BaseApplication, robot_dart::gui::magnum::BaseGraphics, robot_dart::gui::magnum::GraphicsConfiguration)
  • text_indices (robot_dart::gui::magnum::DebugDrawData)
  • text_shader (robot_dart::gui::magnum::DebugDrawData)
  • text_vertices (robot_dart::gui::magnum::DebugDrawData)
  • transparent (robot_dart::gui::magnum::DrawableObject)
  • title (robot_dart::gui::magnum::GraphicsConfiguration)
  • transform_lights (robot_dart::gui::magnum::Camera)
  • TextureCoordinates (robot_dart::gui::magnum::CubeMap, robot_dart::gui::magnum::CubeMapColor, robot_dart::gui::magnum::PhongMultiLight, robot_dart::gui::magnum::ShadowMap, robot_dart::gui::magnum::ShadowMapColor)
  • transformed_position (robot_dart::gui::magnum::Light)
  • transformed_spot_direction (robot_dart::gui::magnum::Light)
  • type (robot_dart::gui::magnum::sensor::Camera, robot_dart::sensor::ForceTorque, robot_dart::sensor::IMU, robot_dart::sensor::Sensor, robot_dart::sensor::Torque)
  • Talos (robot_dart::robots::Talos)
  • torque_map_t (robot_dart::robots::Talos)
  • torques (robot_dart::robots::Talos, robot_dart::sensor::Torque)
  • TalosFastCollision (robot_dart::robots::TalosFastCollision)
  • TalosLight (robot_dart::robots::TalosLight)
  • Tiago (robot_dart::robots::Tiago)
  • torque (robot_dart::sensor::ForceTorque)
  • Torque (robot_dart::sensor::Torque)
  • text_drawings (robot_dart::simu::GUIData)
  • text (robot_dart::simu::TextData)
  • transformation (robot_dart::simu::TextData)
"},{"location":"api/class_members/#u","title":"u","text":"
  • update (robot_dart::Robot)
  • update_joint_dof_maps (robot_dart::Robot)
  • using_angular_errors (robot_dart::control::PDControl)
  • update_graphics (robot_dart::gui::magnum::BaseApplication)
  • update_lights (robot_dart::gui::magnum::BaseApplication)
  • Ur3e (robot_dart::robots::Ur3e)
  • Ur3eHand (robot_dart::robots::Ur3eHand)
  • update_robot (robot_dart::simu::GUIData)
"},{"location":"api/class_members/#v","title":"v","text":"
  • vec_dof (robot_dart::Robot)
  • velocities (robot_dart::Robot)
  • velocity_lower_limits (robot_dart::Robot)
  • velocity_upper_limits (robot_dart::Robot)
  • viewportEvent (robot_dart::gui::magnum::GlfwApplication)
  • Vx300 (robot_dart::robots::Vx300)
"},{"location":"api/class_members/#w","title":"w","text":"
  • what (robot_dart::Assertion)
  • world (robot_dart::RobotDARTSimu)
  • weight (robot_dart::control::RobotControl)
  • width (robot_dart::gui::Base, robot_dart::gui::DepthImage, robot_dart::gui::GrayscaleImage, robot_dart::gui::Image, robot_dart::gui::magnum::BaseGraphics, robot_dart::gui::magnum::GraphicsConfiguration, robot_dart::gui::magnum::Camera)
  • WindowlessGLApplication (robot_dart::gui::magnum::WindowlessGLApplication)
  • WindowlessGraphics (robot_dart::gui::magnum::WindowlessGraphics)
  • wrench (robot_dart::sensor::ForceTorque)
"},{"location":"api/class_members/#_1","title":"~","text":"
  • ~Robot (robot_dart::Robot)
  • ~RobotDARTSimu (robot_dart::RobotDARTSimu)
  • ~RobotPool (robot_dart::RobotPool)
  • ~BitmaskContactFilter (robot_dart::collision_filter::BitmaskContactFilter)
  • ~RobotControl (robot_dart::control::RobotControl)
  • ~Base (robot_dart::gui::Base)
  • ~BaseApplication (robot_dart::gui::magnum::BaseApplication)
  • ~BaseGraphics (robot_dart::gui::magnum::BaseGraphics)
  • ~GlfwApplication (robot_dart::gui::magnum::GlfwApplication)
  • ~GlobalData (robot_dart::gui::magnum::GlobalData)
  • ~Graphics (robot_dart::gui::magnum::Graphics)
  • ~WindowlessGLApplication (robot_dart::gui::magnum::WindowlessGLApplication)
  • ~WindowlessGraphics (robot_dart::gui::magnum::WindowlessGraphics)
  • ~Camera (robot_dart::gui::magnum::Camera, robot_dart::gui::magnum::sensor::Camera)
  • ~Sensor (robot_dart::sensor::Sensor)
"},{"location":"api/class_members/#_","title":"_","text":"
  • _make_message (robot_dart::Assertion)
  • _msg (robot_dart::Assertion)
  • _actuator_type (robot_dart::Robot)
  • _actuator_types (robot_dart::Robot)
  • _axis_shapes (robot_dart::Robot)
  • _cast_shadows (robot_dart::Robot, robot_dart::gui::magnum::Light)
  • _controllers (robot_dart::Robot)
  • _dof_map (robot_dart::Robot)
  • _get_path (robot_dart::Robot)
  • _is_ghost (robot_dart::Robot)
  • _jacobian (robot_dart::Robot)
  • _joint_map (robot_dart::Robot)
  • _load_model (robot_dart::Robot)
  • _mass_matrix (robot_dart::Robot)
  • _model_filename (robot_dart::Robot, robot_dart::RobotPool)
  • _packages (robot_dart::Robot)
  • _post_addition (robot_dart::Robot, robot_dart::robots::Franka, robot_dart::robots::ICub, robot_dart::robots::Iiwa, robot_dart::robots::Talos, robot_dart::robots::TalosFastCollision, robot_dart::robots::Tiago, robot_dart::robots::Ur3e)
  • _post_removal (robot_dart::Robot, robot_dart::robots::Franka, robot_dart::robots::ICub, robot_dart::robots::Iiwa, robot_dart::robots::Talos, robot_dart::robots::Tiago, robot_dart::robots::Ur3e)
  • _robot_name (robot_dart::Robot)
  • _set_actuator_type (robot_dart::Robot)
  • _set_actuator_types (robot_dart::Robot)
  • _set_color_mode (robot_dart::Robot)
  • _skeleton (robot_dart::Robot)
  • _break (robot_dart::RobotDARTSimu)
  • _control_freq (robot_dart::RobotDARTSimu)
  • _enable (robot_dart::RobotDARTSimu)
  • _graphics (robot_dart::RobotDARTSimu)
  • _graphics_freq (robot_dart::RobotDARTSimu)
  • _gui_data (robot_dart::RobotDARTSimu)
  • _old_index (robot_dart::RobotDARTSimu)
  • _physics_freq (robot_dart::RobotDARTSimu)
  • _robots (robot_dart::RobotDARTSimu)
  • _scheduler (robot_dart::RobotDARTSimu)
  • _sensors (robot_dart::RobotDARTSimu)
  • _status_bar (robot_dart::RobotDARTSimu)
  • _text_panel (robot_dart::RobotDARTSimu)
  • _world (robot_dart::RobotDARTSimu)
  • _free (robot_dart::RobotPool)
  • _pool_size (robot_dart::RobotPool)
  • _reset_robot (robot_dart::RobotPool)
  • _robot_creator (robot_dart::RobotPool)
  • _skeleton_mutex (robot_dart::RobotPool)
  • _skeletons (robot_dart::RobotPool)
  • _verbose (robot_dart::RobotPool)
  • _average_it_duration (robot_dart::Scheduler)
  • _current_step (robot_dart::Scheduler)
  • _current_time (robot_dart::Scheduler)
  • _dt (robot_dart::Scheduler, robot_dart::control::PolicyControl)
  • _it_duration (robot_dart::Scheduler)
  • _last_iteration_time (robot_dart::Scheduler)
  • _max_frequency (robot_dart::Scheduler)
  • _real_start_time (robot_dart::Scheduler)
  • _real_time (robot_dart::Scheduler)
  • _simu_start_time (robot_dart::Scheduler)
  • _start_time (robot_dart::Scheduler)
  • _sync (robot_dart::Scheduler)
  • _bitmask_map (robot_dart::collision_filter::BitmaskContactFilter)
  • _Kd (robot_dart::control::PDControl)
  • _Kp (robot_dart::control::PDControl)
  • _angle_dist (robot_dart::control::PDControl)
  • _use_angular_errors (robot_dart::control::PDControl)
  • _first (robot_dart::control::PolicyControl)
  • _full_dt (robot_dart::control::PolicyControl)
  • _i (robot_dart::control::PolicyControl)
  • _policy (robot_dart::control::PolicyControl)
  • _prev_commands (robot_dart::control::PolicyControl)
  • _prev_time (robot_dart::control::PolicyControl)
  • _threshold (robot_dart::control::PolicyControl)
  • _active (robot_dart::control::RobotControl, robot_dart::sensor::Sensor)
  • _check_free (robot_dart::control::RobotControl)
  • _control_dof (robot_dart::control::RobotControl)
  • _controllable_dofs (robot_dart::control::RobotControl)
  • _ctrl (robot_dart::control::RobotControl)
  • _dof (robot_dart::control::RobotControl)
  • _robot (robot_dart::control::RobotControl)
  • _weight (robot_dart::control::RobotControl)
  • _simu (robot_dart::gui::Base, robot_dart::gui::magnum::BaseApplication, robot_dart::gui::magnum::CubeMapShadowedColorObject, robot_dart::gui::magnum::CubeMapShadowedObject, robot_dart::gui::magnum::DrawableObject, robot_dart::gui::magnum::GlfwApplication, robot_dart::gui::magnum::ShadowedColorObject, robot_dart::gui::magnum::ShadowedObject, robot_dart::gui::magnum::WindowlessGLApplication, robot_dart::sensor::Sensor)
  • _3D_axis_mesh (robot_dart::gui::magnum::BaseApplication)
  • _3D_axis_shader (robot_dart::gui::magnum::BaseApplication)
  • _background_mesh (robot_dart::gui::magnum::BaseApplication)
  • _background_shader (robot_dart::gui::magnum::BaseApplication)
  • _camera (robot_dart::gui::magnum::BaseApplication, robot_dart::gui::magnum::Camera, robot_dart::gui::magnum::sensor::Camera)
  • _color_shader (robot_dart::gui::magnum::BaseApplication, robot_dart::gui::magnum::DrawableObject)
  • _configuration (robot_dart::gui::magnum::BaseApplication, robot_dart::gui::magnum::BaseGraphics)
  • _cubemap_color_drawables (robot_dart::gui::magnum::BaseApplication)
  • _cubemap_color_shader (robot_dart::gui::magnum::BaseApplication)
  • _cubemap_drawables (robot_dart::gui::magnum::BaseApplication)
  • _cubemap_shader (robot_dart::gui::magnum::BaseApplication)
  • _cubemap_texture_color_shader (robot_dart::gui::magnum::BaseApplication)
  • _cubemap_texture_shader (robot_dart::gui::magnum::BaseApplication)
  • _dart_world (robot_dart::gui::magnum::BaseApplication)
  • _done (robot_dart::gui::magnum::BaseApplication)
  • _drawable_objects (robot_dart::gui::magnum::BaseApplication)
  • _drawables (robot_dart::gui::magnum::BaseApplication)
  • _font (robot_dart::gui::magnum::BaseApplication)
  • _font_manager (robot_dart::gui::magnum::BaseApplication)
  • _gl_clean_up (robot_dart::gui::magnum::BaseApplication)
  • _glyph_cache (robot_dart::gui::magnum::BaseApplication)
  • _importer_manager (robot_dart::gui::magnum::BaseApplication)
  • _lights (robot_dart::gui::magnum::BaseApplication)
  • _max_lights (robot_dart::gui::magnum::BaseApplication, robot_dart::gui::magnum::PhongMultiLight)
  • _prepare_shadows (robot_dart::gui::magnum::BaseApplication)
  • _scene (robot_dart::gui::magnum::BaseApplication)
  • _shadow_camera (robot_dart::gui::magnum::BaseApplication)
  • _shadow_camera_object (robot_dart::gui::magnum::BaseApplication)
  • _shadow_color_cube_map (robot_dart::gui::magnum::BaseApplication)
  • _shadow_color_shader (robot_dart::gui::magnum::BaseApplication)
  • _shadow_color_texture (robot_dart::gui::magnum::BaseApplication)
  • _shadow_cube_map (robot_dart::gui::magnum::BaseApplication)
  • _shadow_data (robot_dart::gui::magnum::BaseApplication)
  • _shadow_map_size (robot_dart::gui::magnum::BaseApplication)
  • _shadow_shader (robot_dart::gui::magnum::BaseApplication)
  • _shadow_texture (robot_dart::gui::magnum::BaseApplication)
  • _shadow_texture_color_shader (robot_dart::gui::magnum::BaseApplication)
  • _shadow_texture_shader (robot_dart::gui::magnum::BaseApplication)
  • _shadowed (robot_dart::gui::magnum::BaseApplication)
  • _shadowed_color_drawables (robot_dart::gui::magnum::BaseApplication)
  • _shadowed_drawables (robot_dart::gui::magnum::BaseApplication)
  • _text_indices (robot_dart::gui::magnum::BaseApplication)
  • _text_shader (robot_dart::gui::magnum::BaseApplication)
  • _text_vertices (robot_dart::gui::magnum::BaseApplication)
  • _texture_shader (robot_dart::gui::magnum::BaseApplication, robot_dart::gui::magnum::CubeMapShadowedColorObject, robot_dart::gui::magnum::CubeMapShadowedObject, robot_dart::gui::magnum::DrawableObject, robot_dart::gui::magnum::ShadowedColorObject, robot_dart::gui::magnum::ShadowedObject)
  • _transparentSize (robot_dart::gui::magnum::BaseApplication)
  • _transparent_shadows (robot_dart::gui::magnum::BaseApplication)
  • _enabled (robot_dart::gui::magnum::BaseGraphics)
  • _fps (robot_dart::gui::magnum::BaseGraphics)
  • _magnum_app (robot_dart::gui::magnum::BaseGraphics, robot_dart::gui::magnum::sensor::Camera)
  • _magnum_silence_output (robot_dart::gui::magnum::BaseGraphics)
  • _materials (robot_dart::gui::magnum::CubeMapShadowedColorObject, robot_dart::gui::magnum::CubeMapShadowedObject, robot_dart::gui::magnum::DrawableObject, robot_dart::gui::magnum::ShadowedColorObject, robot_dart::gui::magnum::ShadowedObject)
  • _meshes (robot_dart::gui::magnum::CubeMapShadowedColorObject, robot_dart::gui::magnum::CubeMapShadowedObject, robot_dart::gui::magnum::DrawableObject, robot_dart::gui::magnum::ShadowedColorObject, robot_dart::gui::magnum::ShadowedObject)
  • _scalings (robot_dart::gui::magnum::CubeMapShadowedColorObject, robot_dart::gui::magnum::CubeMapShadowedObject, robot_dart::gui::magnum::DrawableObject, robot_dart::gui::magnum::ShadowedColorObject, robot_dart::gui::magnum::ShadowedObject)
  • _shader (robot_dart::gui::magnum::CubeMapShadowedColorObject, robot_dart::gui::magnum::CubeMapShadowedObject, robot_dart::gui::magnum::ShadowedColorObject, robot_dart::gui::magnum::ShadowedObject)
  • _shape (robot_dart::gui::magnum::CubeMapShadowedColorObject, robot_dart::gui::magnum::CubeMapShadowedObject, robot_dart::gui::magnum::DrawableObject, robot_dart::gui::magnum::ShadowedColorObject, robot_dart::gui::magnum::ShadowedObject)
  • _has_negative_scaling (robot_dart::gui::magnum::DrawableObject)
  • _isTransparent (robot_dart::gui::magnum::DrawableObject)
  • _is_soft_body (robot_dart::gui::magnum::DrawableObject)
  • _bg_color (robot_dart::gui::magnum::GlfwApplication, robot_dart::gui::magnum::WindowlessGLApplication)
  • _draw_debug (robot_dart::gui::magnum::GlfwApplication, robot_dart::gui::magnum::WindowlessGLApplication, robot_dart::gui::magnum::sensor::Camera)
  • _draw_main_camera (robot_dart::gui::magnum::GlfwApplication, robot_dart::gui::magnum::WindowlessGLApplication)
  • _speed (robot_dart::gui::magnum::GlfwApplication, robot_dart::gui::magnum::Camera)
  • _speed_move (robot_dart::gui::magnum::GlfwApplication)
  • _speed_strafe (robot_dart::gui::magnum::GlfwApplication)
  • _context_mutex (robot_dart::gui::magnum::GlobalData)
  • _create_contexts (robot_dart::gui::magnum::GlobalData)
  • _gl_contexts (robot_dart::gui::magnum::GlobalData)
  • _max_contexts (robot_dart::gui::magnum::GlobalData)
  • _used (robot_dart::gui::magnum::GlobalData)
  • _color (robot_dart::gui::magnum::WindowlessGLApplication, robot_dart::gui::magnum::sensor::Camera)
  • _depth (robot_dart::gui::magnum::WindowlessGLApplication, robot_dart::gui::magnum::sensor::Camera)
  • _format (robot_dart::gui::magnum::WindowlessGLApplication, robot_dart::gui::magnum::sensor::Camera)
  • _framebuffer (robot_dart::gui::magnum::WindowlessGLApplication, robot_dart::gui::magnum::sensor::Camera)
  • _aspect_ratio (robot_dart::gui::magnum::Camera)
  • _camera_object (robot_dart::gui::magnum::Camera)
  • _clean_up_subprocess (robot_dart::gui::magnum::Camera)
  • _depth_image (robot_dart::gui::magnum::Camera)
  • _far_plane (robot_dart::gui::magnum::Camera)
  • _ffmpeg_process (robot_dart::gui::magnum::Camera)
  • _fov (robot_dart::gui::magnum::Camera)
  • _front (robot_dart::gui::magnum::Camera)
  • _height (robot_dart::gui::magnum::Camera, robot_dart::gui::magnum::sensor::Camera)
  • _image (robot_dart::gui::magnum::Camera)
  • _near_plane (robot_dart::gui::magnum::Camera)
  • _pitch_object (robot_dart::gui::magnum::Camera)
  • _recording (robot_dart::gui::magnum::Camera)
  • _recording_depth (robot_dart::gui::magnum::Camera)
  • _recording_video (robot_dart::gui::magnum::Camera)
  • _right (robot_dart::gui::magnum::Camera)
  • _up (robot_dart::gui::magnum::Camera)
  • _width (robot_dart::gui::magnum::Camera, robot_dart::gui::magnum::sensor::Camera)
  • _yaw_object (robot_dart::gui::magnum::Camera)
  • _diffuse_color_uniform (robot_dart::gui::magnum::CubeMap, robot_dart::gui::magnum::CubeMapColor, robot_dart::gui::magnum::PhongMultiLight, robot_dart::gui::magnum::ShadowMap, robot_dart::gui::magnum::ShadowMapColor)
  • _far_plane_uniform (robot_dart::gui::magnum::CubeMap, robot_dart::gui::magnum::CubeMapColor, robot_dart::gui::magnum::PhongMultiLight)
  • _flags (robot_dart::gui::magnum::CubeMap, robot_dart::gui::magnum::CubeMapColor, robot_dart::gui::magnum::PhongMultiLight, robot_dart::gui::magnum::ShadowMap, robot_dart::gui::magnum::ShadowMapColor)
  • _light_index_uniform (robot_dart::gui::magnum::CubeMap, robot_dart::gui::magnum::CubeMapColor)
  • _light_position_uniform (robot_dart::gui::magnum::CubeMap, robot_dart::gui::magnum::CubeMapColor)
  • _shadow_matrices_uniform (robot_dart::gui::magnum::CubeMap, robot_dart::gui::magnum::CubeMapColor)
  • _transformation_matrix_uniform (robot_dart::gui::magnum::CubeMap, robot_dart::gui::magnum::CubeMapColor, robot_dart::gui::magnum::PhongMultiLight, robot_dart::gui::magnum::ShadowMap, robot_dart::gui::magnum::ShadowMapColor)
  • _cube_map_textures_location (robot_dart::gui::magnum::CubeMapColor, robot_dart::gui::magnum::PhongMultiLight)
  • _attenuation (robot_dart::gui::magnum::Light)
  • _material (robot_dart::gui::magnum::Light)
  • _position (robot_dart::gui::magnum::Light)
  • _shadow_transform (robot_dart::gui::magnum::Light)
  • _spot_cut_off (robot_dart::gui::magnum::Light)
  • _spot_direction (robot_dart::gui::magnum::Light)
  • _spot_exponent (robot_dart::gui::magnum::Light)
  • _transformed_position (robot_dart::gui::magnum::Light)
  • _transformed_spot_direction (robot_dart::gui::magnum::Light)
  • _ambient (robot_dart::gui::magnum::Material)
  • _ambient_texture (robot_dart::gui::magnum::Material)
  • _diffuse (robot_dart::gui::magnum::Material)
  • _diffuse_texture (robot_dart::gui::magnum::Material)
  • _shininess (robot_dart::gui::magnum::Material)
  • _specular (robot_dart::gui::magnum::Material)
  • _specular_texture (robot_dart::gui::magnum::Material)
  • _ambient_color_uniform (robot_dart::gui::magnum::PhongMultiLight)
  • _camera_matrix_uniform (robot_dart::gui::magnum::PhongMultiLight)
  • _cube_map_color_textures_location (robot_dart::gui::magnum::PhongMultiLight)
  • _is_shadowed_uniform (robot_dart::gui::magnum::PhongMultiLight)
  • _light_loc_size (robot_dart::gui::magnum::PhongMultiLight)
  • _lights_matrices_uniform (robot_dart::gui::magnum::PhongMultiLight)
  • _lights_uniform (robot_dart::gui::magnum::PhongMultiLight)
  • _normal_matrix_uniform (robot_dart::gui::magnum::PhongMultiLight)
  • _projection_matrix_uniform (robot_dart::gui::magnum::PhongMultiLight, robot_dart::gui::magnum::ShadowMap, robot_dart::gui::magnum::ShadowMapColor)
  • _shadow_color_textures_location (robot_dart::gui::magnum::PhongMultiLight)
  • _shadow_textures_location (robot_dart::gui::magnum::PhongMultiLight)
  • _shininess_uniform (robot_dart::gui::magnum::PhongMultiLight)
  • _specular_color_uniform (robot_dart::gui::magnum::PhongMultiLight)
  • _specular_strength_uniform (robot_dart::gui::magnum::PhongMultiLight)
  • _transparent_shadows_uniform (robot_dart::gui::magnum::PhongMultiLight)
  • _imu (robot_dart::robots::A1, robot_dart::robots::ICub, robot_dart::robots::Talos)
  • _ft_wrist (robot_dart::robots::Franka, robot_dart::robots::Iiwa, robot_dart::robots::Tiago, robot_dart::robots::Ur3e)
  • _ft_foot_left (robot_dart::robots::ICub, robot_dart::robots::Talos)
  • _ft_foot_right (robot_dart::robots::ICub, robot_dart::robots::Talos)
  • _frequency (robot_dart::robots::Talos, robot_dart::sensor::Sensor)
  • _ft_wrist_left (robot_dart::robots::Talos)
  • _ft_wrist_right (robot_dart::robots::Talos)
  • _torques (robot_dart::robots::Talos, robot_dart::sensor::Torque)
  • _direction (robot_dart::sensor::ForceTorque)
  • _wrench (robot_dart::sensor::ForceTorque)
  • _angular_pos (robot_dart::sensor::IMU)
  • _angular_vel (robot_dart::sensor::IMU)
  • _config (robot_dart::sensor::IMU)
  • _linear_accel (robot_dart::sensor::IMU)
  • _attached_tf (robot_dart::sensor::Sensor)
  • _attached_to_body (robot_dart::sensor::Sensor)
  • _attached_to_joint (robot_dart::sensor::Sensor)
  • _attaching_to_body (robot_dart::sensor::Sensor)
  • _attaching_to_joint (robot_dart::sensor::Sensor)
  • _body_attached (robot_dart::sensor::Sensor)
  • _joint_attached (robot_dart::sensor::Sensor)
  • _world_pose (robot_dart::sensor::Sensor)
"},{"location":"api/class_member_functions/","title":"Class Member Functions","text":""},{"location":"api/class_member_functions/#a","title":"a","text":"
  • Assertion (robot_dart::Assertion)
  • acceleration_lower_limits (robot_dart::Robot)
  • acceleration_upper_limits (robot_dart::Robot)
  • accelerations (robot_dart::Robot)
  • active_controllers (robot_dart::Robot)
  • actuator_type (robot_dart::Robot)
  • actuator_types (robot_dart::Robot)
  • add_body_mass (robot_dart::Robot)
  • add_controller (robot_dart::Robot)
  • add_external_force (robot_dart::Robot)
  • add_external_torque (robot_dart::Robot)
  • adjacent_colliding (robot_dart::Robot)
  • aug_mass_matrix (robot_dart::Robot)
  • add_checkerboard_floor (robot_dart::RobotDARTSimu)
  • add_floor (robot_dart::RobotDARTSimu)
  • add_robot (robot_dart::RobotDARTSimu)
  • add_sensor (robot_dart::RobotDARTSimu)
  • add_text (robot_dart::RobotDARTSimu, robot_dart::simu::GUIData)
  • add_visual_robot (robot_dart::RobotDARTSimu)
  • add_to_map (robot_dart::collision_filter::BitmaskContactFilter)
  • activate (robot_dart::control::RobotControl, robot_dart::sensor::Sensor)
  • active (robot_dart::control::RobotControl, robot_dart::sensor::Sensor)
  • add_light (robot_dart::gui::magnum::BaseApplication, robot_dart::gui::magnum::BaseGraphics)
  • attach_camera (robot_dart::gui::magnum::BaseApplication)
  • attenuation (robot_dart::gui::magnum::Light)
  • ambient_color (robot_dart::gui::magnum::Material)
  • ambient_texture (robot_dart::gui::magnum::Material)
  • attach_to_body (robot_dart::gui::magnum::sensor::Camera, robot_dart::sensor::ForceTorque, robot_dart::sensor::Sensor, robot_dart::sensor::Torque)
  • attach_to_joint (robot_dart::gui::magnum::sensor::Camera, robot_dart::sensor::IMU, robot_dart::sensor::Sensor)
  • A1 (robot_dart::robots::A1)
  • Arm (robot_dart::robots::Arm)
  • angular_position (robot_dart::sensor::IMU)
  • angular_position_vec (robot_dart::sensor::IMU)
  • angular_velocity (robot_dart::sensor::IMU)
  • attached_to (robot_dart::sensor::Sensor)
"},{"location":"api/class_member_functions/#b","title":"b","text":"
  • base_pose (robot_dart::Robot)
  • base_pose_vec (robot_dart::Robot)
  • body_acceleration (robot_dart::Robot)
  • body_index (robot_dart::Robot)
  • body_mass (robot_dart::Robot)
  • body_name (robot_dart::Robot)
  • body_names (robot_dart::Robot)
  • body_node (robot_dart::Robot)
  • body_pose (robot_dart::Robot)
  • body_pose_vec (robot_dart::Robot)
  • body_velocity (robot_dart::Robot)
  • Base (robot_dart::gui::Base)
  • BaseApplication (robot_dart::gui::magnum::BaseApplication)
  • BaseGraphics (robot_dart::gui::magnum::BaseGraphics)
  • bind_cube_map_texture (robot_dart::gui::magnum::CubeMapColor, robot_dart::gui::magnum::PhongMultiLight)
  • bind_cube_map_color_texture (robot_dart::gui::magnum::PhongMultiLight)
  • bind_shadow_color_texture (robot_dart::gui::magnum::PhongMultiLight)
  • bind_shadow_texture (robot_dart::gui::magnum::PhongMultiLight)
"},{"location":"api/class_member_functions/#c","title":"c","text":"
  • cast_shadows (robot_dart::Robot, robot_dart::simu::GUIData)
  • clear_controllers (robot_dart::Robot)
  • clear_external_forces (robot_dart::Robot)
  • clear_internal_forces (robot_dart::Robot)
  • clone (robot_dart::Robot, robot_dart::control::PDControl, robot_dart::control::PolicyControl, robot_dart::control::RobotControl, robot_dart::control::SimpleControl)
  • clone_ghost (robot_dart::Robot)
  • com (robot_dart::Robot)
  • com_acceleration (robot_dart::Robot)
  • com_jacobian (robot_dart::Robot)
  • com_jacobian_deriv (robot_dart::Robot)
  • com_velocity (robot_dart::Robot)
  • commands (robot_dart::Robot)
  • constraint_forces (robot_dart::Robot)
  • controller (robot_dart::Robot)
  • controllers (robot_dart::Robot)
  • coriolis_forces (robot_dart::Robot)
  • coriolis_gravity_forces (robot_dart::Robot)
  • coulomb_coeffs (robot_dart::Robot)
  • create_box (robot_dart::Robot)
  • create_ellipsoid (robot_dart::Robot)
  • clear_robots (robot_dart::RobotDARTSimu)
  • clear_sensors (robot_dart::RobotDARTSimu)
  • collision_category (robot_dart::RobotDARTSimu)
  • collision_detector (robot_dart::RobotDARTSimu)
  • collision_mask (robot_dart::RobotDARTSimu)
  • collision_masks (robot_dart::RobotDARTSimu)
  • control_freq (robot_dart::RobotDARTSimu)
  • current_time (robot_dart::Scheduler)
  • clear_all (robot_dart::collision_filter::BitmaskContactFilter)
  • calculate (robot_dart::control::PDControl, robot_dart::control::PolicyControl, robot_dart::control::RobotControl, robot_dart::control::SimpleControl, robot_dart::gui::magnum::sensor::Camera, robot_dart::sensor::ForceTorque, robot_dart::sensor::IMU, robot_dart::sensor::Sensor, robot_dart::sensor::Torque)
  • configure (robot_dart::control::PDControl, robot_dart::control::PolicyControl, robot_dart::control::RobotControl, robot_dart::control::SimpleControl)
  • controllable_dofs (robot_dart::control::RobotControl)
  • camera (robot_dart::gui::magnum::BaseApplication, robot_dart::gui::magnum::BaseGraphics, robot_dart::gui::magnum::Camera, robot_dart::gui::magnum::sensor::Camera)
  • clear_lights (robot_dart::gui::magnum::BaseApplication, robot_dart::gui::magnum::BaseGraphics)
  • camera_extrinsic_matrix (robot_dart::gui::magnum::BaseGraphics, robot_dart::gui::magnum::sensor::Camera)
  • camera_intrinsic_matrix (robot_dart::gui::magnum::BaseGraphics, robot_dart::gui::magnum::sensor::Camera)
  • CubeMapShadowedColorObject (robot_dart::gui::magnum::CubeMapShadowedColorObject)
  • CubeMapShadowedObject (robot_dart::gui::magnum::CubeMapShadowedObject)
  • Camera (robot_dart::gui::magnum::Camera, robot_dart::gui::magnum::sensor::Camera)
  • camera_object (robot_dart::gui::magnum::Camera)
  • CubeMap (robot_dart::gui::magnum::CubeMap)
  • CubeMapColor (robot_dart::gui::magnum::CubeMapColor)
  • casts_shadows (robot_dart::gui::magnum::Light)
  • collision_vec (robot_dart::robots::TalosFastCollision)
  • caster_joints (robot_dart::robots::Tiago)
"},{"location":"api/class_member_functions/#d","title":"d","text":"
  • damping_coeffs (robot_dart::Robot)
  • dof (robot_dart::Robot)
  • dof_index (robot_dart::Robot)
  • dof_map (robot_dart::Robot)
  • dof_name (robot_dart::Robot)
  • dof_names (robot_dart::Robot)
  • drawing_axes (robot_dart::Robot, robot_dart::simu::GUIData)
  • dt (robot_dart::Scheduler)
  • depth_array (robot_dart::gui::Base, robot_dart::gui::magnum::BaseApplication, robot_dart::gui::magnum::BaseGraphics, robot_dart::gui::magnum::sensor::Camera)
  • depth_image (robot_dart::gui::Base, robot_dart::gui::magnum::BaseApplication, robot_dart::gui::magnum::BaseGraphics, robot_dart::gui::magnum::Camera, robot_dart::gui::magnum::sensor::Camera)
  • done (robot_dart::gui::Base, robot_dart::gui::magnum::BaseApplication, robot_dart::gui::magnum::BaseGraphics)
  • debug_draw_data (robot_dart::gui::magnum::BaseApplication)
  • drawables (robot_dart::gui::magnum::BaseApplication)
  • draw (robot_dart::gui::magnum::CubeMapShadowedColorObject, robot_dart::gui::magnum::CubeMapShadowedObject, robot_dart::gui::magnum::DrawableObject, robot_dart::gui::magnum::ShadowedColorObject, robot_dart::gui::magnum::ShadowedObject, robot_dart::gui::magnum::Camera)
  • DrawableObject (robot_dart::gui::magnum::DrawableObject)
  • drawEvent (robot_dart::gui::magnum::GlfwApplication)
  • default_configuration (robot_dart::gui::magnum::Graphics, robot_dart::gui::magnum::WindowlessGraphics)
  • diffuse_color (robot_dart::gui::magnum::Material)
  • diffuse_texture (robot_dart::gui::magnum::Material)
  • draw_debug (robot_dart::gui::magnum::sensor::Camera)
  • drawing_debug (robot_dart::gui::magnum::sensor::Camera)
  • detach (robot_dart::sensor::Sensor)
  • drawing_texts (robot_dart::simu::GUIData)
"},{"location":"api/class_member_functions/#e","title":"e","text":"
  • external_forces (robot_dart::Robot)
  • enable_status_bar (robot_dart::RobotDARTSimu)
  • enable_text_panel (robot_dart::RobotDARTSimu)
  • enable_shadows (robot_dart::gui::magnum::BaseApplication, robot_dart::gui::magnum::BaseGraphics)
  • exitEvent (robot_dart::gui::magnum::GlfwApplication)
  • exec (robot_dart::gui::magnum::WindowlessGLApplication)
  • extrinsic_matrix (robot_dart::gui::magnum::Camera)
"},{"location":"api/class_member_functions/#f","title":"f","text":"
  • fix_to_world (robot_dart::Robot)
  • fixed (robot_dart::Robot)
  • force_lower_limits (robot_dart::Robot)
  • force_position_bounds (robot_dart::Robot)
  • force_torque (robot_dart::Robot)
  • force_upper_limits (robot_dart::Robot)
  • forces (robot_dart::Robot)
  • free (robot_dart::Robot)
  • free_from_world (robot_dart::Robot)
  • friction_coeff (robot_dart::Robot)
  • friction_dir (robot_dart::Robot)
  • free_robot (robot_dart::RobotPool)
  • free_gl_context (robot_dart::gui::magnum::GlobalData)
  • far_plane (robot_dart::gui::magnum::Camera)
  • forward (robot_dart::gui::magnum::Camera)
  • fov (robot_dart::gui::magnum::Camera)
  • flags (robot_dart::gui::magnum::CubeMap, robot_dart::gui::magnum::CubeMapColor, robot_dart::gui::magnum::PhongMultiLight, robot_dart::gui::magnum::ShadowMap, robot_dart::gui::magnum::ShadowMapColor)
  • Franka (robot_dart::robots::Franka)
  • ft_wrist (robot_dart::robots::Franka, robot_dart::robots::Iiwa, robot_dart::robots::Tiago, robot_dart::robots::Ur3e)
  • ft_foot_left (robot_dart::robots::ICub, robot_dart::robots::Talos)
  • ft_foot_right (robot_dart::robots::ICub, robot_dart::robots::Talos)
  • ft_wrist_left (robot_dart::robots::Talos)
  • ft_wrist_right (robot_dart::robots::Talos)
  • ForceTorque (robot_dart::sensor::ForceTorque)
  • force (robot_dart::sensor::ForceTorque)
  • frequency (robot_dart::sensor::Sensor)
"},{"location":"api/class_member_functions/#g","title":"g","text":"
  • ghost (robot_dart::Robot, robot_dart::simu::GUIData)
  • gravity_forces (robot_dart::Robot)
  • graphics (robot_dart::RobotDARTSimu)
  • graphics_freq (robot_dart::RobotDARTSimu)
  • gravity (robot_dart::RobotDARTSimu)
  • gui_data (robot_dart::RobotDARTSimu)
  • get_robot (robot_dart::RobotPool)
  • GlfwApplication (robot_dart::gui::magnum::GlfwApplication)
  • GlobalData (robot_dart::gui::magnum::GlobalData)
  • gl_context (robot_dart::gui::magnum::GlobalData)
  • Graphics (robot_dart::gui::magnum::Graphics)
"},{"location":"api/class_member_functions/#h","title":"h","text":"
  • halted_sim (robot_dart::RobotDARTSimu)
  • h_params (robot_dart::control::PolicyControl)
  • height (robot_dart::gui::Base, robot_dart::gui::magnum::BaseGraphics, robot_dart::gui::magnum::Camera)
  • has_ambient_texture (robot_dart::gui::magnum::Material)
  • has_diffuse_texture (robot_dart::gui::magnum::Material)
  • has_specular_texture (robot_dart::gui::magnum::Material)
  • Hexapod (robot_dart::robots::Hexapod)
"},{"location":"api/class_member_functions/#i","title":"i","text":"
  • inv_aug_mass_matrix (robot_dart::Robot)
  • inv_mass_matrix (robot_dart::Robot)
  • it_duration (robot_dart::Scheduler)
  • ignoresCollision (robot_dart::collision_filter::BitmaskContactFilter)
  • init (robot_dart::control::RobotControl, robot_dart::gui::magnum::BaseApplication, robot_dart::gui::magnum::sensor::Camera, robot_dart::sensor::ForceTorque, robot_dart::sensor::IMU, robot_dart::sensor::Sensor, robot_dart::sensor::Torque)
  • image (robot_dart::gui::Base, robot_dart::gui::magnum::BaseApplication, robot_dart::gui::magnum::BaseGraphics, robot_dart::gui::magnum::Camera, robot_dart::gui::magnum::sensor::Camera)
  • instance (robot_dart::gui::magnum::GlobalData)
  • intrinsic_matrix (robot_dart::gui::magnum::Camera)
  • imu (robot_dart::robots::A1, robot_dart::robots::ICub, robot_dart::robots::Talos)
  • ICub (robot_dart::robots::ICub)
  • Iiwa (robot_dart::robots::Iiwa)
  • IMU (robot_dart::sensor::IMU)
  • IMUConfig (robot_dart::sensor::IMUConfig)
"},{"location":"api/class_member_functions/#j","title":"j","text":"
  • jacobian (robot_dart::Robot)
  • jacobian_deriv (robot_dart::Robot)
  • joint (robot_dart::Robot)
  • joint_index (robot_dart::Robot)
  • joint_map (robot_dart::Robot)
  • joint_name (robot_dart::Robot)
  • joint_names (robot_dart::Robot)
"},{"location":"api/class_member_functions/#k","title":"k","text":"
  • keyPressEvent (robot_dart::gui::magnum::GlfwApplication)
  • keyReleaseEvent (robot_dart::gui::magnum::GlfwApplication)
"},{"location":"api/class_member_functions/#l","title":"l","text":"
  • locked_dof_names (robot_dart::Robot)
  • last_it_duration (robot_dart::Scheduler)
  • light (robot_dart::gui::magnum::BaseApplication, robot_dart::gui::magnum::BaseGraphics)
  • lights (robot_dart::gui::magnum::BaseApplication, robot_dart::gui::magnum::BaseGraphics)
  • look_at (robot_dart::gui::magnum::BaseApplication, robot_dart::gui::magnum::BaseGraphics, robot_dart::gui::magnum::Camera, robot_dart::gui::magnum::sensor::Camera)
  • Light (robot_dart::gui::magnum::Light)
  • linear_acceleration (robot_dart::sensor::IMU)
"},{"location":"api/class_member_functions/#m","title":"m","text":"
  • mass_matrix (robot_dart::Robot)
  • mimic_dof_names (robot_dart::Robot)
  • model_filename (robot_dart::Robot, robot_dart::RobotPool)
  • model_packages (robot_dart::Robot)
  • mask (robot_dart::collision_filter::BitmaskContactFilter)
  • magnum_app (robot_dart::gui::magnum::BaseGraphics)
  • magnum_image (robot_dart::gui::magnum::BaseGraphics, robot_dart::gui::magnum::sensor::Camera)
  • materials (robot_dart::gui::magnum::DrawableObject)
  • mouseMoveEvent (robot_dart::gui::magnum::GlfwApplication)
  • mouseScrollEvent (robot_dart::gui::magnum::GlfwApplication)
  • move (robot_dart::gui::magnum::Camera)
  • material (robot_dart::gui::magnum::Light)
  • Material (robot_dart::gui::magnum::Material)
  • max_lights (robot_dart::gui::magnum::PhongMultiLight)
  • magnum_depth_image (robot_dart::gui::magnum::sensor::Camera)
"},{"location":"api/class_member_functions/#n","title":"n","text":"
  • name (robot_dart::Robot)
  • num_bodies (robot_dart::Robot)
  • num_controllers (robot_dart::Robot)
  • num_dofs (robot_dart::Robot)
  • num_joints (robot_dart::Robot)
  • num_robots (robot_dart::RobotDARTSimu)
  • next_time (robot_dart::Scheduler)
  • num_lights (robot_dart::gui::magnum::BaseApplication, robot_dart::gui::magnum::BaseGraphics)
  • near_plane (robot_dart::gui::magnum::Camera)
"},{"location":"api/class_member_functions/#o","title":"o","text":"
  • operator= (robot_dart::RobotPool, robot_dart::gui::magnum::GlobalData)
  • operator() (robot_dart::Scheduler)
"},{"location":"api/class_member_functions/#p","title":"p","text":"
  • passive_dof_names (robot_dart::Robot)
  • position_enforced (robot_dart::Robot)
  • position_lower_limits (robot_dart::Robot)
  • position_upper_limits (robot_dart::Robot)
  • positions (robot_dart::Robot)
  • physics_freq (robot_dart::RobotDARTSimu)
  • PDControl (robot_dart::control::PDControl)
  • pd (robot_dart::control::PDControl)
  • PolicyControl (robot_dart::control::PolicyControl)
  • parameters (robot_dart::control::RobotControl)
  • position (robot_dart::gui::magnum::Light)
  • PhongMultiLight (robot_dart::gui::magnum::PhongMultiLight)
  • Pendulum (robot_dart::robots::Pendulum)
  • pose (robot_dart::sensor::Sensor)
"},{"location":"api/class_member_functions/#r","title":"r","text":"
  • Robot (robot_dart::Robot)
  • reinit_controllers (robot_dart::Robot)
  • remove_all_drawing_axis (robot_dart::Robot)
  • remove_controller (robot_dart::Robot)
  • reset (robot_dart::Robot, robot_dart::Scheduler, robot_dart::robots::A1, robot_dart::robots::Hexapod, robot_dart::robots::ICub, robot_dart::robots::Talos, robot_dart::robots::Tiago)
  • reset_commands (robot_dart::Robot)
  • restitution_coeff (robot_dart::Robot)
  • RobotDARTSimu (robot_dart::RobotDARTSimu)
  • remove_all_collision_masks (robot_dart::RobotDARTSimu)
  • remove_collision_masks (robot_dart::RobotDARTSimu)
  • remove_robot (robot_dart::RobotDARTSimu, robot_dart::simu::GUIData)
  • remove_sensor (robot_dart::RobotDARTSimu)
  • remove_sensors (robot_dart::RobotDARTSimu)
  • robot (robot_dart::RobotDARTSimu, robot_dart::control::RobotControl)
  • robot_index (robot_dart::RobotDARTSimu)
  • robots (robot_dart::RobotDARTSimu)
  • run (robot_dart::RobotDARTSimu)
  • RobotPool (robot_dart::RobotPool)
  • real_time (robot_dart::Scheduler)
  • real_time_factor (robot_dart::Scheduler)
  • remove_from_map (robot_dart::collision_filter::BitmaskContactFilter)
  • RobotControl (robot_dart::control::RobotControl)
  • raw_depth_image (robot_dart::gui::Base, robot_dart::gui::magnum::BaseApplication, robot_dart::gui::magnum::BaseGraphics, robot_dart::gui::magnum::sensor::Camera)
  • refresh (robot_dart::gui::Base, robot_dart::gui::magnum::BaseGraphics, robot_dart::sensor::Sensor)
  • record_video (robot_dart::gui::magnum::BaseApplication, robot_dart::gui::magnum::BaseGraphics, robot_dart::gui::magnum::Camera, robot_dart::gui::magnum::sensor::Camera)
  • render (robot_dart::gui::magnum::BaseApplication, robot_dart::gui::magnum::GlfwApplication, robot_dart::gui::magnum::WindowlessGLApplication)
  • render_shadows (robot_dart::gui::magnum::BaseApplication)
  • record (robot_dart::gui::magnum::Camera)
  • recording (robot_dart::gui::magnum::Camera)
  • recording_depth (robot_dart::gui::magnum::Camera)
  • root_object (robot_dart::gui::magnum::Camera)
  • remove_text (robot_dart::simu::GUIData)
"},{"location":"api/class_member_functions/#s","title":"s","text":"
  • secondary_friction_coeff (robot_dart::Robot)
  • self_colliding (robot_dart::Robot)
  • set_acceleration_lower_limits (robot_dart::Robot)
  • set_acceleration_upper_limits (robot_dart::Robot)
  • set_accelerations (robot_dart::Robot)
  • set_actuator_type (robot_dart::Robot, robot_dart::robots::Tiago)
  • set_actuator_types (robot_dart::Robot, robot_dart::robots::Tiago)
  • set_base_pose (robot_dart::Robot)
  • set_body_mass (robot_dart::Robot)
  • set_body_name (robot_dart::Robot)
  • set_cast_shadows (robot_dart::Robot)
  • set_color_mode (robot_dart::Robot)
  • set_commands (robot_dart::Robot)
  • set_coulomb_coeffs (robot_dart::Robot)
  • set_damping_coeffs (robot_dart::Robot)
  • set_draw_axis (robot_dart::Robot)
  • set_external_force (robot_dart::Robot)
  • set_external_torque (robot_dart::Robot)
  • set_force_lower_limits (robot_dart::Robot)
  • set_force_upper_limits (robot_dart::Robot)
  • set_forces (robot_dart::Robot)
  • set_friction_coeff (robot_dart::Robot)
  • set_friction_coeffs (robot_dart::Robot)
  • set_friction_dir (robot_dart::Robot)
  • set_ghost (robot_dart::Robot)
  • set_joint_name (robot_dart::Robot)
  • set_mimic (robot_dart::Robot)
  • set_position_enforced (robot_dart::Robot)
  • set_position_lower_limits (robot_dart::Robot)
  • set_position_upper_limits (robot_dart::Robot)
  • set_positions (robot_dart::Robot)
  • set_restitution_coeff (robot_dart::Robot)
  • set_restitution_coeffs (robot_dart::Robot)
  • set_secondary_friction_coeff (robot_dart::Robot)
  • set_secondary_friction_coeffs (robot_dart::Robot)
  • set_self_collision (robot_dart::Robot)
  • set_spring_stiffnesses (robot_dart::Robot)
  • set_velocities (robot_dart::Robot)
  • set_velocity_lower_limits (robot_dart::Robot)
  • set_velocity_upper_limits (robot_dart::Robot)
  • skeleton (robot_dart::Robot)
  • spring_stiffnesses (robot_dart::Robot)
  • schedule (robot_dart::RobotDARTSimu, robot_dart::Scheduler)
  • scheduler (robot_dart::RobotDARTSimu)
  • sensor (robot_dart::RobotDARTSimu)
  • sensors (robot_dart::RobotDARTSimu)
  • set_collision_detector (robot_dart::RobotDARTSimu)
  • set_collision_masks (robot_dart::RobotDARTSimu)
  • set_control_freq (robot_dart::RobotDARTSimu)
  • set_graphics (robot_dart::RobotDARTSimu)
  • set_graphics_freq (robot_dart::RobotDARTSimu)
  • set_gravity (robot_dart::RobotDARTSimu)
  • set_text_panel (robot_dart::RobotDARTSimu)
  • set_timestep (robot_dart::RobotDARTSimu)
  • status_bar_text (robot_dart::RobotDARTSimu)
  • step (robot_dart::RobotDARTSimu, robot_dart::Scheduler)
  • step_world (robot_dart::RobotDARTSimu)
  • stop_sim (robot_dart::RobotDARTSimu)
  • Scheduler (robot_dart::Scheduler)
  • set_sync (robot_dart::Scheduler)
  • sync (robot_dart::Scheduler)
  • set_pd (robot_dart::control::PDControl)
  • set_use_angular_errors (robot_dart::control::PDControl)
  • set_h_params (robot_dart::control::PolicyControl)
  • set_parameters (robot_dart::control::RobotControl)
  • set_robot (robot_dart::control::RobotControl)
  • set_weight (robot_dart::control::RobotControl)
  • SimpleControl (robot_dart::control::SimpleControl)
  • set_enable (robot_dart::gui::Base, robot_dart::gui::magnum::BaseGraphics)
  • set_fps (robot_dart::gui::Base, robot_dart::gui::magnum::BaseGraphics)
  • set_render_period (robot_dart::gui::Base)
  • set_simu (robot_dart::gui::Base, robot_dart::gui::magnum::BaseGraphics, robot_dart::gui::magnum::Graphics, robot_dart::gui::magnum::WindowlessGraphics, robot_dart::sensor::Sensor)
  • simu (robot_dart::gui::Base, robot_dart::gui::magnum::CubeMapShadowedColorObject, robot_dart::gui::magnum::CubeMapShadowedObject, robot_dart::gui::magnum::DrawableObject, robot_dart::gui::magnum::ShadowedColorObject, robot_dart::gui::magnum::ShadowedObject, robot_dart::sensor::Sensor)
  • scene (robot_dart::gui::magnum::BaseApplication)
  • shadowed (robot_dart::gui::magnum::BaseApplication, robot_dart::gui::magnum::BaseGraphics)
  • set_materials (robot_dart::gui::magnum::CubeMapShadowedColorObject, robot_dart::gui::magnum::CubeMapShadowedObject, robot_dart::gui::magnum::DrawableObject, robot_dart::gui::magnum::ShadowedColorObject, robot_dart::gui::magnum::ShadowedObject)
  • set_meshes (robot_dart::gui::magnum::CubeMapShadowedColorObject, robot_dart::gui::magnum::CubeMapShadowedObject, robot_dart::gui::magnum::DrawableObject, robot_dart::gui::magnum::ShadowedColorObject, robot_dart::gui::magnum::ShadowedObject)
  • set_scalings (robot_dart::gui::magnum::CubeMapShadowedColorObject, robot_dart::gui::magnum::CubeMapShadowedObject, robot_dart::gui::magnum::DrawableObject, robot_dart::gui::magnum::ShadowedColorObject, robot_dart::gui::magnum::ShadowedObject)
  • shape (robot_dart::gui::magnum::CubeMapShadowedColorObject, robot_dart::gui::magnum::CubeMapShadowedObject, robot_dart::gui::magnum::DrawableObject, robot_dart::gui::magnum::ShadowedColorObject, robot_dart::gui::magnum::ShadowedObject)
  • set_color_shader (robot_dart::gui::magnum::DrawableObject)
  • set_soft_bodies (robot_dart::gui::magnum::DrawableObject)
  • set_texture_shader (robot_dart::gui::magnum::DrawableObject)
  • set_transparent (robot_dart::gui::magnum::DrawableObject)
  • set_max_contexts (robot_dart::gui::magnum::GlobalData)
  • ShadowedColorObject (robot_dart::gui::magnum::ShadowedColorObject)
  • ShadowedObject (robot_dart::gui::magnum::ShadowedObject)
  • set_camera_params (robot_dart::gui::magnum::Camera)
  • set_far_plane (robot_dart::gui::magnum::Camera, robot_dart::gui::magnum::CubeMap, robot_dart::gui::magnum::CubeMapColor, robot_dart::gui::magnum::PhongMultiLight)
  • set_fov (robot_dart::gui::magnum::Camera)
  • set_near_plane (robot_dart::gui::magnum::Camera)
  • set_speed (robot_dart::gui::magnum::Camera)
  • set_viewport (robot_dart::gui::magnum::Camera)
  • speed (robot_dart::gui::magnum::Camera)
  • strafe (robot_dart::gui::magnum::Camera)
  • set_light_index (robot_dart::gui::magnum::CubeMap, robot_dart::gui::magnum::CubeMapColor)
  • set_light_position (robot_dart::gui::magnum::CubeMap, robot_dart::gui::magnum::CubeMapColor)
  • set_material (robot_dart::gui::magnum::CubeMap, robot_dart::gui::magnum::CubeMapColor, robot_dart::gui::magnum::Light, robot_dart::gui::magnum::PhongMultiLight, robot_dart::gui::magnum::ShadowMap, robot_dart::gui::magnum::ShadowMapColor)
  • set_shadow_matrices (robot_dart::gui::magnum::CubeMap, robot_dart::gui::magnum::CubeMapColor)
  • set_transformation_matrix (robot_dart::gui::magnum::CubeMap, robot_dart::gui::magnum::CubeMapColor, robot_dart::gui::magnum::PhongMultiLight, robot_dart::gui::magnum::ShadowMap, robot_dart::gui::magnum::ShadowMapColor)
  • set_attenuation (robot_dart::gui::magnum::Light)
  • set_casts_shadows (robot_dart::gui::magnum::Light)
  • set_position (robot_dart::gui::magnum::Light)
  • set_shadow_matrix (robot_dart::gui::magnum::Light)
  • set_spot_cut_off (robot_dart::gui::magnum::Light)
  • set_spot_direction (robot_dart::gui::magnum::Light)
  • set_spot_exponent (robot_dart::gui::magnum::Light)
  • set_transformed_position (robot_dart::gui::magnum::Light)
  • set_transformed_spot_direction (robot_dart::gui::magnum::Light)
  • shadow_matrix (robot_dart::gui::magnum::Light)
  • spot_cut_off (robot_dart::gui::magnum::Light)
  • spot_direction (robot_dart::gui::magnum::Light)
  • spot_exponent (robot_dart::gui::magnum::Light)
  • set_ambient_color (robot_dart::gui::magnum::Material)
  • set_ambient_texture (robot_dart::gui::magnum::Material)
  • set_diffuse_color (robot_dart::gui::magnum::Material)
  • set_diffuse_texture (robot_dart::gui::magnum::Material)
  • set_shininess (robot_dart::gui::magnum::Material)
  • set_specular_color (robot_dart::gui::magnum::Material)
  • set_specular_texture (robot_dart::gui::magnum::Material)
  • shininess (robot_dart::gui::magnum::Material)
  • specular_color (robot_dart::gui::magnum::Material)
  • specular_texture (robot_dart::gui::magnum::Material)
  • set_camera_matrix (robot_dart::gui::magnum::PhongMultiLight)
  • set_is_shadowed (robot_dart::gui::magnum::PhongMultiLight)
  • set_light (robot_dart::gui::magnum::PhongMultiLight)
  • set_normal_matrix (robot_dart::gui::magnum::PhongMultiLight)
  • set_projection_matrix (robot_dart::gui::magnum::PhongMultiLight, robot_dart::gui::magnum::ShadowMap, robot_dart::gui::magnum::ShadowMapColor)
  • set_specular_strength (robot_dart::gui::magnum::PhongMultiLight)
  • set_transparent_shadows (robot_dart::gui::magnum::PhongMultiLight)
  • ShadowMap (robot_dart::gui::magnum::ShadowMap)
  • ShadowMapColor (robot_dart::gui::magnum::ShadowMapColor)
  • Sensor (robot_dart::sensor::Sensor)
  • set_frequency (robot_dart::sensor::Sensor)
  • set_pose (robot_dart::sensor::Sensor)
"},{"location":"api/class_member_functions/#t","title":"t","text":"
  • text_panel_text (robot_dart::RobotDARTSimu)
  • timestep (robot_dart::RobotDARTSimu)
  • transparent_shadows (robot_dart::gui::magnum::BaseApplication, robot_dart::gui::magnum::BaseGraphics)
  • transparent (robot_dart::gui::magnum::DrawableObject)
  • transform_lights (robot_dart::gui::magnum::Camera)
  • transformed_position (robot_dart::gui::magnum::Light)
  • transformed_spot_direction (robot_dart::gui::magnum::Light)
  • type (robot_dart::gui::magnum::sensor::Camera, robot_dart::sensor::ForceTorque, robot_dart::sensor::IMU, robot_dart::sensor::Sensor, robot_dart::sensor::Torque)
  • Talos (robot_dart::robots::Talos)
  • torques (robot_dart::robots::Talos, robot_dart::sensor::Torque)
  • TalosFastCollision (robot_dart::robots::TalosFastCollision)
  • TalosLight (robot_dart::robots::TalosLight)
  • Tiago (robot_dart::robots::Tiago)
  • torque (robot_dart::sensor::ForceTorque)
  • Torque (robot_dart::sensor::Torque)
"},{"location":"api/class_member_functions/#u","title":"u","text":"
  • update (robot_dart::Robot)
  • update_joint_dof_maps (robot_dart::Robot)
  • using_angular_errors (robot_dart::control::PDControl)
  • update_graphics (robot_dart::gui::magnum::BaseApplication)
  • update_lights (robot_dart::gui::magnum::BaseApplication)
  • Ur3e (robot_dart::robots::Ur3e)
  • Ur3eHand (robot_dart::robots::Ur3eHand)
  • update_robot (robot_dart::simu::GUIData)
"},{"location":"api/class_member_functions/#v","title":"v","text":"
  • vec_dof (robot_dart::Robot)
  • velocities (robot_dart::Robot)
  • velocity_lower_limits (robot_dart::Robot)
  • velocity_upper_limits (robot_dart::Robot)
  • viewportEvent (robot_dart::gui::magnum::GlfwApplication)
  • Vx300 (robot_dart::robots::Vx300)
"},{"location":"api/class_member_functions/#w","title":"w","text":"
  • what (robot_dart::Assertion)
  • world (robot_dart::RobotDARTSimu)
  • weight (robot_dart::control::RobotControl)
  • width (robot_dart::gui::Base, robot_dart::gui::magnum::BaseGraphics, robot_dart::gui::magnum::Camera)
  • WindowlessGLApplication (robot_dart::gui::magnum::WindowlessGLApplication)
  • WindowlessGraphics (robot_dart::gui::magnum::WindowlessGraphics)
  • wrench (robot_dart::sensor::ForceTorque)
"},{"location":"api/class_member_functions/#_1","title":"~","text":"
  • ~Robot (robot_dart::Robot)
  • ~RobotDARTSimu (robot_dart::RobotDARTSimu)
  • ~RobotPool (robot_dart::RobotPool)
  • ~BitmaskContactFilter (robot_dart::collision_filter::BitmaskContactFilter)
  • ~RobotControl (robot_dart::control::RobotControl)
  • ~Base (robot_dart::gui::Base)
  • ~BaseApplication (robot_dart::gui::magnum::BaseApplication)
  • ~BaseGraphics (robot_dart::gui::magnum::BaseGraphics)
  • ~GlfwApplication (robot_dart::gui::magnum::GlfwApplication)
  • ~GlobalData (robot_dart::gui::magnum::GlobalData)
  • ~Graphics (robot_dart::gui::magnum::Graphics)
  • ~WindowlessGLApplication (robot_dart::gui::magnum::WindowlessGLApplication)
  • ~WindowlessGraphics (robot_dart::gui::magnum::WindowlessGraphics)
  • ~Camera (robot_dart::gui::magnum::Camera, robot_dart::gui::magnum::sensor::Camera)
  • ~Sensor (robot_dart::sensor::Sensor)
"},{"location":"api/class_member_functions/#_","title":"_","text":"
  • _make_message (robot_dart::Assertion)
  • _actuator_type (robot_dart::Robot)
  • _actuator_types (robot_dart::Robot)
  • _get_path (robot_dart::Robot)
  • _jacobian (robot_dart::Robot)
  • _load_model (robot_dart::Robot)
  • _mass_matrix (robot_dart::Robot)
  • _post_addition (robot_dart::Robot, robot_dart::robots::Franka, robot_dart::robots::ICub, robot_dart::robots::Iiwa, robot_dart::robots::Talos, robot_dart::robots::TalosFastCollision, robot_dart::robots::Tiago, robot_dart::robots::Ur3e)
  • _post_removal (robot_dart::Robot, robot_dart::robots::Franka, robot_dart::robots::ICub, robot_dart::robots::Iiwa, robot_dart::robots::Talos, robot_dart::robots::Tiago, robot_dart::robots::Ur3e)
  • _set_actuator_type (robot_dart::Robot)
  • _set_actuator_types (robot_dart::Robot)
  • _set_color_mode (robot_dart::Robot)
  • _enable (robot_dart::RobotDARTSimu)
  • _reset_robot (robot_dart::RobotPool)
  • _angle_dist (robot_dart::control::PDControl)
  • _gl_clean_up (robot_dart::gui::magnum::BaseApplication)
  • _prepare_shadows (robot_dart::gui::magnum::BaseApplication)
  • _create_contexts (robot_dart::gui::magnum::GlobalData)
  • _clean_up_subprocess (robot_dart::gui::magnum::Camera)
"},{"location":"api/class_member_variables/","title":"Class Member Variables","text":""},{"location":"api/class_member_variables/#a","title":"a","text":"
  • axes_mesh (robot_dart::gui::magnum::DebugDrawData)
  • axes_shader (robot_dart::gui::magnum::DebugDrawData)
  • accel_bias (robot_dart::sensor::IMUConfig)
  • alignment (robot_dart::simu::TextData)
"},{"location":"api/class_member_variables/#b","title":"b","text":"
  • background_mesh (robot_dart::gui::magnum::DebugDrawData)
  • background_shader (robot_dart::gui::magnum::DebugDrawData)
  • bg_color (robot_dart::gui::magnum::GraphicsConfiguration)
  • body (robot_dart::sensor::IMUConfig)
  • background_color (robot_dart::simu::TextData)
"},{"location":"api/class_member_variables/#c","title":"c","text":"
  • category_mask (robot_dart::collision_filter::BitmaskContactFilter::Masks)
  • collision_mask (robot_dart::collision_filter::BitmaskContactFilter::Masks)
  • channels (robot_dart::gui::Image)
  • cache (robot_dart::gui::magnum::DebugDrawData)
  • cubemapped (robot_dart::gui::magnum::ObjectStruct)
  • cubemapped_color (robot_dart::gui::magnum::ObjectStruct)
  • color (robot_dart::simu::TextData)
  • casting_shadows (robot_dart::simu::GUIData::RobotData)
"},{"location":"api/class_member_variables/#d","title":"d","text":"
  • data (robot_dart::gui::DepthImage, robot_dart::gui::GrayscaleImage, robot_dart::gui::Image)
  • draw_debug (robot_dart::gui::magnum::GraphicsConfiguration)
  • draw_main_camera (robot_dart::gui::magnum::GraphicsConfiguration)
  • draw_text (robot_dart::gui::magnum::GraphicsConfiguration)
  • drawable (robot_dart::gui::magnum::ObjectStruct)
  • draw_background (robot_dart::simu::TextData)
"},{"location":"api/class_member_variables/#f","title":"f","text":"
  • font (robot_dart::gui::magnum::DebugDrawData)
  • frequency (robot_dart::sensor::IMUConfig)
  • font_size (robot_dart::simu::TextData)
"},{"location":"api/class_member_variables/#g","title":"g","text":"
  • gyro_bias (robot_dart::sensor::IMUConfig)
"},{"location":"api/class_member_variables/#h","title":"h","text":"
  • height (robot_dart::gui::DepthImage, robot_dart::gui::GrayscaleImage, robot_dart::gui::Image, robot_dart::gui::magnum::GraphicsConfiguration)
"},{"location":"api/class_member_variables/#i","title":"i","text":"
  • is_ghost (robot_dart::simu::GUIData::RobotData)
"},{"location":"api/class_member_variables/#m","title":"m","text":"
  • max_lights (robot_dart::gui::magnum::GraphicsConfiguration)
"},{"location":"api/class_member_variables/#r","title":"r","text":"
  • robot_axes (robot_dart::simu::GUIData)
  • robot_data (robot_dart::simu::GUIData)
"},{"location":"api/class_member_variables/#s","title":"s","text":"
  • shadow_map_size (robot_dart::gui::magnum::GraphicsConfiguration)
  • shadowed (robot_dart::gui::magnum::GraphicsConfiguration, robot_dart::gui::magnum::ObjectStruct)
  • specular_strength (robot_dart::gui::magnum::GraphicsConfiguration)
  • shadowed_color (robot_dart::gui::magnum::ObjectStruct)
  • shadow_color_framebuffer (robot_dart::gui::magnum::ShadowData)
  • shadow_framebuffer (robot_dart::gui::magnum::ShadowData)
"},{"location":"api/class_member_variables/#t","title":"t","text":"
  • text_indices (robot_dart::gui::magnum::DebugDrawData)
  • text_shader (robot_dart::gui::magnum::DebugDrawData)
  • text_vertices (robot_dart::gui::magnum::DebugDrawData)
  • title (robot_dart::gui::magnum::GraphicsConfiguration)
  • transparent_shadows (robot_dart::gui::magnum::GraphicsConfiguration)
  • text_drawings (robot_dart::simu::GUIData)
  • text (robot_dart::simu::TextData)
  • transformation (robot_dart::simu::TextData)
"},{"location":"api/class_member_variables/#w","title":"w","text":"
  • width (robot_dart::gui::DepthImage, robot_dart::gui::GrayscaleImage, robot_dart::gui::Image, robot_dart::gui::magnum::GraphicsConfiguration)
"},{"location":"api/class_member_variables/#_","title":"_","text":"
  • _msg (robot_dart::Assertion)
  • _axis_shapes (robot_dart::Robot)
  • _cast_shadows (robot_dart::Robot, robot_dart::gui::magnum::Light)
  • _controllers (robot_dart::Robot)
  • _dof_map (robot_dart::Robot)
  • _is_ghost (robot_dart::Robot)
  • _joint_map (robot_dart::Robot)
  • _model_filename (robot_dart::Robot, robot_dart::RobotPool)
  • _packages (robot_dart::Robot)
  • _robot_name (robot_dart::Robot)
  • _skeleton (robot_dart::Robot)
  • _break (robot_dart::RobotDARTSimu)
  • _control_freq (robot_dart::RobotDARTSimu)
  • _graphics (robot_dart::RobotDARTSimu)
  • _graphics_freq (robot_dart::RobotDARTSimu)
  • _gui_data (robot_dart::RobotDARTSimu)
  • _old_index (robot_dart::RobotDARTSimu)
  • _physics_freq (robot_dart::RobotDARTSimu)
  • _robots (robot_dart::RobotDARTSimu)
  • _scheduler (robot_dart::RobotDARTSimu)
  • _sensors (robot_dart::RobotDARTSimu)
  • _status_bar (robot_dart::RobotDARTSimu)
  • _text_panel (robot_dart::RobotDARTSimu)
  • _world (robot_dart::RobotDARTSimu)
  • _free (robot_dart::RobotPool)
  • _pool_size (robot_dart::RobotPool)
  • _robot_creator (robot_dart::RobotPool)
  • _skeleton_mutex (robot_dart::RobotPool)
  • _skeletons (robot_dart::RobotPool)
  • _verbose (robot_dart::RobotPool)
  • _average_it_duration (robot_dart::Scheduler)
  • _current_step (robot_dart::Scheduler)
  • _current_time (robot_dart::Scheduler)
  • _dt (robot_dart::Scheduler, robot_dart::control::PolicyControl)
  • _it_duration (robot_dart::Scheduler)
  • _last_iteration_time (robot_dart::Scheduler)
  • _max_frequency (robot_dart::Scheduler)
  • _real_start_time (robot_dart::Scheduler)
  • _real_time (robot_dart::Scheduler)
  • _simu_start_time (robot_dart::Scheduler)
  • _start_time (robot_dart::Scheduler)
  • _sync (robot_dart::Scheduler)
  • _bitmask_map (robot_dart::collision_filter::BitmaskContactFilter)
  • _Kd (robot_dart::control::PDControl)
  • _Kp (robot_dart::control::PDControl)
  • _use_angular_errors (robot_dart::control::PDControl)
  • _first (robot_dart::control::PolicyControl)
  • _full_dt (robot_dart::control::PolicyControl)
  • _i (robot_dart::control::PolicyControl)
  • _policy (robot_dart::control::PolicyControl)
  • _prev_commands (robot_dart::control::PolicyControl)
  • _prev_time (robot_dart::control::PolicyControl)
  • _threshold (robot_dart::control::PolicyControl)
  • _active (robot_dart::control::RobotControl, robot_dart::sensor::Sensor)
  • _check_free (robot_dart::control::RobotControl)
  • _control_dof (robot_dart::control::RobotControl)
  • _controllable_dofs (robot_dart::control::RobotControl)
  • _ctrl (robot_dart::control::RobotControl)
  • _dof (robot_dart::control::RobotControl)
  • _robot (robot_dart::control::RobotControl)
  • _weight (robot_dart::control::RobotControl)
  • _simu (robot_dart::gui::Base, robot_dart::gui::magnum::BaseApplication, robot_dart::gui::magnum::CubeMapShadowedColorObject, robot_dart::gui::magnum::CubeMapShadowedObject, robot_dart::gui::magnum::DrawableObject, robot_dart::gui::magnum::GlfwApplication, robot_dart::gui::magnum::ShadowedColorObject, robot_dart::gui::magnum::ShadowedObject, robot_dart::gui::magnum::WindowlessGLApplication, robot_dart::sensor::Sensor)
  • _3D_axis_mesh (robot_dart::gui::magnum::BaseApplication)
  • _3D_axis_shader (robot_dart::gui::magnum::BaseApplication)
  • _background_mesh (robot_dart::gui::magnum::BaseApplication)
  • _background_shader (robot_dart::gui::magnum::BaseApplication)
  • _camera (robot_dart::gui::magnum::BaseApplication, robot_dart::gui::magnum::Camera, robot_dart::gui::magnum::sensor::Camera)
  • _color_shader (robot_dart::gui::magnum::BaseApplication, robot_dart::gui::magnum::DrawableObject)
  • _configuration (robot_dart::gui::magnum::BaseApplication, robot_dart::gui::magnum::BaseGraphics)
  • _cubemap_color_drawables (robot_dart::gui::magnum::BaseApplication)
  • _cubemap_color_shader (robot_dart::gui::magnum::BaseApplication)
  • _cubemap_drawables (robot_dart::gui::magnum::BaseApplication)
  • _cubemap_shader (robot_dart::gui::magnum::BaseApplication)
  • _cubemap_texture_color_shader (robot_dart::gui::magnum::BaseApplication)
  • _cubemap_texture_shader (robot_dart::gui::magnum::BaseApplication)
  • _dart_world (robot_dart::gui::magnum::BaseApplication)
  • _done (robot_dart::gui::magnum::BaseApplication)
  • _drawable_objects (robot_dart::gui::magnum::BaseApplication)
  • _drawables (robot_dart::gui::magnum::BaseApplication)
  • _font (robot_dart::gui::magnum::BaseApplication)
  • _font_manager (robot_dart::gui::magnum::BaseApplication)
  • _glyph_cache (robot_dart::gui::magnum::BaseApplication)
  • _importer_manager (robot_dart::gui::magnum::BaseApplication)
  • _lights (robot_dart::gui::magnum::BaseApplication)
  • _max_lights (robot_dart::gui::magnum::BaseApplication, robot_dart::gui::magnum::PhongMultiLight)
  • _scene (robot_dart::gui::magnum::BaseApplication)
  • _shadow_camera (robot_dart::gui::magnum::BaseApplication)
  • _shadow_camera_object (robot_dart::gui::magnum::BaseApplication)
  • _shadow_color_cube_map (robot_dart::gui::magnum::BaseApplication)
  • _shadow_color_shader (robot_dart::gui::magnum::BaseApplication)
  • _shadow_color_texture (robot_dart::gui::magnum::BaseApplication)
  • _shadow_cube_map (robot_dart::gui::magnum::BaseApplication)
  • _shadow_data (robot_dart::gui::magnum::BaseApplication)
  • _shadow_map_size (robot_dart::gui::magnum::BaseApplication)
  • _shadow_shader (robot_dart::gui::magnum::BaseApplication)
  • _shadow_texture (robot_dart::gui::magnum::BaseApplication)
  • _shadow_texture_color_shader (robot_dart::gui::magnum::BaseApplication)
  • _shadow_texture_shader (robot_dart::gui::magnum::BaseApplication)
  • _shadowed (robot_dart::gui::magnum::BaseApplication)
  • _shadowed_color_drawables (robot_dart::gui::magnum::BaseApplication)
  • _shadowed_drawables (robot_dart::gui::magnum::BaseApplication)
  • _text_indices (robot_dart::gui::magnum::BaseApplication)
  • _text_shader (robot_dart::gui::magnum::BaseApplication)
  • _text_vertices (robot_dart::gui::magnum::BaseApplication)
  • _texture_shader (robot_dart::gui::magnum::BaseApplication, robot_dart::gui::magnum::CubeMapShadowedColorObject, robot_dart::gui::magnum::CubeMapShadowedObject, robot_dart::gui::magnum::DrawableObject, robot_dart::gui::magnum::ShadowedColorObject, robot_dart::gui::magnum::ShadowedObject)
  • _transparentSize (robot_dart::gui::magnum::BaseApplication)
  • _transparent_shadows (robot_dart::gui::magnum::BaseApplication)
  • _enabled (robot_dart::gui::magnum::BaseGraphics)
  • _fps (robot_dart::gui::magnum::BaseGraphics)
  • _magnum_app (robot_dart::gui::magnum::BaseGraphics, robot_dart::gui::magnum::sensor::Camera)
  • _magnum_silence_output (robot_dart::gui::magnum::BaseGraphics)
  • _materials (robot_dart::gui::magnum::CubeMapShadowedColorObject, robot_dart::gui::magnum::CubeMapShadowedObject, robot_dart::gui::magnum::DrawableObject, robot_dart::gui::magnum::ShadowedColorObject, robot_dart::gui::magnum::ShadowedObject)
  • _meshes (robot_dart::gui::magnum::CubeMapShadowedColorObject, robot_dart::gui::magnum::CubeMapShadowedObject, robot_dart::gui::magnum::DrawableObject, robot_dart::gui::magnum::ShadowedColorObject, robot_dart::gui::magnum::ShadowedObject)
  • _scalings (robot_dart::gui::magnum::CubeMapShadowedColorObject, robot_dart::gui::magnum::CubeMapShadowedObject, robot_dart::gui::magnum::DrawableObject, robot_dart::gui::magnum::ShadowedColorObject, robot_dart::gui::magnum::ShadowedObject)
  • _shader (robot_dart::gui::magnum::CubeMapShadowedColorObject, robot_dart::gui::magnum::CubeMapShadowedObject, robot_dart::gui::magnum::ShadowedColorObject, robot_dart::gui::magnum::ShadowedObject)
  • _shape (robot_dart::gui::magnum::CubeMapShadowedColorObject, robot_dart::gui::magnum::CubeMapShadowedObject, robot_dart::gui::magnum::DrawableObject, robot_dart::gui::magnum::ShadowedColorObject, robot_dart::gui::magnum::ShadowedObject)
  • _has_negative_scaling (robot_dart::gui::magnum::DrawableObject)
  • _isTransparent (robot_dart::gui::magnum::DrawableObject)
  • _is_soft_body (robot_dart::gui::magnum::DrawableObject)
  • _bg_color (robot_dart::gui::magnum::GlfwApplication, robot_dart::gui::magnum::WindowlessGLApplication)
  • _draw_debug (robot_dart::gui::magnum::GlfwApplication, robot_dart::gui::magnum::WindowlessGLApplication, robot_dart::gui::magnum::sensor::Camera)
  • _draw_main_camera (robot_dart::gui::magnum::GlfwApplication, robot_dart::gui::magnum::WindowlessGLApplication)
  • _speed (robot_dart::gui::magnum::GlfwApplication, robot_dart::gui::magnum::Camera)
  • _speed_move (robot_dart::gui::magnum::GlfwApplication)
  • _speed_strafe (robot_dart::gui::magnum::GlfwApplication)
  • _context_mutex (robot_dart::gui::magnum::GlobalData)
  • _gl_contexts (robot_dart::gui::magnum::GlobalData)
  • _max_contexts (robot_dart::gui::magnum::GlobalData)
  • _used (robot_dart::gui::magnum::GlobalData)
  • _color (robot_dart::gui::magnum::WindowlessGLApplication, robot_dart::gui::magnum::sensor::Camera)
  • _depth (robot_dart::gui::magnum::WindowlessGLApplication, robot_dart::gui::magnum::sensor::Camera)
  • _format (robot_dart::gui::magnum::WindowlessGLApplication, robot_dart::gui::magnum::sensor::Camera)
  • _framebuffer (robot_dart::gui::magnum::WindowlessGLApplication, robot_dart::gui::magnum::sensor::Camera)
  • _aspect_ratio (robot_dart::gui::magnum::Camera)
  • _camera_object (robot_dart::gui::magnum::Camera)
  • _depth_image (robot_dart::gui::magnum::Camera)
  • _far_plane (robot_dart::gui::magnum::Camera)
  • _ffmpeg_process (robot_dart::gui::magnum::Camera)
  • _fov (robot_dart::gui::magnum::Camera)
  • _front (robot_dart::gui::magnum::Camera)
  • _height (robot_dart::gui::magnum::Camera, robot_dart::gui::magnum::sensor::Camera)
  • _image (robot_dart::gui::magnum::Camera)
  • _near_plane (robot_dart::gui::magnum::Camera)
  • _pitch_object (robot_dart::gui::magnum::Camera)
  • _recording (robot_dart::gui::magnum::Camera)
  • _recording_depth (robot_dart::gui::magnum::Camera)
  • _recording_video (robot_dart::gui::magnum::Camera)
  • _right (robot_dart::gui::magnum::Camera)
  • _up (robot_dart::gui::magnum::Camera)
  • _width (robot_dart::gui::magnum::Camera, robot_dart::gui::magnum::sensor::Camera)
  • _yaw_object (robot_dart::gui::magnum::Camera)
  • _diffuse_color_uniform (robot_dart::gui::magnum::CubeMap, robot_dart::gui::magnum::CubeMapColor, robot_dart::gui::magnum::PhongMultiLight, robot_dart::gui::magnum::ShadowMap, robot_dart::gui::magnum::ShadowMapColor)
  • _far_plane_uniform (robot_dart::gui::magnum::CubeMap, robot_dart::gui::magnum::CubeMapColor, robot_dart::gui::magnum::PhongMultiLight)
  • _flags (robot_dart::gui::magnum::CubeMap, robot_dart::gui::magnum::CubeMapColor, robot_dart::gui::magnum::PhongMultiLight, robot_dart::gui::magnum::ShadowMap, robot_dart::gui::magnum::ShadowMapColor)
  • _light_index_uniform (robot_dart::gui::magnum::CubeMap, robot_dart::gui::magnum::CubeMapColor)
  • _light_position_uniform (robot_dart::gui::magnum::CubeMap, robot_dart::gui::magnum::CubeMapColor)
  • _shadow_matrices_uniform (robot_dart::gui::magnum::CubeMap, robot_dart::gui::magnum::CubeMapColor)
  • _transformation_matrix_uniform (robot_dart::gui::magnum::CubeMap, robot_dart::gui::magnum::CubeMapColor, robot_dart::gui::magnum::PhongMultiLight, robot_dart::gui::magnum::ShadowMap, robot_dart::gui::magnum::ShadowMapColor)
  • _cube_map_textures_location (robot_dart::gui::magnum::CubeMapColor, robot_dart::gui::magnum::PhongMultiLight)
  • _attenuation (robot_dart::gui::magnum::Light)
  • _material (robot_dart::gui::magnum::Light)
  • _position (robot_dart::gui::magnum::Light)
  • _shadow_transform (robot_dart::gui::magnum::Light)
  • _spot_cut_off (robot_dart::gui::magnum::Light)
  • _spot_direction (robot_dart::gui::magnum::Light)
  • _spot_exponent (robot_dart::gui::magnum::Light)
  • _transformed_position (robot_dart::gui::magnum::Light)
  • _transformed_spot_direction (robot_dart::gui::magnum::Light)
  • _ambient (robot_dart::gui::magnum::Material)
  • _ambient_texture (robot_dart::gui::magnum::Material)
  • _diffuse (robot_dart::gui::magnum::Material)
  • _diffuse_texture (robot_dart::gui::magnum::Material)
  • _shininess (robot_dart::gui::magnum::Material)
  • _specular (robot_dart::gui::magnum::Material)
  • _specular_texture (robot_dart::gui::magnum::Material)
  • _ambient_color_uniform (robot_dart::gui::magnum::PhongMultiLight)
  • _camera_matrix_uniform (robot_dart::gui::magnum::PhongMultiLight)
  • _cube_map_color_textures_location (robot_dart::gui::magnum::PhongMultiLight)
  • _is_shadowed_uniform (robot_dart::gui::magnum::PhongMultiLight)
  • _light_loc_size (robot_dart::gui::magnum::PhongMultiLight)
  • _lights_matrices_uniform (robot_dart::gui::magnum::PhongMultiLight)
  • _lights_uniform (robot_dart::gui::magnum::PhongMultiLight)
  • _normal_matrix_uniform (robot_dart::gui::magnum::PhongMultiLight)
  • _projection_matrix_uniform (robot_dart::gui::magnum::PhongMultiLight, robot_dart::gui::magnum::ShadowMap, robot_dart::gui::magnum::ShadowMapColor)
  • _shadow_color_textures_location (robot_dart::gui::magnum::PhongMultiLight)
  • _shadow_textures_location (robot_dart::gui::magnum::PhongMultiLight)
  • _shininess_uniform (robot_dart::gui::magnum::PhongMultiLight)
  • _specular_color_uniform (robot_dart::gui::magnum::PhongMultiLight)
  • _specular_strength_uniform (robot_dart::gui::magnum::PhongMultiLight)
  • _transparent_shadows_uniform (robot_dart::gui::magnum::PhongMultiLight)
  • _imu (robot_dart::robots::A1, robot_dart::robots::ICub, robot_dart::robots::Talos)
  • _ft_wrist (robot_dart::robots::Franka, robot_dart::robots::Iiwa, robot_dart::robots::Tiago, robot_dart::robots::Ur3e)
  • _ft_foot_left (robot_dart::robots::ICub, robot_dart::robots::Talos)
  • _ft_foot_right (robot_dart::robots::ICub, robot_dart::robots::Talos)
  • _frequency (robot_dart::robots::Talos, robot_dart::sensor::Sensor)
  • _ft_wrist_left (robot_dart::robots::Talos)
  • _ft_wrist_right (robot_dart::robots::Talos)
  • _torques (robot_dart::robots::Talos, robot_dart::sensor::Torque)
  • _direction (robot_dart::sensor::ForceTorque)
  • _wrench (robot_dart::sensor::ForceTorque)
  • _angular_pos (robot_dart::sensor::IMU)
  • _angular_vel (robot_dart::sensor::IMU)
  • _config (robot_dart::sensor::IMU)
  • _linear_accel (robot_dart::sensor::IMU)
  • _attached_tf (robot_dart::sensor::Sensor)
  • _attached_to_body (robot_dart::sensor::Sensor)
  • _attached_to_joint (robot_dart::sensor::Sensor)
  • _attaching_to_body (robot_dart::sensor::Sensor)
  • _attaching_to_joint (robot_dart::sensor::Sensor)
  • _body_attached (robot_dart::sensor::Sensor)
  • _joint_attached (robot_dart::sensor::Sensor)
  • _world_pose (robot_dart::sensor::Sensor)
"},{"location":"api/class_member_typedefs/","title":"Class Member Typedefs","text":""},{"location":"api/class_member_typedefs/#c","title":"c","text":"
  • clock_t (robot_dart::Scheduler)
"},{"location":"api/class_member_typedefs/#d","title":"d","text":"
  • DartCollisionConstPtr (robot_dart::collision_filter::BitmaskContactFilter)
  • DartShapeConstPtr (robot_dart::collision_filter::BitmaskContactFilter)
"},{"location":"api/class_member_typedefs/#f","title":"f","text":"
  • Flags (robot_dart::gui::magnum::CubeMap, robot_dart::gui::magnum::CubeMapColor, robot_dart::gui::magnum::PhongMultiLight, robot_dart::gui::magnum::ShadowMap, robot_dart::gui::magnum::ShadowMapColor)
"},{"location":"api/class_member_typedefs/#n","title":"n","text":"
  • Normal (robot_dart::gui::magnum::PhongMultiLight)
"},{"location":"api/class_member_typedefs/#p","title":"p","text":"
  • Position (robot_dart::gui::magnum::CubeMap, robot_dart::gui::magnum::CubeMapColor, robot_dart::gui::magnum::PhongMultiLight, robot_dart::gui::magnum::ShadowMap, robot_dart::gui::magnum::ShadowMapColor)
"},{"location":"api/class_member_typedefs/#r","title":"r","text":"
  • robot_t (robot_dart::RobotDARTSimu)
  • robot_creator_t (robot_dart::RobotPool)
"},{"location":"api/class_member_typedefs/#t","title":"t","text":"
  • TextureCoordinates (robot_dart::gui::magnum::CubeMap, robot_dart::gui::magnum::CubeMapColor, robot_dart::gui::magnum::PhongMultiLight, robot_dart::gui::magnum::ShadowMap, robot_dart::gui::magnum::ShadowMapColor)
  • torque_map_t (robot_dart::robots::Talos)
"},{"location":"api/class_member_enums/","title":"Class Member Enums","text":""},{"location":"api/class_member_enums/#f","title":"f","text":"
  • Flag (robot_dart::gui::magnum::CubeMap, robot_dart::gui::magnum::CubeMapColor, robot_dart::gui::magnum::PhongMultiLight, robot_dart::gui::magnum::ShadowMap, robot_dart::gui::magnum::ShadowMapColor)
"},{"location":"api/namespace_members/","title":"Namespace Members","text":""},{"location":"api/namespace_members/#a","title":"a","text":"
  • add_dof_data (robot_dart::detail)
"},{"location":"api/namespace_members/#b","title":"b","text":"
  • body_node_get_friction_coeff (robot_dart)
  • body_node_get_restitution_coeff (robot_dart)
  • body_node_set_friction_coeff (robot_dart)
  • body_node_set_restitution_coeff (robot_dart)
"},{"location":"api/namespace_members/#c","title":"c","text":"
  • createCompatibilityShader (Magnum::Shaders::Implementation)
  • convert_rgb_to_grayscale (robot_dart::gui)
  • Camera3D (robot_dart::gui::magnum)
  • create_directional_light (robot_dart::gui::magnum::gs)
  • create_point_light (robot_dart::gui::magnum::gs)
  • create_spot_light (robot_dart::gui::magnum::gs)
"},{"location":"api/namespace_members/#d","title":"d","text":"
  • dof_data (robot_dart::detail)
  • depth_array_from_image (robot_dart::gui::magnum::gs)
  • depth_from_image (robot_dart::gui::magnum::gs)
"},{"location":"api/namespace_members/#g","title":"g","text":"
  • gs (robot_dart::gui::magnum::gs)
"},{"location":"api/namespace_members/#m","title":"m","text":"
  • make_tf (robot_dart)
  • make_vector (robot_dart)
  • make_application (robot_dart::gui::magnum)
"},{"location":"api/namespace_members/#o","title":"o","text":"
  • Object3D (robot_dart::gui::magnum)
"},{"location":"api/namespace_members/#p","title":"p","text":"
  • point_cloud_from_depth_array (robot_dart::gui)
"},{"location":"api/namespace_members/#r","title":"r","text":"
  • rgb_from_image (robot_dart::gui::magnum::gs)
"},{"location":"api/namespace_members/#s","title":"s","text":"
  • set_dof_data (robot_dart::detail)
  • Scene3D (robot_dart::gui::magnum)
  • search_path (robot_dart::gui::magnum::gs)
  • save_png_image (robot_dart::gui)
"},{"location":"api/namespace_member_functions/","title":"Namespace Member Functions","text":""},{"location":"api/namespace_member_functions/#a","title":"a","text":"
  • add_dof_data (robot_dart::detail)
"},{"location":"api/namespace_member_functions/#c","title":"c","text":"
  • createCompatibilityShader (Magnum::Shaders::Implementation)
  • convert_rgb_to_grayscale (robot_dart::gui)
  • create_directional_light (robot_dart::gui::magnum::gs)
  • create_point_light (robot_dart::gui::magnum::gs)
  • create_spot_light (robot_dart::gui::magnum::gs)
"},{"location":"api/namespace_member_functions/#d","title":"d","text":"
  • dof_data (robot_dart::detail)
  • depth_array_from_image (robot_dart::gui::magnum::gs)
  • depth_from_image (robot_dart::gui::magnum::gs)
"},{"location":"api/namespace_member_functions/#m","title":"m","text":"
  • make_tf (robot_dart)
  • make_vector (robot_dart)
  • make_application (robot_dart::gui::magnum)
"},{"location":"api/namespace_member_functions/#p","title":"p","text":"
  • point_cloud_from_depth_array (robot_dart::gui)
"},{"location":"api/namespace_member_functions/#r","title":"r","text":"
  • rgb_from_image (robot_dart::gui::magnum::gs)
"},{"location":"api/namespace_member_functions/#s","title":"s","text":"
  • set_dof_data (robot_dart::detail)
  • search_path (robot_dart::gui::magnum::gs)
  • save_png_image (robot_dart::gui)
"},{"location":"api/namespace_member_variables/","title":"Namespace Member Variables","text":""},{"location":"api/namespace_member_variables/#b","title":"b","text":"
  • body_node_get_friction_coeff (robot_dart)
  • body_node_get_restitution_coeff (robot_dart)
  • body_node_set_friction_coeff (robot_dart)
  • body_node_set_restitution_coeff (robot_dart)
"},{"location":"api/namespace_member_typedefs/","title":"Namespace Member Typedefs","text":""},{"location":"api/namespace_member_typedefs/#c","title":"c","text":"
  • Camera3D (robot_dart::gui::magnum)
"},{"location":"api/namespace_member_typedefs/#o","title":"o","text":"
  • Object3D (robot_dart::gui::magnum)
"},{"location":"api/namespace_member_typedefs/#s","title":"s","text":"
  • Scene3D (robot_dart::gui::magnum)
"},{"location":"api/namespace_member_enums/","title":"Namespace Member Enums","text":""},{"location":"api/namespace_member_enums/#g","title":"g","text":"
  • gs (robot_dart::gui::magnum::gs)
"},{"location":"api/functions/","title":"Functions","text":""},{"location":"api/functions/#r","title":"r","text":"
  • robot_dart_initialize_magnum_resources (base_graphics.hpp)
"},{"location":"api/functions/#s","title":"s","text":"
  • stbi_flip_vertically_on_write (stb_image_write.h)
  • stbi_write_bmp (stb_image_write.h)
  • stbi_write_bmp_to_func (stb_image_write.h)
  • stbi_write_hdr (stb_image_write.h)
  • stbi_write_hdr_to_func (stb_image_write.h)
  • stbi_write_jpg (stb_image_write.h)
  • stbi_write_jpg_to_func (stb_image_write.h)
  • stbi_write_png (stb_image_write.h)
  • stbi_write_png_to_func (stb_image_write.h)
  • stbi_write_tga (stb_image_write.h)
  • stbi_write_tga_to_func (stb_image_write.h)
"},{"location":"api/macros/","title":"Macros","text":""},{"location":"api/macros/#g","title":"g","text":"
  • get_gl_context (base_application.hpp)
  • get_gl_context_with_sleep (base_application.hpp)
"},{"location":"api/macros/#m","title":"m","text":"
  • M_PIf (utils.hpp)
"},{"location":"api/macros/#r","title":"r","text":"
  • release_gl_context (base_application.hpp)
  • ROBOT_DART_ASSERT (utils.hpp)
  • ROBOT_DART_EXCEPTION_ASSERT (utils.hpp)
  • ROBOT_DART_EXCEPTION_INTERNAL_ASSERT (utils.hpp)
  • ROBOT_DART_INTERNAL_ASSERT (utils.hpp)
  • ROBOT_DART_SHOW_WARNINGS (utils.hpp)
  • ROBOT_DART_UNUSED_VARIABLE (utils.hpp)
  • ROBOT_DART_WARNING (utils.hpp)
"},{"location":"api/macros/#s","title":"s","text":"
  • STB_IMAGE_WRITE_IMPLEMENTATION (helper.cpp)
  • STBIWDEF (stb_image_write.h)
"},{"location":"api/variables/","title":"Variables","text":""},{"location":"api/variables/#s","title":"s","text":"
  • stbi_write_force_png_filter (stb_image_write.h)
  • stbi_write_func (stb_image_write.h)
  • stbi_write_png_compression_level (stb_image_write.h)
  • stbi_write_tga_with_rle (stb_image_write.h)
"},{"location":"api/links/","title":"Links","text":"
  • Related Pages
  • Modules
  • Class List
  • Namespace ListNamespace List
  • Namespace Members
  • Namespace Member Functions
  • Namespace Member Variables
  • Namespace Member Typedefs
  • Namespace Member Enumerations
  • Class Index
  • Class Hierarchy
  • Class Members
  • Class Member Functions
  • Class Member Variables
  • Class Member Typedefs
  • Class Member Enumerations
  • Files
  • File Variables
  • File Functions
  • File Macros
"}]} \ No newline at end of file diff --git a/scripts/install_osx.sh b/scripts/install_osx.sh index 30913750..c3a37c42 100755 --- a/scripts/install_osx.sh +++ b/scripts/install_osx.sh @@ -76,6 +76,17 @@ cmake -DCMAKE_BUILD_TYPE=Release -DCMAKE_INSTALL_PREFIX=/opt/magnum -DMAGNUM_WIT make -j sudo make install +cd ../.. +if [ ! -d "magnum-bindings" ] +then +git clone https://github.com/mosra/magnum-bindings.git +cd magnum-bindings +mkdir build && cd build +cmake .. -DMAGNUM_WITH_PYTHON=ON +make -j +cd src/python +sudo python3 setup.py install + export PATH=/opt/magnum/bin:$PATH export LD_LIBRARY_PATH=/opt/magnum/lib:$LD_LIBRARY_PATH