Skip to content

Commit

Permalink
Considerable clean-up and reorganization of doxygen front page, and d…
Browse files Browse the repository at this point in the history
…oxygen modules.

Added new @InGroup tags that were missing from some systems.
I've specifically attempted to take a somewhat complete first pass at the "Modeling Dynamical Systems" documentation.  I've introduced the "Algorithms" branch of the doxygen, but have not taken a complete pass through it yet.
More cleanup is still necessary... but it's a start.
  • Loading branch information
RussTedrake committed Sep 24, 2018
1 parent be184ed commit 9c27cc2
Show file tree
Hide file tree
Showing 20 changed files with 162 additions and 92 deletions.
5 changes: 4 additions & 1 deletion attic/multibody/plants.h
Original file line number Diff line number Diff line change
@@ -1,7 +1,10 @@


/** @defgroup rigid_body_systems Rigid-Body Systems
/** @addtogroup rigid_body_systems
* @{
* @brief These systems are being replaced with
* drake::multibody::multibody_plant::MultibodyPlant and
* drake::geometry::SceneGraph.
* @ingroup systems
* @}
*/
2 changes: 2 additions & 0 deletions attic/multibody/rigid_body_plant/contact_results_to_lcm.h
Original file line number Diff line number Diff line change
Expand Up @@ -15,6 +15,8 @@ namespace systems {
* A System that encodes ContactResults into a lcmt_contact_results_for_viz
* message. It has a single input port with type ContactResults<T> and a
* single output port with lcmt_contact_results_for_viz.
*
* @ingroup visualization
*/
template <typename T>
class ContactResultsToLcmSystem : public LeafSystem<double> {
Expand Down
7 changes: 2 additions & 5 deletions automotive/automotive.h
Original file line number Diff line number Diff line change
@@ -1,11 +1,8 @@

/** @defgroup automotive_systems Automotive Systems
*
/** @addtogroup automotive_systems
* @{
* The `drake/automotive` folder collects automotive-specific System models and
* related software.
*
* @{
* @ingroup systems
* @}
*/

Expand Down
5 changes: 3 additions & 2 deletions bindings/pydrake/pydrake_pybind.h
Original file line number Diff line number Diff line change
Expand Up @@ -9,8 +9,9 @@
namespace drake {
namespace pydrake {

/**
@page python_bindings Python Bindings
/** @defgroup python_bindings Python Bindings
@ingroup technical_notes
@brief Details on implementing python bindings for the C++ code.
# Overview
Expand Down
2 changes: 1 addition & 1 deletion common/doxygen_cxx.h
Original file line number Diff line number Diff line change
@@ -1,2 +1,2 @@
/// @defgroup cxx C++ support features
/// @ingroup drake_technical_notes
/// @ingroup technical_notes
84 changes: 43 additions & 41 deletions doc/doxygen.h
Original file line number Diff line number Diff line change
Expand Up @@ -5,39 +5,21 @@
<p>Drake's C++ library is composed primarily of an interface for solving
numerical optimization problems, interfaces for modeling dynamical system,
and collection of state-of-the-art algorithms for optimization on dynamical
and a collection of state-of-the-art algorithms for optimization on dynamical
systems:</p>
<ul>
<li><a href="group__solvers.html">Formulating and Solving Optimization
Problems</a></li>
<li><a href="group__systems.html">Modeling Dynamical Systems</a></li>
<ul>
<li><a href="class_rigid_body_tree.html">Rigid-Body Kinematics and
Dynamics</a></li>
<li><a href="group__automotive__systems.html">Automotive Systems</a></li>
<li> \subpage stochastic_systems
</ul>
<li>Algorithms</li>
<ul>
<li><a href="classdrake_1_1systems_1_1_simulator.html">Simulation</a></li>
<li>Analysis</li>
<li>Planning</li>
<li>Feedback Control Design</li>
<li>State Estimation</li>
<li>System Identification</li>
</ul>
</ul>
<p>For more general information, you can also visit the <a
<ul>
<li> @subpage solvers </li>
<li> @subpage systems </li>
<li> @subpage algorithms </li>
<li> @ref drake::examples "Examples" </li>
<li> @subpage technical_notes </li>
</ul>
<p>For more general information, you can also visit the <a
href="https://drake.mit.edu">Drake documentation main page</a>.</p>
</p>
<p>Drake's C++ libraries use a small amount of template metaprogramming to
enable more advanced features (autodiff, symbolic computation, etc). We
have tried to avoid users having to be expert template programmers, but this
is a good reference if you'd like to
<a href="http://www.generic-programming.org/languages/cpp/techniques.php">
learn more about generic programming</a>.</p>
<h3>How do I document the code I am contributing?</h3>
<p>
Expand All @@ -52,24 +34,44 @@ out the Doxygen C++ documentation</a></p>
<a href="https://drake.mit.edu">hosted online</a> for the master branch, but is
only updated nightly.</p>
<h3>Technical Notes</h3>
These links provide notes on Drake's theory, design, and implementation.
- @ref multibody_concepts
- @ref collision_concepts
- @ref cache_design_notes
- @ref system_scalar_conversion
*/
// Define groups here so we can contol the ordering.
// TODO(sherm1) Change Collision Concepts title here when #9467 is fixed.
/**
@defgroup systems Modeling Dynamical Systems
@defgroup solvers Formulating and Solving Optimization Problems
@defgroup multibody_concepts Multibody Dynamics Concepts
@defgroup collision_concepts Collision Concepts (RigidBodyPlant only)
@defgroup drake_technical_notes Technical Notes
@defgroup systems Modeling Dynamical Systems
@defgroup algorithms Algorithms
@defgroup technical_notes Technical Notes
*/

// TODO(russt): Take a thorough pass through the algorithms group
// documentation, adding brief descriptions of each and tagging the relevant
// algorithms throughout the code.
/** @addtogroup algorithms
@{
@defgroup multibody Multibody Dynamics
@defgroup simulation Simulation
@defgroup analysis Analysis
@defgroup planning Planning
@defgroup control Feedback Control Design
@defgroup estimation State Estimation
@defgroup identification System Identification
@}
*/

/** @addtogroup technical_notes
@{
@defgroup templates Template MetaProgramming
<p>Drake's C++ libraries use a small amount of template metaprogramming to
enable more advanced features (autodiff, symbolic computation, etc). We
have tried to avoid users having to be expert template programmers, but this
is a good reference if you'd like to
<a href="http://www.generic-programming.org/languages/cpp/techniques.php">
learn more about generic programming</a>.</p>
@}
*/

4 changes: 3 additions & 1 deletion geometry/geometry_visualization.h
Original file line number Diff line number Diff line change
Expand Up @@ -66,7 +66,9 @@ class GeometryVisualizationImpl {
@pre The given `scene_graph` must be contained within the supplied
DiagramBuilder.
@see geometry::DispatchLoadMessage() */
@see geometry::DispatchLoadMessage()
@ingroup visualization
*/
void ConnectDrakeVisualizer(systems::DiagramBuilder<double>* builder,
const SceneGraph<double>& scene_graph,
lcm::DrakeLcmInterface* lcm = nullptr);
Expand Down
5 changes: 4 additions & 1 deletion geometry/scene_graph.h
Original file line number Diff line number Diff line change
Expand Up @@ -193,7 +193,10 @@ class QueryObject;
- AutoDiffXd
They are already available to link against in the containing library.
No other values for T are currently supported. */
No other values for T are currently supported.
@ingroup systems
*/
template <typename T>
class SceneGraph final : public systems::LeafSystem<T> {
public:
Expand Down
2 changes: 1 addition & 1 deletion multibody/constraint/constraint_doxygen.h
Original file line number Diff line number Diff line change
@@ -1,4 +1,4 @@
/** @defgroup constraint_overview Multibody dynamics constraints in Drake
/** @addtogroup constraint_overview
@ingroup multibody_concepts
This documentation describes the types of multibody constraints supported in
Expand Down
21 changes: 19 additions & 2 deletions multibody/multibody_doxygen.h
Original file line number Diff line number Diff line change
Expand Up @@ -5,8 +5,20 @@
// For example, to link to the notation group: @ref multibody_notation
// To link to the Spatial Inertia discussion: @ref multibody_spatial_inertia.


//------------------------------------------------------------------------------
// TODO(sherm1) Change Collision Concepts title here when #9467 is fixed.
/** @addtogroup multibody Multibody Dynamics
@{
@ingroup algorithms
@defgroup multibody_concepts Multibody Dynamics Concepts
@defgroup collision_concepts Collision Concepts (RigidBodyPlant only)
@}
*/

//------------------------------------------------------------------------------
/** @addtogroup multibody_concepts
@{
Translating from the mathematics of multibody mechanics to correct code is a
difficult process and requires careful discipline to ensure that the resulting
Expand Down Expand Up @@ -45,11 +57,16 @@ from your Doxygen comments; instructions are at the top of the source file used
to generate them.</em>
Next topic: @ref multibody_notation
@defgroup multibody_notation Terminology and Notation
@defgroup multibody_spatial_algebra Spatial Algebra
@defgroup constraint_overview Multibody dynamics constraints
@}
**/


//------------------------------------------------------------------------------
/** @defgroup multibody_notation Terminology and Notation
/** @addtogroup multibody_notation
@ingroup multibody_concepts
Drake uses consistent terminology and notation for multibody mechanics
Expand Down Expand Up @@ -407,7 +424,7 @@ Next topic: @ref multibody_spatial_algebra
**/

//------------------------------------------------------------------------------
/** @defgroup multibody_spatial_algebra Spatial Algebra
/** @addtogroup multibody_spatial_algebra
@ingroup multibody_concepts
Multibody dynamics involves both rotational and translational quantities, for
Expand Down
5 changes: 4 additions & 1 deletion multibody/multibody_tree/multibody_plant/multibody_plant.h
Original file line number Diff line number Diff line change
Expand Up @@ -39,7 +39,9 @@ namespace multibody_plant {

/// %MultibodyPlant is a Drake system framework representation (see
/// systems::System) for the model of a physical system consisting of a
/// collection of interconnected bodies.
/// collection of interconnected bodies. See @ref multibody for an overview of
/// concepts/notation.
///
/// %MultibodyPlant provides a user-facing API to:
/// - add bodies, joints, force elements, and constraints,
/// - register geometries to a provided SceneGraph instance,
Expand Down Expand Up @@ -181,6 +183,7 @@ namespace multibody_plant {
///
/// They are already available to link against in the containing library.
/// No other values for T are currently supported.
/// @ingroup systems
template<typename T>
class MultibodyPlant : public systems::LeafSystem<T> {
public:
Expand Down
2 changes: 2 additions & 0 deletions solvers/mathematical_program.h
Original file line number Diff line number Diff line change
Expand Up @@ -297,6 +297,8 @@ struct assert_if_is_constraint {
* MathematicalProgram stores the decision variables, the constraints and costs
* of an optimization problem. The user can solve the problem by calling Solve()
* function, and obtain the results of the optimization.
*
* @ingroup solvers
*/
class MathematicalProgram {
public:
Expand Down
7 changes: 0 additions & 7 deletions systems/controllers/controllers.h

This file was deleted.

6 changes: 0 additions & 6 deletions systems/estimators/estimators.h

This file was deleted.

2 changes: 1 addition & 1 deletion systems/framework/cache_doxygen.h
Original file line number Diff line number Diff line change
Expand Up @@ -5,7 +5,7 @@ namespace drake {
namespace systems {

/** @defgroup cache_design_notes System Cache Design and Implementation Notes
@ingroup drake_technical_notes
@ingroup technical_notes
<!-- Fluff needed to keep Doxygen from misformatting due to quotes and
this being in the "autobrief" location. -->
Expand Down
2 changes: 1 addition & 1 deletion systems/framework/system_scalar_conversion_doxygen.h
Original file line number Diff line number Diff line change
@@ -1,6 +1,6 @@
//------------------------------------------------------------------------------
/** @defgroup system_scalar_conversion System Scalar Conversion
@ingroup drake_technical_notes
@ingroup technical_notes
System scalar conversion refers to cloning a System templatized by one scalar
type into an identical System that is templatized by a different scalar type.
Expand Down
6 changes: 0 additions & 6 deletions systems/primitives/primitives.h

This file was deleted.

6 changes: 0 additions & 6 deletions systems/sensors/sensors.h

This file was deleted.

7 changes: 3 additions & 4 deletions systems/stochastic_systems.h
Original file line number Diff line number Diff line change
Expand Up @@ -2,10 +2,8 @@
namespace drake {
namespace systems {

/**
@page stochastic_systems Stochastic Systems
This page describes the implementation details of modeling a
/** @addtogroup stochastic_systems
@brief This page describes the implementation details of modeling a
stochastic system in Drake and writing algorithms that explicitly
leverage the stochastic modeling framework.
Expand Down Expand Up @@ -64,6 +62,7 @@ System<T>::SetRandomState() and System<T>::SetRandomParameters() are
expected to call the random number generators in the C++ Standard
Library.
@ingroup systems
*/

} // namespace systems
Expand Down
Loading

0 comments on commit 9c27cc2

Please sign in to comment.