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 | . +
@@ -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