From c4ca1701ee086b97fce8795a3a2345f20842d6cb Mon Sep 17 00:00:00 2001 From: Jamie Snape Date: Tue, 16 Oct 2018 17:39:25 -0400 Subject: [PATCH] Miscellaneous documentation fixes --- attic/multibody/collision/bullet_model.h | 2 + attic/multibody/rigid_body.h | 4 +- .../rigid_body_plant/compliant_material.h | 1 + .../rigid_body_plant/contact_force.h | 1 + .../rigid_body_plant_bridge.h | 2 + common/copyable_unique_ptr.h | 1 + common/symbolic_formula_cell.h | 4 +- common/symbolic_rational_function.h | 2 + common/type_safe_index.h | 6 +- .../kuka_iiwa_arm/pick_and_place/action.h | 1 + examples/rod2d/rod2d.h | 60 +++---- examples/scene_graph/solar_system.h | 6 +- geometry/dev/geometry_roles.h | 1 + geometry/dev/geometry_visualization.h | 1 + geometry/dev/render/render_label.h | 1 + geometry/dev/scene_graph.h | 1 + geometry/dev/scene_graph_inspector.h | 21 +-- geometry/geometry_frame.h | 1 + geometry/geometry_instance.h | 2 + geometry/geometry_set.h | 1 + geometry/geometry_visualization.h | 1 + geometry/scene_graph.h | 13 +- geometry/scene_graph_inspector.h | 21 +-- geometry/shape_specification.h | 21 +-- .../schunk_wsg/schunk_wsg_plain_controller.h | 11 +- manipulation/sensors/xtion.h | 1 + multibody/benchmarks/acrobot/acrobot.h | 23 +-- multibody/constraint/constraint_doxygen.h | 12 +- multibody/multibody_tree/body_node.h | 2 + .../multibody_plant/contact_info.h | 1 + .../multibody_plant/contact_results_to_lcm.h | 1 + .../multibody_plant/multibody_plant.h | 3 +- multibody/multibody_tree/multibody_tree.h | 2 + .../multibody_tree/multibody_tree_topology.h | 2 + multibody/multibody_tree/rotational_inertia.h | 1 + multibody/multibody_tree/spatial_inertia.h | 2 + perception/point_cloud.h | 14 +- solvers/mathematical_program.h | 6 + solvers/mixed_integer_rotation_constraint.h | 1 + systems/analysis/integrator_base.h | 4 + systems/framework/cache_doxygen.h | 147 ++++++++++-------- systems/framework/context.h | 3 + systems/framework/system.h | 9 +- systems/lcm/connect_lcm_scope.h | 1 + systems/sensors/camera_info.h | 1 + systems/sensors/depth_sensor.h | 20 +-- 46 files changed, 264 insertions(+), 178 deletions(-) diff --git a/attic/multibody/collision/bullet_model.h b/attic/multibody/collision/bullet_model.h index 845902d83bac..6a66b09c8276 100644 --- a/attic/multibody/collision/bullet_model.h +++ b/attic/multibody/collision/bullet_model.h @@ -94,6 +94,7 @@ class BulletModel : public Model { * Computes the closest point in the collision world to each of a set of * points. For each query point, a PointPair instance, `p`, is returned with * the following semantics: + * * - p.elementA = p.elementB = pointer to the closest element. * - p.idA = p.idB = ElementId of closest element. * - p.ptA = the point on the closest element's surface expressed and @@ -104,6 +105,7 @@ class BulletModel : public Model { * point, expressed in the world frame. * - p.distance = The *signed* distance between the query point and the * nearest point. Negative values indicate penetration. + * * If there are no objects in the scene, then the pointers will be nullptr, * the ids, 0, the distance infinite, and the nearest points, infinitely far * away. diff --git a/attic/multibody/rigid_body.h b/attic/multibody/rigid_body.h index f423af5525a0..0e2413fc7245 100644 --- a/attic/multibody/rigid_body.h +++ b/attic/multibody/rigid_body.h @@ -25,7 +25,8 @@ class RigidBody { /** * Returns a clone of this RigidBody. * - * *Important note!* The following are not cloned: + * @attention The following are not cloned: + * * - the joint * - the parent %RigidBody * - the visual elements @@ -297,6 +298,7 @@ class RigidBody { * single inboard joint. This joint defines several frames, discussed in * @ref rigid_body_tree_frames, including its parent frame: `Pₖ ≡ Bₖ₋₁`. This * allows us to compute `X_Bₖ₋₁Bₖ` as follows: + * * - `X_Bₖ₋₁Bₖ = X_PₖBₖ` because `Pₖ ≡ Bₖ₋₁` * - `X_PₖBₖ ≡ X_PₖFₖ * X_FₖMₖ(q) * X_MₖBₖ`, where: * - `X_MₖBₖ = I` in Drake's implementation. diff --git a/attic/multibody/rigid_body_plant/compliant_material.h b/attic/multibody/rigid_body_plant/compliant_material.h index e4d40d773edd..e700a54e0b61 100644 --- a/attic/multibody/rigid_body_plant/compliant_material.h +++ b/attic/multibody/rigid_body_plant/compliant_material.h @@ -58,6 +58,7 @@ class CompliantMaterial { /** Constructs fully specified material. Will throw an exception in any of the following circumstances: + - `youngs_modulus` <= 0 - `dissipation` < 0 - `static_friction` < 0 diff --git a/attic/multibody/rigid_body_plant/contact_force.h b/attic/multibody/rigid_body_plant/contact_force.h index 0679ce00eb44..76be0eb992fa 100644 --- a/attic/multibody/rigid_body_plant/contact_force.h +++ b/attic/multibody/rigid_body_plant/contact_force.h @@ -11,6 +11,7 @@ namespace systems { Ultimately, a contact force consists of an application point, a spatial force, and a unit vector. The spatial force includes: + - a translational force, that is a pure force applied at a point, - a torque, the rotational force. This is not the same as the moment induced by the translational force. This torque can arise from a diff --git a/attic/multibody/rigid_body_plant/rigid_body_plant_bridge.h b/attic/multibody/rigid_body_plant/rigid_body_plant_bridge.h index 874a8586a5d7..edc2c2785b8d 100644 --- a/attic/multibody/rigid_body_plant/rigid_body_plant_bridge.h +++ b/attic/multibody/rigid_body_plant/rigid_body_plant_bridge.h @@ -33,6 +33,7 @@ namespace systems { - . : No geometry is used, shapes of this type are *ignored* The columns of the table indicate the SceneGraph roles. + - Proximity: The shape is used in proximity queries (e.g., penetration, distance, ray-casting, etc.) - Visual: The shape is displayed in drake_visualizer. @@ -48,6 +49,7 @@ namespace systems { %MeshPoints | . | . | . %Plane | V | V | . %Sphere | V | V | . +

Table: Level of Support. Indication of what types of shapes (rows) are read from the RigidBodyTree, the role they played in the RigidBodyTree, collision or visual, (cell values "C", "V", or ".") and how they are used in SceneGraph diff --git a/common/copyable_unique_ptr.h b/common/copyable_unique_ptr.h index d91c3391afcd..e145d13daef0 100644 --- a/common/copyable_unique_ptr.h +++ b/common/copyable_unique_ptr.h @@ -78,6 +78,7 @@ namespace drake { referenced object, such that the new copy contains an instance of `Base` instead of `Derived`. Some mistakes that would lead to this degenerate behavior: + - The `Base` class has a public copy constructor. - The `Base` class's Clone() implementation does not invoke the `Derived` class's implementation of a suitable virtual method. diff --git a/common/symbolic_formula_cell.h b/common/symbolic_formula_cell.h index 84bcf123ec9f..8c3723c29946 100644 --- a/common/symbolic_formula_cell.h +++ b/common/symbolic_formula_cell.h @@ -372,6 +372,7 @@ class FormulaPositiveSemidefinite : public FormulaCell { * the two matrices `m1` in `psd1` and `m2` in `psd2`. * * First, we compare the size of `m1` and `m2`: + * * - If `m1` is smaller than `m2`, `psd1.Less(psd2)` is true. * - If `m2` is smaller than `m1`, `psd1.Less(psd2)` is false. * @@ -389,7 +390,8 @@ class FormulaPositiveSemidefinite : public FormulaCell { * EXPECT_TRUE(psd1.Less(psd2)); * @endcode * - * Note that in the code above, `psd1.Less(psd2)` holds because we have + * @note In the code above, `psd1.Less(psd2)` holds because we have + * * - m1 in column-major ordering : (x + y) -3.14 -3.14 y_ * - m2 in column-major ordering : (x + y) 3.14 3.14 y_. */ diff --git a/common/symbolic_rational_function.h b/common/symbolic_rational_function.h index 6eef1bfba659..33f7c46e00f2 100644 --- a/common/symbolic_rational_function.h +++ b/common/symbolic_rational_function.h @@ -151,10 +151,12 @@ RationalFunction operator/(double c, const RationalFunction& f); RationalFunction pow(const RationalFunction& f, int n); /** * Provides the following operations: + * * - Matrix * Matrix => Matrix * - Matrix * Matrix => Matrix * - Matrix * Matrix => Matrix * - Matrix * Matrix => Matrix + * * where RF is a shorthand for RationalFunction. * * @note that these operator overloadings are necessary even after providing diff --git a/common/type_safe_index.h b/common/type_safe_index.h index 61c4e24c2a67..a83b762641e6 100644 --- a/common/type_safe_index.h +++ b/common/type_safe_index.h @@ -327,8 +327,10 @@ class TypeSafeIndex { // without unsigned/signed comparison warnings (which Drake considers to be an // error). Furthermore, the SFINAE is necessary to prevent ambiguity. // Index == int can be resolved two ways: - // - convert Index to int - // - promote int to size_t + // + // - convert Index to int + // - promote int to size_t + // // SFINAE prevents the latter. /// Whitelist equality test with indices of this tag. diff --git a/examples/kuka_iiwa_arm/pick_and_place/action.h b/examples/kuka_iiwa_arm/pick_and_place/action.h index 56e213f31ba8..909412ec948f 100644 --- a/examples/kuka_iiwa_arm/pick_and_place/action.h +++ b/examples/kuka_iiwa_arm/pick_and_place/action.h @@ -154,6 +154,7 @@ class WsgAction : public Action { /** * Returns true if the following criteria are satisfied: + * * - The gripper speed is less than the final speed threshold. * - 0.5 s have elapsed since the last Open/Close command was issued. * - The gripper position is greater than (for an Open command) or less than diff --git a/examples/rod2d/rod2d.h b/examples/rod2d/rod2d.h index b66182e377e8..76d6f899acc5 100644 --- a/examples/rod2d/rod2d.h +++ b/examples/rod2d/rod2d.h @@ -25,26 +25,27 @@ standard multibody notation as described in detail here: For a quick summary and translation to 2D: - - When we combine rotational and translational quantities into a single - quantity in 3D, we call those "spatial" quantities. In 2D those combined - quantities are actually planar, but we will continue to refer to them as - "spatial" to keep the notation analogous and promote easy extension of 2D - pedagogical examples to 3D. - - We use capital letters to represent bodies and coordinate frames. Frame F has - an origin point Fo, and a basis formed by orthogonal unit vector axes Fx and - Fy, with an implicit `Fz=Fx × Fy` always pointing out of the screen for a 2D - system. The inertial frame World is W, and the rod frame is R. - - We also use capitals to represent points, and we allow a frame name F to be - used where a point is expected to represent its origin Fo. - - We use `p_CD` to represent the position vector from point C to point D. Note - that if A and B are frames, `p_AB` means `p_AoBo`. - - If we need to be explicit about the expressed-in frame F for any quantity, we - add the suffix `_F` to its symbol. So the position vector from C to D, - expressed in W, is `p_CD_W`. - - R_AB is the rotation matrix giving frame B's orientation in frame A. - - X_AB is the transformation matrix giving frame B's pose in frame A, combining - both a rotation and a translation; this is conventionally called a - "transform". A transform is a spatial quantity. + +- When we combine rotational and translational quantities into a single + quantity in 3D, we call those "spatial" quantities. In 2D those combined + quantities are actually planar, but we will continue to refer to them as + "spatial" to keep the notation analogous and promote easy extension of 2D + pedagogical examples to 3D. +- We use capital letters to represent bodies and coordinate frames. Frame F has + an origin point Fo, and a basis formed by orthogonal unit vector axes Fx and + Fy, with an implicit `Fz=Fx × Fy` always pointing out of the screen for a 2D + system. The inertial frame World is W, and the rod frame is R. +- We also use capitals to represent points, and we allow a frame name F to be + used where a point is expected to represent its origin Fo. +- We use `p_CD` to represent the position vector from point C to point D. Note + that if A and B are frames, `p_AB` means `p_AoBo`. +- If we need to be explicit about the expressed-in frame F for any quantity, we + add the suffix `_F` to its symbol. So the position vector from C to D, + expressed in W, is `p_CD_W`. +- R_AB is the rotation matrix giving frame B's orientation in frame A. +- X_AB is the transformation matrix giving frame B's pose in frame A, combining + both a rotation and a translation; this is conventionally called a + "transform". A transform is a spatial quantity. In 2D, with frames A and B the above quantities are (conceptually) matrices with the indicated dimensions:
@@ -58,11 +59,12 @@ represented by (x,y,θ).
 
 We use v for translational velocity of a point and w (ω) for rotational
 velocity of a frame. The symbols are:
- - `v_AP` is point P's velocity in frame A, expressed in frame A if no
-   other frame is given as a suffix.
- - `w_AB` is frame B's angular velocity in frame A, expressed in frame A
-   if no other frame is given as a suffix.
- - `V_AB` is frame B's spatial velocity in A, meaning `v_ABo` and `w_AB`.
+
+- `v_AP` is point P's velocity in frame A, expressed in frame A if no
+  other frame is given as a suffix.
+- `w_AB` is frame B's angular velocity in frame A, expressed in frame A
+  if no other frame is given as a suffix.
+- `V_AB` is frame B's spatial velocity in A, meaning `v_ABo` and `w_AB`.
 
 
 These quantities are conceptually: 
@@ -75,9 +77,10 @@ velocity with just the scalar w=ω=@f$\dot{\theta}@f$ (that is, d/dt θ), and
 spatial velocity as (vx,vy,ω).
 
 Forces f and torques τ are represented similarly:
- - `f_P` is an in-plane force applied to a point P fixed to some rigid body.
- - `t_A` is an in-plane torque applied to frame A (meaning it is about Az).
- - `F_A` is a spatial force including both `f_Ao` and `t_A`.
+
+- `f_P` is an in-plane force applied to a point P fixed to some rigid body.
+- `t_A` is an in-plane torque applied to frame A (meaning it is about Az).
+- `F_A` is a spatial force including both `f_Ao` and `t_A`.
 
 The above symbols can be suffixed with an expressed-in frame if the frame is
 not already obvious, so `F_A_W` is a spatial force applied to frame A (at Ao)
@@ -109,6 +112,7 @@ h, and "left" and "right" endpoints `Rl=Ro-h*Rx` and `Rr=Ro+h*Rx` at which
 it can contact the halfspace whose surface is at Wy=0.
 
 This system can be simulated using one of three models:
+
 - continuously, using a compliant contact model (the rod is rigid, but contact
   between the rod and the half-space is modeled as compliant) simulated using
   ordinary differential equations (ODEs),
diff --git a/examples/scene_graph/solar_system.h b/examples/scene_graph/solar_system.h
index 9596ed369f22..40a260234bb5 100644
--- a/examples/scene_graph/solar_system.h
+++ b/examples/scene_graph/solar_system.h
@@ -31,10 +31,10 @@ namespace solar_system {
    Luna but at different relative angular positions around their axis of
    rotation.
  - Mars orbits the sun at a farther distance on a plane that is tilted off of
- the xy-plane. Its moon (Phobos) orbits around Mars on a plane parallel to
- Mars's orbital plane, but in the opposite direction.
+   the xy-plane. Its moon (Phobos) orbits around Mars on a plane parallel to
+   Mars's orbital plane, but in the opposite direction.
  - Mars has been given an arbitrary set of rings posed askew. The rings are
- declared as a child of mars's geometry.
+   declared as a child of mars's geometry.
 
  This system illustrates the following features:
 
diff --git a/geometry/dev/geometry_roles.h b/geometry/dev/geometry_roles.h
index 5236826cbbdb..51fb62f674f5 100644
--- a/geometry/dev/geometry_roles.h
+++ b/geometry/dev/geometry_roles.h
@@ -106,6 +106,7 @@ namespace dev {
  Role assignment is achieved by assigning as set of role-related *properties*
  to a geometry (see SceneGraph::AssignRole()). The set *can* be empty. Each
  role has a specific property set associated with it:
+
    - __Proximity role__: ProximityProperties
    - __Perception role__: PerceptionProperties
    - __Illustration role__: IllustrationProperties
diff --git a/geometry/dev/geometry_visualization.h b/geometry/dev/geometry_visualization.h
index bac65401e8c8..5a25415d69eb 100644
--- a/geometry/dev/geometry_visualization.h
+++ b/geometry/dev/geometry_visualization.h
@@ -37,6 +37,7 @@ class GeometryVisualizationImpl {
 
  This is a convenience method to simplify some common boilerplate for adding
  visualization capability to a Diagram. What it does is:
+
  - adds an initialization event that sends the required load message to set up
    the visualizer with the relevant geometry,
  - adds systems PoseBundleToDrawMessage and LcmPublisherSystem to
diff --git a/geometry/dev/render/render_label.h b/geometry/dev/render/render_label.h
index 03dea1d665d5..490ce50ee0aa 100644
--- a/geometry/dev/render/render_label.h
+++ b/geometry/dev/render/render_label.h
@@ -74,6 +74,7 @@ namespace render {
  @cond
  NOTE: In many ways, this is very similar to the TypeSafeIndex class. There are
  several key differences:
+
    - added static members,
    - special values (empty and terrain),
    - arbitrarily limited domain (kLabelCount).
diff --git a/geometry/dev/scene_graph.h b/geometry/dev/scene_graph.h
index a747b877c2ec..81d2d2c060b5 100644
--- a/geometry/dev/scene_graph.h
+++ b/geometry/dev/scene_graph.h
@@ -51,6 +51,7 @@ class QueryObject;
  source owns, via a port connection on %SceneGraph.
 
  The basic workflow for interacting with %SceneGraph is:
+
    - Register as a geometry source, acquiring a unique SourceId.
    - Register geometry (anchored and dynamic) with the system.
    - Connect source's geometry output ports to the corresponding %SceneGraph
diff --git a/geometry/dev/scene_graph_inspector.h b/geometry/dev/scene_graph_inspector.h
index 5f6c923b4655..88f1de12c2e2 100644
--- a/geometry/dev/scene_graph_inspector.h
+++ b/geometry/dev/scene_graph_inspector.h
@@ -19,24 +19,25 @@ class QueryObject;
  of the SceneGraph data that does *not* depend on input pose data. Including,
  but not limited to:
 
-   - names of frames and geometries
-   - hierarchies (parents of geometries, parents of frames, etc.)
-   - geometry parameters (e.g., contact, rendering, visualization)
-   - fixed poses of geometries relative to frames
+ - names of frames and geometries
+ - hierarchies (parents of geometries, parents of frames, etc.)
+ - geometry parameters (e.g., contact, rendering, visualization)
+ - fixed poses of geometries relative to frames
 
  In contrast, the following pieces of data *do* depend on input pose data and
  *cannot* be performed with the %SceneGraphInspector (see the QueryObject
  instead):
 
-   - world pose of frames or geometry
-   - collision queries
-   - proximity queries
+ - world pose of frames or geometry
+ - collision queries
+ - proximity queries
 
  A %SceneGraphInspector cannot be instantiated explicitly. Nor can it be copied
  or moved. A *reference* to a %SceneGraphInspector instance can be acquired from
-   - a SceneGraph instance (to inspect the state of the system's _model_), or
-   - a QueryObject instance (to inspect the state of the scene graph data stored
-     in the context).
+
+ - a SceneGraph instance (to inspect the state of the system's _model_), or
+ - a QueryObject instance (to inspect the state of the scene graph data stored
+   in the context).
 
  The reference should not be persisted (and, as previously indicated, cannot
  be copied). %SceneGraphInspector instances are cheap; they can be created,
diff --git a/geometry/geometry_frame.h b/geometry/geometry_frame.h
index 60188d7c6779..56875fa39194 100644
--- a/geometry/geometry_frame.h
+++ b/geometry/geometry_frame.h
@@ -16,6 +16,7 @@ namespace geometry {
  over to SceneGraph.
 
  A frame is defined by three pieces of information:
+
     - the name, which must be unique within a single geometry source,
     - the "frame group", an integer identifier that can be used to group frames
       together within a geometry source, and
diff --git a/geometry/geometry_instance.h b/geometry/geometry_instance.h
index b363e0831914..209392b84b09 100644
--- a/geometry/geometry_instance.h
+++ b/geometry/geometry_instance.h
@@ -23,6 +23,7 @@ namespace geometry {
  valid names in SDF files. Specifically, any user-specified name will have
  all leading and trailing space and tab characters trimmed off. The trimmed name
  will have to satisfy the following requirements:
+
    - cannot be empty, and
    - the name should be unique in the scope of its frame and role. For example,
      two GeometryInstances can both be called "ball" as long as they are
@@ -31,6 +32,7 @@ namespace geometry {
      but will be enforced in the future.
      
+
  If valid, the trimmed name will be assigned to the instance.
 
  Names *can* have internal whitespace (e.g., "my geometry name").
diff --git a/geometry/geometry_set.h b/geometry/geometry_set.h
index 773ef9aa5110..2b9fde782b21 100644
--- a/geometry/geometry_set.h
+++ b/geometry/geometry_set.h
@@ -147,6 +147,7 @@ class GeometrySet {
 
    The interface for adding geometries to the set is simply an overload of the
    Add() method. For maximum flexibility, the Add method can take:
+
      - a single geometry id
      - a single frame id
      - an iterable object containing geometry ids
diff --git a/geometry/geometry_visualization.h b/geometry/geometry_visualization.h
index d4dad045a807..b3cc976c4b6e 100644
--- a/geometry/geometry_visualization.h
+++ b/geometry/geometry_visualization.h
@@ -36,6 +36,7 @@ class GeometryVisualizationImpl {
 
  This is a convenience method to simplify some common boilerplate for adding
  visualization capability to a Diagram. What it does is:
+
  - adds an initialization event that sends the required load message to set up
    the visualizer with the relevant geometry,
  - adds systems PoseBundleToDrawMessage and LcmPublisherSystem to
diff --git a/geometry/scene_graph.h b/geometry/scene_graph.h
index d08f83294904..9da39f20a441 100644
--- a/geometry/scene_graph.h
+++ b/geometry/scene_graph.h
@@ -48,12 +48,13 @@ class QueryObject;
  source owns, via a port connection on %SceneGraph.
 
  The basic workflow for interacting with %SceneGraph is:
-   - Register as a geometry source, acquiring a unique SourceId.
-   - Register geometry (anchored and dynamic) with the system.
-   - Connect source's geometry output ports to the corresponding %SceneGraph
-     input ports.
-     - Implement appropriate `Calc*` methods on the geometry output ports to
-       update geometry pose values.
+
+ - Register as a geometry source, acquiring a unique SourceId.
+ - Register geometry (anchored and dynamic) with the system.
+ - Connect source's geometry output ports to the corresponding %SceneGraph
+   input ports.
+   - Implement appropriate `Calc*` methods on the geometry output ports to
+     update geometry pose values.
 
  @section geom_sys_inputs Inputs
  @cond
diff --git a/geometry/scene_graph_inspector.h b/geometry/scene_graph_inspector.h
index fc39e8a1fb90..6790d649a374 100644
--- a/geometry/scene_graph_inspector.h
+++ b/geometry/scene_graph_inspector.h
@@ -17,24 +17,25 @@ class QueryObject;
  of the SceneGraph data that does *not* depend on input pose data. Including,
  but not limited to:
 
-   - names of frames and geometries
-   - hierarchies (parents of geometries, parents of frames, etc.)
-   - geometry parameters (e.g., contact, rendering, visualization)
-   - fixed poses of geometries relative to frames
+ - names of frames and geometries
+ - hierarchies (parents of geometries, parents of frames, etc.)
+ - geometry parameters (e.g., contact, rendering, visualization)
+ - fixed poses of geometries relative to frames
 
  In contrast, the following pieces of data *do* depend on input pose data and
  *cannot* be performed with the %SceneGraphInspector (see the QueryObject
  instead):
 
-   - world pose of frames or geometry
-   - collision queries
-   - proximity queries
+ - world pose of frames or geometry
+ - collision queries
+ - proximity queries
 
  A %SceneGraphInspector cannot be instantiated explicitly. Nor can it be copied
  or moved. A *reference* to a %SceneGraphInspector instance can be acquired from
-   - a SceneGraph instance (to inspect the state of the system's _model_), or
-   - a QueryObject instance (to inspect the state of the scene graph data stored
-     in the context).
+
+ - a SceneGraph instance (to inspect the state of the system's _model_), or
+ - a QueryObject instance (to inspect the state of the scene graph data stored
+   in the context).
 
  The reference should not be persisted (and, as previously indicated, cannot
  be copied). %SceneGraphInspector instances are cheap; they can be created,
diff --git a/geometry/shape_specification.h b/geometry/shape_specification.h
index 656775fea29f..65f60f9a5417 100644
--- a/geometry/shape_specification.h
+++ b/geometry/shape_specification.h
@@ -29,19 +29,22 @@ struct ShapeTag{};
 /** The base interface for all shape specifications. It has no public
   constructor and cannot be instantiated directly. The Shape class has two
   key properties:
+
    - it is cloneable, and
    - it can be "reified" (see ShapeReifier).
 
   When you add a new subclass of Shape, you must:
-   1. add a pure virtual function ImplementGeometry() for the new shape in
-      ShapeReifier.
-   2. define ImplementGeometry() for the new shape in the subclasses of
-      ShapeReifier.
-   3. modify CopyShapeOrThrow() of ProximityEngine to support the new shape and
-      add an instance of the new shape to the CopySemantics test in
-      proximity_engine_test.cc.
-   4. test the new shape in the class BoxPenetrationTest of
-      proximity_engine_test.cc
+
+  1. add a pure virtual function ImplementGeometry() for the new shape in
+     ShapeReifier.
+  2. define ImplementGeometry() for the new shape in the subclasses of
+     ShapeReifier.
+  3. modify CopyShapeOrThrow() of ProximityEngine to support the new shape and
+     add an instance of the new shape to the CopySemantics test in
+     proximity_engine_test.cc.
+  4. test the new shape in the class BoxPenetrationTest of
+     proximity_engine_test.cc
+
   Otherwise, you might get a runtime error. We do not have an automatic way to
   enforce them at compile time.
  */
diff --git a/manipulation/schunk_wsg/schunk_wsg_plain_controller.h b/manipulation/schunk_wsg/schunk_wsg_plain_controller.h
index 967d7059e275..8917e1d5ca7c 100644
--- a/manipulation/schunk_wsg/schunk_wsg_plain_controller.h
+++ b/manipulation/schunk_wsg/schunk_wsg_plain_controller.h
@@ -46,8 +46,9 @@ enum class ControlMode { kPosition = 0, kForce = 1 };
  *                     └──┘      └──────────┘   └───────────┘
  *```
  * The blocks with double outlines (══) differ between the two control modes:
- *  - Generate Desired Control State
- *    - ControlMode::kPosition
+ *
+ * - Generate Desired Control State
+ *   - ControlMode::kPosition
  *```
  *        ┌───────────┐
  *        │Desired    │
@@ -73,8 +74,8 @@ enum class ControlMode { kPosition = 0, kForce = 1 };
  *         grip   ───────▶│IGNORED │
  *         state          └────────┘
  *```
- *  - Handle Feed-Forward Force
- *    - ControlMode::kPosition
+ * - Handle Feed-Forward Force
+ *   - ControlMode::kPosition
  *```
  *                                     █────▶ mean finger force
  *         pid                         █
@@ -85,7 +86,7 @@ enum class ControlMode { kPosition = 0, kForce = 1 };
  *         forward ──────▶│IGNORED │
  *         force          └────────┘
  *```
- *    - ControlMode::kForce
+ *   - ControlMode::kForce
  *```
  *         pid
  *         controller ──────────────────────▶ mean finger force
diff --git a/manipulation/sensors/xtion.h b/manipulation/sensors/xtion.h
index 106e333fd638..b9a582df66cc 100644
--- a/manipulation/sensors/xtion.h
+++ b/manipulation/sensors/xtion.h
@@ -19,6 +19,7 @@ namespace sensors {
  * and provides the ability to add the camera as a system in a diagram builder.
  *
  * Frames:
+ *
  *  B - RgbdCamera sensor frame (X-forward, Y-left, Z-up).
  *  X - Xtion base frame
  *      Same orientation as RgbdCamera frame, but with different offset.
diff --git a/multibody/benchmarks/acrobot/acrobot.h b/multibody/benchmarks/acrobot/acrobot.h
index c67a58bea609..2cb189088242 100644
--- a/multibody/benchmarks/acrobot/acrobot.h
+++ b/multibody/benchmarks/acrobot/acrobot.h
@@ -39,17 +39,18 @@ class Acrobot {
   /// 
/// The remaining arguments define the properties of the double pendulum /// system: - /// - m1: mass of the first link. - /// - m2: mass of the second link. - /// - l1: length of the first link. - /// - l2: length of the second link. - /// - lc1: length from the shoulder to the center of mass of the first link. - /// - lc2: length from the elbow to the center of mass of the second link. - /// - Ic1: moment of inertia about the center of mass for the first link. - /// - Ic2: moment of inertia about the center of mass for the second link. - /// - b1: damping coefficient of the shoulder joint. - /// - b2: damping coefficient of the elbow joint. - /// - g: acceleration of gavity. + /// + /// - m1: mass of the first link. + /// - m2: mass of the second link. + /// - l1: length of the first link. + /// - l2: length of the second link. + /// - lc1: length from the shoulder to the center of mass of the first link. + /// - lc2: length from the elbow to the center of mass of the second link. + /// - Ic1: moment of inertia about the center of mass for the first link. + /// - Ic2: moment of inertia about the center of mass for the second link. + /// - b1: damping coefficient of the shoulder joint. + /// - b2: damping coefficient of the elbow joint. + /// - g: acceleration of gavity. Acrobot(const Vector3& normal, const Vector3& up, double m1 = 1.0, double m2 = 1.0, diff --git a/multibody/constraint/constraint_doxygen.h b/multibody/constraint/constraint_doxygen.h index be90d60ed0fe..2f35d3dd7524 100644 --- a/multibody/constraint/constraint_doxygen.h +++ b/multibody/constraint/constraint_doxygen.h @@ -18,22 +18,24 @@ constraints and does so in a manner very different from "smoothing methods" (also known as "penalty methods"). Smoothing methods have traditionally required significant computation to maintain `g = 0` to high accuracy (and typically yielding what is known in ODE and DAE literature as a "computationally stiff -system"). +system"). We also provide the core components of an efficient first-order integration scheme for a system with both compliant and rigid unilateral constraints. Such a system arises in many contact problems, where the correct modeling parameters would yield a computationally stiff system. The integration scheme is low-accuracy but very stable for mechanical systems, even when the algebraic -variables (i.e., the constraint forces) are computed to low accuracy. +variables (i.e., the constraint forces) are computed to low accuracy. This discussion will provide necessary background material in: + - @ref constraint_types - @ref constraint_stabilization - @ref constraint_Jacobians - @ref contact_surface_constraints and will delve into the constraint solver functionality in: + - @ref discretization A prodigious number of variables will be referenced throughout the discussion @@ -169,8 +171,8 @@ direction (λ ≥ 0). This triplet is known as a *complementarity constraint*. /** @defgroup constraint_stabilization Constraint stabilization @ingroup constraint_overview - -Both truncation and rounding errors can prevent constraints from being + +Both truncation and rounding errors can prevent constraints from being exactly satisfied. For example, consider the bilateral holonomic constraint equation gₚ(t,q) = 0. Even if gₚ(t₀,q(t₀)) = ġₚ(t₀,q(t₀),v(t₀)) = g̈ₚ(t₀,q(t₀),v(t₀),v̇(t₀)) = 0, it is often @@ -317,7 +319,7 @@ constraint problem data

@ref drake::multibody::constraint::ConstraintVelProblemData "ConstraintVelProblemData") */ - + /** @defgroup constraint_references References @ingroup constraint_overview diff --git a/multibody/multibody_tree/body_node.h b/multibody/multibody_tree/body_node.h index 53b0d1549d42..42ac04f41626 100644 --- a/multibody/multibody_tree/body_node.h +++ b/multibody/multibody_tree/body_node.h @@ -181,8 +181,10 @@ class BodyNode : public MultibodyTreeElement, BodyNodeIndex> { /// This method is used by MultibodyTree within a base-to-tip loop to compute /// this node's kinematics that only depend on generalized positions. /// This method aborts in Debug builds when: + /// /// - Called on the _root_ node. /// - `pc` is nullptr. + /// /// @param[in] context The context with the state of the MultibodyTree model. /// @param[out] pc A pointer to a valid, non nullptr, kinematics cache. /// @pre CalcPositionKinematicsCache_BaseToTip() must have already been called diff --git a/multibody/multibody_tree/multibody_plant/contact_info.h b/multibody/multibody_tree/multibody_plant/contact_info.h index 5a1e37bee1ab..8372002d40a2 100644 --- a/multibody/multibody_tree/multibody_plant/contact_info.h +++ b/multibody/multibody_tree/multibody_plant/contact_info.h @@ -16,6 +16,7 @@ namespace multibody_plant { /** A class containing information regarding contact response between two bodies including: + - The pair of bodies that are contacting, referenced by their BodyIndex. - A resultant contact force. - A contact point. diff --git a/multibody/multibody_tree/multibody_plant/contact_results_to_lcm.h b/multibody/multibody_tree/multibody_plant/contact_results_to_lcm.h index aa175be2cf08..68d2d51ba479 100644 --- a/multibody/multibody_tree/multibody_plant/contact_results_to_lcm.h +++ b/multibody/multibody_tree/multibody_plant/contact_results_to_lcm.h @@ -73,6 +73,7 @@ class ContactResultsToLcmSystem final : public systems::LeafSystem { This is a convenience method to simplify some common boilerplate for adding contact results visualization capability to a Diagram. What it does is: + - adds systems ContactResultsToLcmSystem and LcmPublisherSystem to the Diagram and connects the draw message output to the publisher input, - connects the `multibody_plant` contact results output to the diff --git a/multibody/multibody_tree/multibody_plant/multibody_plant.h b/multibody/multibody_tree/multibody_plant/multibody_plant.h index a029fb24f747..151924f9dc1b 100644 --- a/multibody/multibody_tree/multibody_plant/multibody_plant.h +++ b/multibody/multibody_tree/multibody_plant/multibody_plant.h @@ -44,6 +44,7 @@ namespace multibody_plant { /// concepts/notation. /// /// %MultibodyPlant provides a user-facing API to: +/// /// - add bodies, joints, force elements, and constraints, /// - register geometries to a provided SceneGraph instance, /// - create and manipulate its Context, @@ -151,7 +152,7 @@ namespace multibody_plant { /// Refer to the documentation provided in each of the methods above for further /// details. /// -/// @section Finalize() stage +/// @section finalize_stage Finalize() stage /// /// Once the user is done adding modeling elements and registering geometry, a /// call to Finalize() must be performed. This call will: diff --git a/multibody/multibody_tree/multibody_tree.h b/multibody/multibody_tree/multibody_tree.h index 934cffc5204b..eeca5c16809a 100644 --- a/multibody/multibody_tree/multibody_tree.h +++ b/multibody/multibody_tree/multibody_tree.h @@ -1923,6 +1923,7 @@ class MultibodyTree { /// Computes into the position kinematics `pc` all the kinematic quantities /// that depend on the generalized positions only. These include: + /// /// - For each body B, the pose `X_BF` of each of the frames F attached to /// body B. /// - Pose `X_WB` of each body B in the model as measured and expressed in @@ -2552,6 +2553,7 @@ class MultibodyTree { /// The new deep copy is guaranteed to have exactly the same /// MultibodyTreeTopology as the original tree the method is called on. /// This method ensures the following cloning order: + /// /// - Body objects, and their corresponding BodyFrame objects. /// - Frame objects. /// - If a Frame is attached to another frame, its parent frame is diff --git a/multibody/multibody_tree/multibody_tree_topology.h b/multibody/multibody_tree/multibody_tree_topology.h index 69f4e89ef253..83e502d8dec7 100644 --- a/multibody/multibody_tree/multibody_tree_topology.h +++ b/multibody/multibody_tree/multibody_tree_topology.h @@ -688,6 +688,7 @@ class MultibodyTreeTopology { /// how bodies, joints and, any other elements connect with each other, and /// performs all the required pre-processing to perform computations at a /// later stage. This preprocessing includes: + /// /// - sorting in BFT order for fast recursions through the tree, /// - computation of state sizes and of pool sizes within cache entries, /// - computation of index maps to retrieve either state or cache entries for @@ -906,6 +907,7 @@ class MultibodyTreeTopology { /// sub-graph will have all of the bodies welded to the world; all /// subsequent sub-graphs will be in no particular order. /// A few more notes: + /// /// - Each body in the topology is included in one set and one set only. /// - The maximum size of the list equals the number of bodies in the topology /// (num_bodies()). This corresponds to a topology with no weld mobilizers. diff --git a/multibody/multibody_tree/rotational_inertia.h b/multibody/multibody_tree/rotational_inertia.h index 332105cf6772..7db9e4ab172d 100644 --- a/multibody/multibody_tree/rotational_inertia.h +++ b/multibody/multibody_tree/rotational_inertia.h @@ -462,6 +462,7 @@ class RotationalInertia { /// Performs several necessary checks to verify whether `this` rotational /// inertia *could* be physically valid, including: + /// /// - No NaN moments or products of inertia. /// - Ixx, Iyy, Izz and principal moments are all non-negative. /// - Ixx, Iyy Izz and principal moments satisfy the triangle inequality: diff --git a/multibody/multibody_tree/spatial_inertia.h b/multibody/multibody_tree/spatial_inertia.h index d8efe07f836c..ceea418bf118 100755 --- a/multibody/multibody_tree/spatial_inertia.h +++ b/multibody/multibody_tree/spatial_inertia.h @@ -211,6 +211,7 @@ class SpatialInertia { /// Performs a number of checks to verify that this is a physically valid /// spatial inertia. /// The checks performed are: + /// /// - No NaN entries. /// - Non-negative mass. /// - Non-negative principal moments about the center of mass. @@ -219,6 +220,7 @@ class SpatialInertia { /// - `Ixx + Iyy >= Izz` /// - `Ixx + Izz >= Iyy` /// - `Iyy + Izz >= Ixx` + /// /// These are the tests performed by /// RotationalInertia::CouldBePhysicallyValid() which become a sufficient /// condition when performed on a rotational inertia about a body's center of diff --git a/perception/point_cloud.h b/perception/point_cloud.h index 0f18f6b54501..052daca97544 100644 --- a/perception/point_cloud.h +++ b/perception/point_cloud.h @@ -28,16 +28,16 @@ namespace perception { /// /// Definitions: /// -/// - point - An entry in a point cloud (not exclusively an XYZ point). -/// - feature - Abstract representation of local properties (geometric and -/// non-geometric) -/// - descriptor - Concrete representation of a feature. -/// - field - A feature or descriptor described by the point cloud. +/// - point - An entry in a point cloud (not exclusively an XYZ point). +/// - feature - Abstract representation of local properties (geometric and +/// non-geometric) +/// - descriptor - Concrete representation of a feature. +/// - field - A feature or descriptor described by the point cloud. /// /// This point cloud class provides the following fields: /// -/// - xyz - Cartesian XYZ coordinates (float[3]). -/// - descriptor - An descriptor that is run-time defined (float[X]). +/// - xyz - Cartesian XYZ coordinates (float[3]). +/// - descriptor - An descriptor that is run-time defined (float[X]). /// /// @note "contiguous" here means contiguous in memory. This was chosen to /// avoid ambiguity between PCL and Eigen, where in PCL "dense" implies that diff --git a/solvers/mathematical_program.h b/solvers/mathematical_program.h index ee9f6e54f9dd..409989eb3de1 100644 --- a/solvers/mathematical_program.h +++ b/solvers/mathematical_program.h @@ -318,11 +318,13 @@ class MathematicalProgram { /** Clones an optimization program. * The clone will be functionally equivalent to the source program with the * same: + * * - decision variables * - constraints * - costs * - solver settings * - initial guess + * * However, the clone's x values will be initialized to NaN, and all internal * solvers will be freshly constructed. * @retval new_prog. The newly constructed mathematical program. @@ -2105,6 +2107,7 @@ class MathematicalProgram { * Adds constraints that a given polynomial @p p is a sums-of-squares (SOS), * that is, @p p can be decomposed into `mᵀQm`, where m is the @p * monomial_basis. It returns a pair of constraint bindings expressing: + * * - The coefficients matrix Q is PSD (positive semidefinite). * - The coefficients matching conditions in linear equality constraint. */ @@ -2119,6 +2122,7 @@ class MathematicalProgram { * that is, @p p can be decomposed into `mᵀQm`, where m is the monomial * basis of all indeterminates in the program with degree equal to half the * TotalDegree of @p p. It returns a pair of constraint bindings expressing: + * * - The coefficients matrix Q is PSD (positive semidefinite). * - The coefficients matching conditions in linear equality constraint. */ @@ -2132,6 +2136,7 @@ class MathematicalProgram { * where m is the @p monomial_basis. Note that it decomposes @p e into a * polynomial with respect to `indeterminates()` in this mathematical * program. It returns a pair of constraint bindings expressing: + * * - The coefficients matrix Q is PSD (positive semidefinite). * - The coefficients matching conditions in linear equality constraint. */ @@ -2147,6 +2152,7 @@ class MathematicalProgram { * @p e into a polynomial with respect to `indeterminates()` in this * mathematical program. It returns a pair of * constraint bindings expressing: + * * - The coefficients matrix Q is PSD (positive semidefinite). * - The coefficients matching conditions in linear equality constraint. */ diff --git a/solvers/mixed_integer_rotation_constraint.h b/solvers/mixed_integer_rotation_constraint.h index 0734539fbda1..fc4dce8096af 100644 --- a/solvers/mixed_integer_rotation_constraint.h +++ b/solvers/mixed_integer_rotation_constraint.h @@ -190,6 +190,7 @@ struct AddRotationMatrixBoxSphereIntersectionReturn { * Adds binary variables that constrain the value of the column *and* row * vectors of R, in order to add the following (in some cases non-convex) * constraints as an MILP. Specifically, for column vectors Ri, we constrain: + * * - forall i, |Ri| = 1 ± envelope, * - forall i,j. i ≠ j, Ri.dot(Rj) = 0 ± envelope, * - R2 = R0.cross(R1) ± envelope, diff --git a/systems/analysis/integrator_base.h b/systems/analysis/integrator_base.h index cf03f263c849..123ba98049f5 100644 --- a/systems/analysis/integrator_base.h +++ b/systems/analysis/integrator_base.h @@ -292,6 +292,7 @@ class IntegratorBase { * an appropriate minimum step and throw an exception if the requirements * can't be achieved without going below that. Methods in this section allow * you to influence two aspects of this procedure: + * * - you can increase the minimum step size, and * - you can control whether an exception is thrown if a smaller step would * have been needed to achieve the aforementioned integrator requirements. @@ -560,6 +561,7 @@ class IntegratorBase { * typically call `IntegratorBase::IntegrateWithMultipleSteps()`. * * This method at a glance: + * * - For integrating ODEs/DAEs via Simulator * - Supports fixed step and variable step integration schemes * - Takes only a single step forward. @@ -594,6 +596,7 @@ class IntegratorBase { /// cannot advance time by @p dt in a single step. /// /// This method at a glance: + /// /// - For integrating ODEs/DAEs not using Simulator /// - Supports fixed step and variable step integration schemes /// - Takes as many steps as necessary until time has advanced by @p dt @@ -646,6 +649,7 @@ class IntegratorBase { /// necessary until time has been stepped forward by @p dt. /// /// This method at a glance: + /// /// - For integrating ODEs/DAEs not using Simulator /// - Fixed step integration (no step size reductions for error control or /// integrator convergence) diff --git a/systems/framework/cache_doxygen.h b/systems/framework/cache_doxygen.h index 3b1a0a92617b..552e2d7d27a4 100644 --- a/systems/framework/cache_doxygen.h +++ b/systems/framework/cache_doxygen.h @@ -24,9 +24,10 @@ parameters, states, input ports, accuracy) and _computed_ values (e.g. derivatives, output ports) that depend on some or all of the source values. We call the particular dependencies of a computed value its _prerequisites_. The caching system described here manages computed values so that - - they are recomputed _only if_ a prerequisite has changed, - - they are marked out of date _whenever_ a prerequisite changes, and - - _every_ access to a computed value first ensures that it is up to date. + +- they are recomputed _only if_ a prerequisite has changed, +- they are marked out of date _whenever_ a prerequisite changes, and +- _every_ access to a computed value first ensures that it is up to date. Accessing computed values is a critical, inner-loop activity during simulation (many times per step) so the implementation is designed to provide @@ -42,13 +43,14 @@ Caching is entirely about performance. Hence, other than correctness, the performance goals listed above are the primary architectural constraints. Other goals also influenced the design. Here are the main goals in roughly descending order of importance. - 1. Must be correct (same result with caching on or off). - 2. Must be fast. - 3. Must preserve independence of System and Context objects (e.g., no - cross-pointers). - 4. Should provide a simple conceptual model and API for users. - 5. Should treat all value sources and dependencies in Drake uniformly. - 6. Should be backwards compatible with the existing API. + +1. Must be correct (same result with caching on or off). +2. Must be fast. +3. Must preserve independence of System and Context objects (e.g., no + cross-pointers). +4. Should provide a simple conceptual model and API for users. +5. Should treat all value sources and dependencies in Drake uniformly. +6. Should be backwards compatible with the existing API. In service of correctness and speed we need instrumentation for debugging and performance measurement. For example, it should be possible to disable caching @@ -58,9 +60,10 @@ to verify that the results don't change. validation of dependency lists. Instead we rely on a conservative default (depends on everything), and the ability to disable caching during testing. Several follow-ons are possible to improve this: - - Runtime validation that computations only request sub-computations for which - they hold tickets (probably affordable only in Debug), and - - Use of symbolic expressions to calculate dependency lists automatically. + +- Runtime validation that computations only request sub-computations for which + they hold tickets (probably affordable only in Debug), and +- Use of symbolic expressions to calculate dependency lists automatically. @anchor cache_design_architecture

Architecture

@@ -90,17 +93,18 @@ values to be exposed directly without the intermediate cache entry, but the semantics will be unchanged. From a user perspective: - - Cache entries of arbitrary type are allocated to hold the results of all - significant computations, including built-ins like derivatives, energy, - and output ports as well as user-defined internal computations. - Prerequisites for these computations are explicitly noted at the time they - are declared; the default for user-defined cache entries is that they are - dependent on all sources. - - Computation is initiated when a result is requested via an "Eval" method, if - the result is not already up to date with respect to its prerequisites, which - are recursively obtained using their Eval methods. - - Cached results are automatically marked out of date when any of their - prerequisites may have changed. + +- Cache entries of arbitrary type are allocated to hold the results of all + significant computations, including built-ins like derivatives, energy, + and output ports as well as user-defined internal computations. + Prerequisites for these computations are explicitly noted at the time they + are declared; the default for user-defined cache entries is that they are + dependent on all sources. +- Computation is initiated when a result is requested via an "Eval" method, if + the result is not already up to date with respect to its prerequisites, which + are recursively obtained using their Eval methods. +- Cached results are automatically marked out of date when any of their + prerequisites may have changed. Figure 1 below illustrates the computational structure of a Drake LeafSystem, paired with its LeafContext. A Drake Diagram interconnects subsystems like @@ -148,12 +152,13 @@ _intra_-System dependencies are permitted; _inter_-System dependencies are expressed by listing an input port as a prerequisite. There are six kinds of value sources within a System's Context that can serve as prerequisites for cached results within that %Context: - 1. Time - 2. Input ports - 3. %Parameters (numerical and abstract) - 4. %State (including continuous, discrete, and abstract variables) - 5. Other cache entries - 6. Accuracy + +1. Time +2. Input ports +3. %Parameters (numerical and abstract) +4. %State (including continuous, discrete, and abstract variables) +5. Other cache entries +6. Accuracy In addition, we support "fixed" input ports whose values are provided locally; each such value is a value source, but is restricted to its corresponding @@ -181,10 +186,11 @@ can be properly notified when it may be invalid. An Output Port for a System is a "window" onto one of the value sources within that %System's Context; that is the only way in which internal values of a %System are exported to other Systems in a Diagram. That value source may be - - a cache entry allocated specifically for the output port, or - - a pre-existing source like a state subgroup or a cached value that has other - uses (not implemented yet), or - - an output port of a contained subsystem that has been exported. + +- a cache entry allocated specifically for the output port, or +- a pre-existing source like a state subgroup or a cached value that has other + uses (not implemented yet), or +- an output port of a contained subsystem that has been exported. An output port is a subscriber to its source, and a prerequisite to the downstream input ports that it drives. @@ -199,9 +205,10 @@ to the source output port's tracker.

Input ports

The value source for a subsystem input port is either - - an output port of a peer subsystem, or - - an input port of its parent Diagram, or - - a locally-stored value. + +- an output port of a peer subsystem, or +- an input port of its parent Diagram, or +- a locally-stored value. When an input port's value comes from a locally-stored value, we call it a _fixed_ input port. Note that the fixed value is stored as a source value in the @@ -223,9 +230,10 @@ is automatically subscribed to the input port's source's tracker. Certain computations are defined by the system framework so are automatically assigned cache entries in the Context. Currently those are: - - Leaf output ports - - Time derivatives - - Power and energy (scalars) + +- Leaf output ports +- Time derivatives +- Power and energy (scalars) Output ports that have their own Calc() methods are also automatically assigned cache entries. Currently that applies to every leaf output port, but not to @@ -313,6 +321,7 @@ input_port(i) | uᵢ | one input port | peer, parent, or self cache_entry(i) | cᵢ | one cache entry | explicit prerequisites _Notes_ + 1. %Diagram has additional subscriptions for this tracker. See the diagram-specific table in the @ref caching_implementation_for_diagrams "Diagram-specific implementation" @@ -372,13 +381,14 @@ category. Diagram contexts do have trackers for their composite state and parameters, and we must subscribe those to the corresponding child subsystem trackers to ensure notifications propagate upward. Using capital letters to denote the %Diagram composite trackers we have: - - Q = { qₛ : s ∈ 𝕊} - - V = { vₛ : s ∈ 𝕊} - - Z = { zₛ : s ∈ 𝕊} - - Xd = {xdₛ : s ∈ 𝕊} - - Xa = {xaₛ : s ∈ 𝕊} - - Pn = {pnₛ : s ∈ 𝕊} - - Pa = {paₛ : s ∈ 𝕊} + +- Q = { qₛ : s ∈ 𝕊} +- V = { vₛ : s ∈ 𝕊} +- Z = { zₛ : s ∈ 𝕊} +- Xd = {xdₛ : s ∈ 𝕊} +- Xa = {xaₛ : s ∈ 𝕊} +- Pn = {pnₛ : s ∈ 𝕊} +- Pa = {paₛ : s ∈ 𝕊} where 𝕊 is the set of immediate child subsystems of a %Diagram. Note that the higher-level built-in trackers (all_state, all_parameters, configuration, etc.) @@ -390,11 +400,12 @@ subsystems. In addition to composite sources, Diagrams have a limited set of built-in computations that are composites of their children's corresponding computations. These are - - xcdot: composite time derivatives - - pe: summed potential energy - - ke: summed kinetic energy - - pc: summed conservative power - - pnc: summed non-conservative power + +- xcdot: composite time derivatives +- pe: summed potential energy +- ke: summed kinetic energy +- pc: summed conservative power +- pnc: summed non-conservative power Each of these has a cache entry and an associated Calc() method that sets the cache value by visiting the children to Eval() the corresponding quantities, @@ -447,6 +458,7 @@ pc | — | subsystem pc pnc | — | subsystem pnc _Notes_ + 1. Time and accuracy can be set only in the root Context so can only propagate downward. @@ -477,6 +489,7 @@ The logical cache entry object is split into two pieces to reflect the const and mutable aspects. Given a CacheIndex, either piece may be obtained very efficiently. The `const` part is a CacheEntry owned by the System, and consists of: + - The Allocator() and Calculator() methods, - a list of the Calculator's prerequisites, and - the assigned dependency ticket for this cache entry. @@ -484,6 +497,7 @@ efficiently. The `const` part is a CacheEntry owned by the System, and consists The mutable part is a CacheEntryValue and associated DependencyTracker, both owned by the Context. The CacheEntryValue is designed to optimize access efficiency. It contains: + - an AbstractValue (obtained by invoking the Allocator()), and - a flag indicating whether the value is out of date with respect to its prerequisites, and @@ -502,6 +516,7 @@ chosen so that only a single check that an int is zero is required to know that a value may be returned without computation. To summarize, the Eval() method for a CacheEntry operates as follows: + 1. The CacheEntryValue is obtained using an array index into the Context's cache. 2. If the value is out of date (or caching is disabled), call the @@ -512,6 +527,7 @@ To summarize, the Eval() method for a CacheEntry operates as follows: The DependencyTracker is designed to optimize invalidation efficiency. It contains: + - Pointers to the prerequisite DependencyTrackers to which it has subscribed, - pointers to downstream subscribers that have registered as dependents of this cache entry, @@ -519,19 +535,20 @@ It contains: - bookkeeping and statistics-gathering members. A prerequisite change to a particular value source works like this: - 1. A "set" method or method providing mutable access to a source is invoked - on a Context. - 2. A unique "change event" number N is assigned. - 3. The ticket associated with the source is used to find its DependencyTracker - (just an array index operation). - 4. The tracker's notification method is invoked, providing the change event - number N. - 5. The tracker records N, and then notifies all trackers on its "subscribers" - list that change event N is occurring. - 6. A notified tracker first checks its recorded change event number. If it is - already set to N then no further action is taken. Otherwise, it records N, - marks the associated cache entry (if any) out of date, and recursively - notifies all trackers on its "subscribers" list. + +1. A "set" method or method providing mutable access to a source is invoked + on a Context. +2. A unique "change event" number N is assigned. +3. The ticket associated with the source is used to find its DependencyTracker + (just an array index operation). +4. The tracker's notification method is invoked, providing the change event + number N. +5. The tracker records N, and then notifies all trackers on its "subscribers" + list that change event N is occurring. +6. A notified tracker first checks its recorded change event number. If it is + already set to N then no further action is taken. Otherwise, it records N, + marks the associated cache entry (if any) out of date, and recursively + notifies all trackers on its "subscribers" list. For efficiency, changes to multiple value sources can be grouped into the same change event. Also, DependencyTracker subscriber lists and cache entry diff --git a/systems/framework/context.h b/systems/framework/context.h index 53a109f0f90d..190824ec3a2e 100644 --- a/systems/framework/context.h +++ b/systems/framework/context.h @@ -50,6 +50,7 @@ class Context : public ContextBase { /// @name Accessors for locally-stored values /// Methods in this group provide `const` access to values stored locally in /// this %Context. The available values are: + /// /// - time /// - state /// - parameters @@ -201,6 +202,7 @@ class Context : public ContextBase { /// @name Methods for changing locally-stored values /// Methods in this group allow changes to the values of quantities stored /// locally in this %Context. The changeable quantities are: + /// /// - time /// - state /// - parameters @@ -225,6 +227,7 @@ class Context : public ContextBase { /// ///

Caching

/// Drake provides a caching system that is responsible for + /// /// - storing computed results in the %Context's _cache_, and /// - ensuring that any cached result that _may_ be invalid is marked /// "out of date". diff --git a/systems/framework/system.h b/systems/framework/system.h index 62f10b4a803d..cacb72711fbe 100644 --- a/systems/framework/system.h +++ b/systems/framework/system.h @@ -289,10 +289,11 @@ class System : public SystemBase { /// a system with m input ports: `I = i₀, i₁, ..., iₘ₋₁`, and n output ports, /// `O = o₀, o₁, ..., oₙ₋₁`, the return map will contain pairs (u, v) such /// that - /// - 0 ≤ u < m, - /// - 0 ≤ v < n, - /// - and there _might_ be a direct feedthrough from input iᵤ to each - /// output oᵥ. + /// + /// - 0 ≤ u < m, + /// - 0 ≤ v < n, + /// - and there _might_ be a direct feedthrough from input iᵤ to each + /// output oᵥ. virtual std::multimap GetDirectFeedthroughs() const = 0; /// Returns `true` if any of the inputs to the system might be directly diff --git a/systems/lcm/connect_lcm_scope.h b/systems/lcm/connect_lcm_scope.h index 6791ef509a44..196dc1acd044 100644 --- a/systems/lcm/connect_lcm_scope.h +++ b/systems/lcm/connect_lcm_scope.h @@ -18,6 +18,7 @@ namespace lcm { avoided). What it does is: + - adds systems LcmtDrakeSignalTranslator and LcmPublisherSystem to the Diagram and connects the translator output to the publisher input, and - connects the @p src output to the LcmtDrakeSignalTranslator diff --git a/systems/sensors/camera_info.h b/systems/sensors/camera_info.h index 3ae8dea558c8..e4d127abeee8 100644 --- a/systems/sensors/camera_info.h +++ b/systems/sensors/camera_info.h @@ -21,6 +21,7 @@ namespace sensors { /// /// There are three types of the coordinate systems that are relevant to this /// class: +/// /// - the camera coordinate system /// - the image coordinate system /// - the pixel coordinate system. diff --git a/systems/sensors/depth_sensor.h b/systems/sensors/depth_sensor.h index 94ca44faceb9..e5e9e3502330 100644 --- a/systems/sensors/depth_sensor.h +++ b/systems/sensors/depth_sensor.h @@ -41,16 +41,16 @@ namespace sensors { /// are defined in terms of the sensor's base frame. Together they define a /// transform between the base frame and optical frame. /// -/// 1. yaw - The horizontal scan angle that rotates about this sensor's base -/// frame's +Z axis using the right-hand rule. When the pitch is -/// zero, a yaw of zero results in this sensor measuring down the -/// base frame's +X axis. -/// 2. pitch - The vertical scan angle that rotates about this sensor's base -/// frames's -Y axis using using the right-hand rule. In other -/// words, when the pitch increases from zero to PI / 2, this -/// sensor's optical frame is tilted to point upward. When the yaw -/// is zero, a pitch of zero results in this sensor measuring down -/// the base frame's +X axis. +/// 1. yaw - The horizontal scan angle that rotates about this sensor's base +/// frame's +Z axis using the right-hand rule. When the pitch is +/// zero, a yaw of zero results in this sensor measuring down the +/// base frame's +X axis. +/// 2. pitch - The vertical scan angle that rotates about this sensor's base +/// frames's -Y axis using using the right-hand rule. In other +/// words, when the pitch increases from zero to PI / 2, this +/// sensor's optical frame is tilted to point upward. When the yaw +/// is zero, a pitch of zero results in this sensor measuring down +/// the base frame's +X axis. /// /// To summarize, the location from which this sensor's rays emanate is /// (0, 0, 0) in the base frame. When both the yaw and pitch are zero, this