Skip to content

Commit

Permalink
Clean up drake front page
Browse files Browse the repository at this point in the history
New logo subtitle.
Replace long text list of features with a simple table.
First pass has some simple graphics and links to the c++ doxygen.  I plan to fill in each of these boxes with links to sphynx tutorials (using pydrake) in the next passes.We can also make better images.

Zap some old, stale documentaiton.
Zap outdated models text referenced in RobotLocomotion#9287

Added some follow-on TODOs:
RobotLocomotion#10965, RobotLocomotion#10966, RobotLocomotion#10967
  • Loading branch information
RussTedrake committed Mar 20, 2019
1 parent bbb3552 commit 2bfd7eb
Show file tree
Hide file tree
Showing 13 changed files with 455 additions and 382 deletions.
2 changes: 2 additions & 0 deletions doc/BUILD.bazel
Original file line number Diff line number Diff line change
Expand Up @@ -31,6 +31,8 @@ drake_py_binary(
"conf.py",
"images/favicon.ico",
"images/logo_w_text.jpg",
"images/mathematical_program.svg",
"images/systems.svg",
"images/doxygen_instructions/visual_studio_build_targets.png",
"sample_vimrc",
],
Expand Down
39 changes: 0 additions & 39 deletions doc/design.rst

This file was deleted.

1 change: 1 addition & 0 deletions doc/developers.rst
Original file line number Diff line number Diff line change
Expand Up @@ -332,3 +332,4 @@ Version Control
:maxdepth: 1

no_push_to_origin

11 changes: 11 additions & 0 deletions doc/gallery.rst
Original file line number Diff line number Diff line change
Expand Up @@ -11,6 +11,17 @@ Drake Gallery
If you have an example from your own work that you would like to showcase, please edit ``doc/gallery.rst`` directly and submit a pull request!


Underactuated Robotics
======================

Drake is being used to teach a `Underactuated Robotics
<http://underactuated.csail.mit.edu>`_ at MIT. The course textbook has
numerous examples of modeling, controlling, and analyzing many of the canonical
problems in dynamics and control for robotics.

.. TODO(russt): Add videos of a few relevant examples.
Manipulation
============

Expand Down
Binary file modified doc/images/logo_w_text.jpg
Loading
Sorry, something went wrong. Reload?
Sorry, we cannot display this file.
Sorry, this file is invalid so it cannot be displayed.
111 changes: 111 additions & 0 deletions doc/images/mathematical_program.svg
Loading
Sorry, something went wrong. Reload?
Sorry, we cannot display this file.
Sorry, this file is invalid so it cannot be displayed.
9 changes: 9 additions & 0 deletions doc/images/mathematical_program.tex
Original file line number Diff line number Diff line change
@@ -0,0 +1,9 @@
\documentclass[10pt]{article}
\usepackage[usenames]{color} %used for font color
\usepackage{amssymb} %maths
\usepackage{amsmath} %maths
\usepackage[utf8]{inputenc} %useful to type directly diacritic characters
\begin{document}
\begin{align*}\min_x \ \ \ & f(x) \\
\text{s.t. } \ & g(x) \le 0\end{align*}
\end{document}
223 changes: 223 additions & 0 deletions doc/images/systems.svg
Loading
Sorry, something went wrong. Reload?
Sorry, we cannot display this file.
Sorry, this file is invalid so it cannot be displayed.
39 changes: 39 additions & 0 deletions doc/images/systems.tex
Original file line number Diff line number Diff line change
@@ -0,0 +1,39 @@
\documentclass[10pt]{article}
\usepackage[usenames]{color} %used for font color
\usepackage{amssymb} %maths
\usepackage{amsmath} %maths
\usepackage[utf8]{inputenc} %useful to type directly diacritic characters
\usepackage{tikz}
\usetikzlibrary{shapes,arrows}
\begin{document}
\tikzstyle{block} = [draw, rectangle,
minimum height=3em, minimum width=6em]
\tikzstyle{sum} = [draw, circle, node distance=1cm]
\tikzstyle{input} = [coordinate]
\tikzstyle{output} = [coordinate]
\tikzstyle{pinstyle} = [pin edge={to-,thin,black}]

% The block diagram code is probably more verbose than necessary
\begin{tikzpicture}[auto, node distance=2cm,>=latex']
% We start by placing the blocks
\node [input, name=input] {};
\node [sum, right of=input] (sum) {};
\node [block, right of=sum] (controller) {Controller};
\node [block, right of=controller, pin={[pinstyle]above:Disturbances},
node distance=3cm] (system) {System};
% We draw an edge between the controller and system block to
% calculate the coordinate u. We need it to place the measurement block.
\draw [->] (controller) -- node[name=u] {$u$} (system);
\node [output, right of=system] (output) {};
\node [block, below of=u] (measurements) {Estimator};

% Once the nodes are placed, connecting them is easy.
\draw [draw,->] (input) -- node {$r$} (sum);
\draw [->] (sum) -- node {$e$} (controller);
\draw [->] (system) -- node [name=y] {$y$}(output);
\draw [->] (y) |- (measurements);
\draw [->] (measurements) -| node[pos=0.99] {$-$}
node [near end] {$y_m$} (sum);
\end{tikzpicture}

\end{document}
134 changes: 51 additions & 83 deletions doc/index.rst
Original file line number Diff line number Diff line change
Expand Up @@ -15,83 +15,59 @@ It is a collection of tools for analyzing the dynamics of our robots and buildin

While there are an increasing number of simulation tools available for robotics, most of them function like a black box: commands go in, sensors come out. Drake aims to simulate even very complex dynamics of robots (e.g. including friction, contact, aerodynamics, ...), but always with an emphasis on exposing the structure in the governing equations (sparsity, analytical gradients, polynomial structure, uncertainty quantification, ...) and making this information available for advanced planning, control, and analysis algorithms. Drake provides interfaces to high-level languages (MATLAB, Python, ...) to enable rapid-prototyping of new algorithms, and also aims to provide solid open-source implementations for many state-of-the-art algorithms. Finally, we hope Drake provides many compelling examples that can help people get started and provide much needed benchmarks. We are excited to accept user contributions to improve the coverage.

Here is a quick summary of capabilities:

* `Modeling Dynamical Systems <https://drake.mit.edu/doxygen_cxx/group__systems.html>`_
* C++ `block-diagram <https://drake.mit.edu/doxygen_cxx/classdrake_1_1systems_1_1_diagram_builder.html#details>`_ modeling environment with support for:
* Continuous, discrete, hybrid, event-triggered, and multi-rate systems
* `Stochastic systems <https://drake.mit.edu/doxygen_cxx/stochastic_systems.html>`_
* `System constraints <https://drake.mit.edu/doxygen_cxx/classdrake_1_1systems_1_1_system_constraint.html#details>`_
* `Rigid-body kinematics and dynamics <https://drake.mit.edu/doxygen_cxx/group__rigid__body__systems.html>`_
* Rigorously designed and tested, well-documented `multi-body library <https://drake.mit.edu/doxygen_cxx/group__multibody__concepts.html>`_
* Load from :doc:`SDF / URDF models <models>` (+ a few custom tags)
* Contact/collisions modeled with either `compliant <https://drake.mit.edu/doxygen_cxx/group__drake__contacts.html>`_ or rigid contact using continuous (differential equation) and discrete (difference equation, i.e., time stepping) models; **Coming soon**: hybrid models for rigid contact
* Geometry queries (e.g. collision detection, contact queries, and sensor queries) for simple geometries and convex meshes; **Coming soon**: non-convex meshes and multi-contact
* `Rich library of kinematic and dynamic queries <https://drake.mit.edu/doxygen_cxx/class_rigid_body_tree.html>`_ (e.g. Centroidal dynamics, Center of Pressure, Kinematic Jacobians, ...)
* `Sensor models <https://drake.mit.edu/doxygen_cxx/group__sensor__systems.html>`_ (lidar, RGB-D camera, imu, contact force/torque)
* Hand-derived models for many canonical control dynamical systems
* `Easily add your own models/components <https://github.com/RobotLocomotion/drake/blob/master/examples/simple_continuous_time_system.cc>`_
* For nearly all of the above we aim to expose sparsity in the governing equations and provide analytical gradients / symbolic analysis
* **Coming soon**:
* API upgrade from `RigidBodyTree <https://drake.mit.edu/doxygen_cxx/class_rigid_body_tree.html>`_ to `MultiBodyTree <https://drake.mit.edu/doxygen_cxx/classdrake_1_1multibody_1_1_multibody_tree.html>`_
* Soft-body kinematics and dynamics
* More sophisticated rendering (towards photo-realism) and noise models for perception
* Core Libraries / Utilities
* `MathematicalProgram <https://drake.mit.edu/doxygen_cxx/group__solvers.html>`_, a C++ interface wrapping many open-source and commercial solvers
* `Symbolic Computation <https://drake.mit.edu/doxygen_cxx/namespacedrake_1_1symbolic.html>`_, Eigen-compatible scalar types for symbolic design and analysis
* Simulation and Analysis
* `Simulation <https://drake.mit.edu/doxygen_cxx/classdrake_1_1systems_1_1_simulator.html>`_ with a suite of `numerical integration routines <https://drake.mit.edu/doxygen_cxx/classdrake_1_1systems_1_1_integrator_base.html>`_
* Local stability/controllability/observability analysis (via linearization / semi-definite programming)
* **To be ported from MATLAB to C++**:
* Find fixed points / trim conditions
* Region of attraction analysis using sums-of-squares optimization
* Finite-time verification (e.g. forward/backward reachability analysis)
* **Coming soon**:
* Uncertainty quantification
* Planning
* Optimization-based inverse kinematics (fast `SQP-based methods <https://drake.mit.edu/doxygen_cxx/rigid__body__ik_8h.html>`_ and `Global IK <https://drake.mit.edu/doxygen_cxx/classdrake_1_1multibody_1_1_global_inverse_kinematics.html>`_)
* `Trajectory optimization <https://drake.mit.edu/doxygen_cxx/classdrake_1_1systems_1_1_direct_trajectory_optimization.html>`_ (`kinematic <https://drake.mit.edu/doxygen_cxx/rigid__body__ik_8h.html#a6a69c1ef8426e4729ea1c7d4c11e6021>`_ and dynamic)
* `Rich library of constraints <https://drake.mit.edu/doxygen_cxx/class_rigid_body_constraint.html>`_ used by all of the above
* **To be ported from MATLAB to C++**
* Contact-implicit trajectory optimization
* `Mixed-integer-convex trajectory optimization <https://github.com/RobotLocomotion/drake/issues/6243>`_
* Footstep/Gait planning for walking robots
* Grasp optimization
* Feedback motion planning
* **Coming soon**:
* `Sample-based motion planning <https://github.com/RobotLocomotion/drake/issues/3413>`_
* `Feedback Control Design <https://drake.mit.edu/doxygen_cxx/group__control__systems.html>`_
* LQR design for fixed-points
* `Inverse-dynamics controller with contact constraints <https://drake.mit.edu/doxygen_cxx/classdrake_1_1systems_1_1_inverse_dynamics_controller.html#details>`_ using Quadratic Programming (e.g. for humanoid whole-body control)
* **To be ported from MATLAB to C++**
* Time-varying LQR
* Sums-of-squares-based feedback design
* Value iteration algorithms (for low dimensional systems)
* `State Estimation <https://drake.mit.edu/doxygen_cxx/group__estimator__systems.html>`_
* Recursive filter design (Kalman Filters, Luenberger observers)
* **Coming soon**:
* "Smoothing" estimators for nonlinear systems
* `System Identification <https://drake.mit.edu/doxygen_cxx/classdrake_1_1solvers_1_1_system_identification.html>`_
* Least-squares "equation error" minimization for rigid body systems (with automatic extraction of identifiable lumped parameters)
* Nonlinear "simulation error" minimization
* `Many examples / benchmarks / model systems <https://github.com/RobotLocomotion/drake/tree/master/examples>`_
* Acrobot, Cart-Pole, Bouncing balls, ...
* Quadrotors
* `Automotive/Traffic <https://drake.mit.edu/doxygen_cxx/group__automotive__systems.html>`_
* Manipulation
* **To be ported from MATLAB to C++**
* Fixed-Wing UAVs
* Walking Robots
* Humanoids (most notably including the bulk of our codebase for Atlas from `MIT's entry in the DARPA Robotics Challenge <http://drc.mit.edu>`_)
* Other
* `Message passing interfaces <https://drake.mit.edu/doxygen_cxx/group__message__passing.html>`_ (`LCM <https://github.com/lcm-proj/lcm>`_)

Most of these models/tools are described in `the companion textbook from an MIT course/MOOC <https://people.csail.mit.edu/russt/underactuated/underactuated.html?chapter=drake>`_. We've also recently started populating the :doc:`gallery` (contributions welcome!).
********
Features
********

.. raw:: html

<table align="center">
<tr>
<td style="transform: rotate(270deg);
-ms-transform:rotate(270deg); /* IE 9 */
-moz-transform:rotate(270deg); /* Firefox */
-webkit-transform:rotate(270deg); /* Safari and Chrome */
-o-transform:rotate(270deg)"
width="10">Core</td>
<td style="text-align:center;vertical-align:top" width=200
height=150>
<a href="https://drake.mit.edu/doxygen_cxx/group__systems.html">Modeling Dynamical Systems</a>
<p/>
<img src="_images/systems.svg" width=195 />
</td>
<td rowspan=7 style="border-right:1px solid black"></td>
<td style="text-align:center;vertical-align:top" width=200>
<a target="_mathematical_program" href="https://colab.research.google.com/github/RussTedrake/underactuated/blob/master/src/mathematical_program_examples.ipynb">
Solving Mathematical Programs</a>
<p/>
<img src="_images/mathematical_program.svg" width=150 />
</td>
<td rowspan=7 style="border-right:1px solid black"></td>
<td style="text-align:center;vertical-align:top" width=200>
<a href="https://drake.mit.edu/doxygen_cxx/group__multibody.html">Multibody Kinematics and Dynamics</a>
<p/>
<img width="195" src="https://github.com/caelan/pddlstream/raw/d0eb256e88b8b5174fbd136a82867fd9e9cebc67/images/drake_kuka.png"/>
</td>
</tr>
<tr>
<td></td>
<td style="border-bottom:1px solid black" colspan="100%"></td>
</tr>
<tr align="center">
<td></td>
<td style="text-align:center;vertical-align:top" width=200
height=30>
<a href="https://drake.mit.edu/doxygen_cxx/group__algorithms.html">Algorithms</a></td>
<td style="text-align:center;vertical-align:top">
<a href="https://drake.mit.edu/doxygen_cxx/namespacedrake_1_1examples.html">Examples</a></td>
<td style="text-align:center;vertical-align:top"><a
href="gallery.html">Gallery</a></td>
</tr>
</table>

We hope you find this tool useful. Please see :ref:`getting_help` if you wish
to share your comments, questions, success stories, or frustrations. And please contribute your best bug fixes, features, and examples!


************
Citing Drake
************
Expand All @@ -100,8 +76,8 @@ If you would like to cite Drake in your academic publications, we suggest the fo

@misc{drake,
author = "Russ Tedrake and the Drake Development Team",
title = "Drake: A planning, control, and analysis toolbox for nonlinear dynamical systems",
year = 2016,
title = "Drake: Model-based design and verification for robotics",
year = 2019,
url = "https://drake.mit.edu"
}

Expand Down Expand Up @@ -142,11 +118,3 @@ Using Drake from other Programming Languages
julia_bindings
matlab_bindings


***************************************************
Documentation that may be useful but needs updating
***************************************************

* `Introduction and Examples <http://underactuated.csail.mit.edu/underactuated.html?chapter=drake>`_
* :doc:`design`
* :doc:`video_tutorials`
8 changes: 8 additions & 0 deletions doc/index_images.rst
Original file line number Diff line number Diff line change
@@ -0,0 +1,8 @@
:orphan:

This file exists only to install the images for the html table in index.rst.
Note that the files must also be listed in the `gen_sphinx` bazel target.

.. image:: images/mathematical_program.svg
.. image:: images/systems.svg

Loading

0 comments on commit 2bfd7eb

Please sign in to comment.