From 8592c35bd05810323f9b7f46b42542cd53349168 Mon Sep 17 00:00:00 2001 From: Jeremy Nimmer Date: Mon, 9 Mar 2020 14:35:17 -0400 Subject: [PATCH] doc: Use doxygen macro for tparam scalartype boilerplate (#12825) --- common/default_scalars.h | 67 +++++++++---------- .../exponential_plus_piecewise_polynomial.h | 2 + common/trajectories/piecewise_polynomial.h | 6 +- common/trajectories/piecewise_quaternion.h | 3 +- common/trajectories/piecewise_trajectory.h | 6 +- doc/Doxyfile_CXX.in | 3 + examples/acrobot/acrobot_plant.h | 9 +-- examples/bead_on_a_wire/bead_on_a_wire.h | 10 +-- examples/bouncing_ball/bouncing_ball.h | 12 +--- examples/compass_gait/compass_gait.h | 8 +-- .../manipulation_station.h | 7 +- examples/particles/particle.h | 9 +-- examples/pendulum/pendulum_plant.h | 8 +-- .../planar_gripper/planar_gripper_common.h | 2 +- examples/rimless_wheel/rimless_wheel.h | 7 +- examples/rod2d/rod2d.h | 13 ++-- examples/scene_graph/bouncing_ball_plant.h | 6 +- examples/scene_graph/solar_system.h | 6 +- examples/van_der_pol/van_der_pol.h | 8 +-- geometry/frame_kinematics_vector.h | 11 +-- geometry/geometry_state.h | 11 +-- geometry/proximity_engine.h | 10 +-- geometry/query_object.h | 11 +-- geometry/query_results/contact_surface.h | 2 +- geometry/scene_graph.h | 11 +-- math/barycentric.h | 6 +- math/rigid_transform.h | 2 +- math/roll_pitch_yaw.h | 8 +-- math/rotation_matrix.h | 8 +-- multibody/benchmarks/acrobot/BUILD.bazel | 2 +- multibody/benchmarks/acrobot/acrobot.cc | 8 +-- multibody/benchmarks/acrobot/acrobot.h | 7 +- .../benchmarks/mass_damper_spring/BUILD.bazel | 1 + .../mass_damper_spring_analytical_solution.cc | 7 +- .../mass_damper_spring_analytical_solution.h | 8 +-- multibody/constraint/constraint_solver.h | 8 +-- multibody/math/spatial_acceleration.h | 2 +- multibody/math/spatial_force.h | 2 +- multibody/math/spatial_momentum.h | 2 +- multibody/math/spatial_vector.h | 2 +- multibody/math/spatial_velocity.h | 2 +- multibody/plant/contact_results.h | 2 +- multibody/plant/contact_results_to_lcm.h | 2 +- multibody/plant/coulomb_friction.h | 2 +- multibody/plant/hydroelastic_contact_info.h | 2 +- multibody/plant/multibody_plant.h | 3 +- multibody/plant/point_pair_contact_info.h | 2 +- multibody/plant/tamsi_solver.h | 2 +- .../test_utilities/floating_body_plant.h | 10 +-- .../tree/acceleration_kinematics_cache.h | 9 +-- multibody/tree/articulated_body_force_cache.h | 10 +-- multibody/tree/articulated_body_inertia.h | 10 +-- .../tree/articulated_body_inertia_cache.h | 10 +-- multibody/tree/body.h | 4 +- multibody/tree/body_node.h | 2 +- multibody/tree/fixed_offset_frame.h | 2 +- multibody/tree/force_element.h | 2 +- multibody/tree/frame.h | 2 +- multibody/tree/frame_base.h | 2 +- multibody/tree/joint.h | 2 +- multibody/tree/joint_actuator.h | 11 +-- multibody/tree/linear_spring_damper.h | 11 +-- multibody/tree/mobilizer.h | 2 +- multibody/tree/mobilizer_impl.h | 2 +- multibody/tree/model_instance.h | 8 +-- multibody/tree/multibody_element.h | 2 +- multibody/tree/multibody_forces.h | 11 +-- multibody/tree/multibody_tree.h | 11 +-- multibody/tree/position_kinematics_cache.h | 11 +-- multibody/tree/prismatic_joint.h | 11 +-- multibody/tree/prismatic_mobilizer.h | 11 +-- .../tree/quaternion_floating_mobilizer.h | 11 +-- multibody/tree/revolute_joint.h | 11 +-- multibody/tree/revolute_mobilizer.h | 11 +-- multibody/tree/revolute_spring.h | 2 +- multibody/tree/rigid_body.h | 11 +-- multibody/tree/rotational_inertia.h | 9 +-- multibody/tree/space_xyz_mobilizer.h | 11 +-- multibody/tree/spatial_inertia.h | 10 +-- .../tree/test/free_rotating_body_plant.h | 11 +-- .../tree/uniform_gravity_field_element.h | 11 +-- multibody/tree/unit_inertia.h | 10 +-- multibody/tree/velocity_kinematics_cache.h | 11 +-- multibody/tree/weld_joint.h | 11 +-- multibody/tree/weld_mobilizer.h | 11 +-- systems/analysis/antiderivative_function.h | 7 +- .../analysis/bogacki_shampine3_integrator.h | 7 +- systems/analysis/implicit_euler_integrator.h | 11 +-- systems/analysis/implicit_integrator.h | 2 +- systems/analysis/initial_value_problem.h | 7 +- systems/analysis/integrator_base.h | 2 +- systems/analysis/radau_integrator.h | 9 +-- systems/analysis/runge_kutta3_integrator.h | 11 +-- systems/analysis/runge_kutta5_integrator.h | 8 +-- .../analysis/scalar_initial_value_problem.h | 7 +- systems/analysis/simulator.h | 9 +-- .../controlled_spring_mass_system.h | 10 +-- .../velocity_implicit_euler_integrator.h | 3 +- systems/controllers/inverse_dynamics.h | 5 +- .../controllers/inverse_dynamics_controller.h | 6 +- .../linear_model_predictive_controller.h | 5 +- systems/controllers/pid_controlled_system.h | 8 +-- systems/controllers/pid_controller.h | 9 +-- systems/framework/abstract_values.h | 2 - systems/framework/basic_vector.h | 2 +- systems/framework/context.h | 4 +- systems/framework/continuous_state.h | 2 +- systems/framework/diagram.h | 2 +- systems/framework/diagram_context.h | 3 +- systems/framework/diagram_continuous_state.h | 2 +- systems/framework/diagram_output_port.h | 11 +-- systems/framework/discrete_values.h | 2 +- systems/framework/event_collection.h | 2 +- systems/framework/fixed_input_port_value.h | 4 +- systems/framework/input_port.h | 3 +- systems/framework/leaf_context.h | 4 +- systems/framework/leaf_output_port.h | 12 +--- systems/framework/leaf_system.h | 2 +- systems/framework/output_port.h | 12 +--- systems/framework/parameters.h | 2 +- .../framework/single_output_vector_source.h | 2 +- systems/framework/state.h | 2 +- systems/framework/subvector.h | 2 +- systems/framework/supervector.h | 2 +- systems/framework/system.h | 2 +- systems/framework/system_constraint.h | 12 +--- systems/framework/system_output.h | 3 +- .../system_scalar_conversion_doxygen.h | 10 +-- systems/framework/system_scalar_converter.h | 6 +- systems/framework/value_to_abstract_value.h | 3 +- systems/framework/vector_base.h | 2 +- systems/framework/vector_system.h | 2 +- .../spring_mass_system/spring_mass_system.h | 19 +----- systems/primitives/adder.h | 13 +--- systems/primitives/affine_system.h | 18 ++--- systems/primitives/barycentric_system.h | 2 + systems/primitives/constant_value_source.h | 12 +--- systems/primitives/constant_vector_source.h | 12 +--- systems/primitives/demultiplexer.h | 11 +-- systems/primitives/discrete_derivative.h | 16 +---- systems/primitives/discrete_time_delay.h | 4 +- .../primitives/first_order_low_pass_filter.h | 12 +--- systems/primitives/gain.h | 15 +---- systems/primitives/integrator.h | 10 +-- systems/primitives/linear_system.h | 25 +------ systems/primitives/matrix_gain.h | 12 +--- systems/primitives/multiplexer.h | 12 +--- systems/primitives/pass_through.h | 13 +--- systems/primitives/port_switch.h | 9 +-- systems/primitives/saturation.h | 7 +- systems/primitives/signal_log.h | 2 +- systems/primitives/signal_logger.h | 9 +-- systems/primitives/sine.h | 15 +---- systems/primitives/symbolic_vector_system.h | 6 +- systems/primitives/trajectory_affine_system.h | 12 +--- systems/primitives/trajectory_linear_system.h | 12 +--- systems/primitives/trajectory_source.h | 9 +-- systems/primitives/wrap_to_system.h | 7 +- systems/primitives/zero_order_hold.h | 1 + systems/rendering/frame_velocity.h | 3 +- .../multibody_position_to_geometry_pose.h | 7 +- systems/rendering/pose_aggregator.h | 10 +-- systems/rendering/pose_bundle.h | 10 +-- systems/rendering/pose_vector.h | 3 +- systems/sensors/beam_model.h | 6 +- .../com_github_pybind_pybind11/mkdoc.py | 5 ++ 166 files changed, 249 insertions(+), 970 deletions(-) diff --git a/common/default_scalars.h b/common/default_scalars.h index 2e5312b95db9..1b74cc168045 100644 --- a/common/default_scalars.h +++ b/common/default_scalars.h @@ -3,8 +3,8 @@ #include "drake/common/autodiff.h" #include "drake/common/symbolic.h" -// N.B. `CommonScalarPack` in `systems_pybind.h` should be kept in sync -// with this file. +// N.B. `CommonScalarPack` and `NonSymbolicScalarPack` in `systems_pybind.h` +// should be kept in sync with this file. /// @defgroup default_scalars Default Scalars /// @ingroup technical_notes @@ -25,27 +25,34 @@ /// /// Alternatively, reference to "default nonsymbolic scalars" means all except /// `drake::symbolic::Expression`. +/// +/// For code within Drake, we offer Doxygen custom commands to document the +/// `` template parameter in the conventional cases: +/// +/// - @c \@tparam_default_scalar for the default scalars. +/// - @c \@tparam_nonsymbolic_scalar for the default nonsymbolic scalars. +/// - @c \@tparam_double_only for only the `double` scalar and nothing else. +/// +/// All three commands assume that the template parameter is named `T`. When +/// possible, prefer to use these commands instead of writing out a @c \@tparam +/// line manually. -/// A macro that defines explicit class template instantiations for Drake's -/// default set of supported scalar types. This macro should only be used in -/// .cc files, never in .h files. +/// @name Template instantiation macros +/// These macros either declare or define class template instantiations for +/// Drake's supported scalar types (see @ref default_scalars), either "default +/// scalars" or "default nonsymbolic scalars". Use the `DECLARE` macros only +/// in .h files; use the `DEFINE` macros only in .cc files. /// /// @param SomeType the template typename to instantiate, *including* the /// leading `class` or `struct` keyword. /// -/// Currently the supported types are: -/// -/// - double -/// - drake::AutoDiffXd -/// - drake::symbolic::Expression -/// /// Example `my_system.h`: /// @code /// #include "drake/common/default_scalars.h" /// /// namespace sample { /// template -/// class MySystem final : public LeafSystem { +/// class MySystem final : public drake::systems::LeafSystem { /// ... /// }; /// } // namespace sample @@ -63,42 +70,34 @@ /// @endcode /// /// See also @ref system_scalar_conversion. +/// @{ + +/// Defines template instantiations for Drake's default scalars. +/// This should only be used in .cc files, never in .h files. #define DRAKE_DEFINE_CLASS_TEMPLATE_INSTANTIATIONS_ON_DEFAULT_SCALARS( \ SomeType) \ -DRAKE_DEFINE_CLASS_TEMPLATE_INSTANTIATIONS_ON_DEFAULT_NONSYMBOLIC_SCALARS( \ - SomeType) \ +template SomeType; \ +template SomeType<::drake::AutoDiffXd>; \ template SomeType<::drake::symbolic::Expression>; -// N.B. `NonSymbolicScalarPack` in `systems_pybind.h` should be kept in sync -// with this. -/// A macro that defines explicit class template instantiations for Drake's -/// default set of supported scalar types, excluding all symbolic types. This -/// macro should only be used in .cc files, never in .h files. This is -/// identical to DRAKE_DEFINE_CLASS_TEMPLATE_INSTANTIATIONS_ON_DEFAULT_SCALARS -/// except that it does not define support for any drake::symbolic types. +/// Defines template instantiations for Drake's default nonsymbolic scalars. +/// This should only be used in .cc files, never in .h files. #define \ DRAKE_DEFINE_CLASS_TEMPLATE_INSTANTIATIONS_ON_DEFAULT_NONSYMBOLIC_SCALARS( \ SomeType) \ template SomeType; \ template SomeType<::drake::AutoDiffXd>; -/// A macro that declares that an explicit class instantiation exists in the -/// same library for Drake's default set of supported scalar types (having -/// been defined by -/// DRAKE_DEFINE_CLASS_TEMPLATE_INSTANTIATIONS_ON_DEFAULT_SCALARS in a .cc -/// file) . This macro should only be used in .h files, never in .cc files. +/// Declares that template instantiations exist for Drake's default scalars. +/// This should only be used in .h files, never in .cc files. #define DRAKE_DECLARE_CLASS_TEMPLATE_INSTANTIATIONS_ON_DEFAULT_SCALARS( \ SomeType) \ -DRAKE_DECLARE_CLASS_TEMPLATE_INSTANTIATIONS_ON_DEFAULT_NONSYMBOLIC_SCALARS( \ - SomeType) \ +extern template SomeType; \ +extern template SomeType<::drake::AutoDiffXd>; \ extern template SomeType<::drake::symbolic::Expression>; -/// A macro that declares that an explicit class instantiation exists in the -/// same library for Drake's default set of supported scalar types, excluding -/// all symbolic types (having been defined by -/// DRAKE_DEFINE_CLASS_TEMPLATE_INSTANTIATIONS_ON_DEFAULT_NONSYMBOLIC_SCALARS -/// in a .cc file) . This macro should only be used in .h files, never in .cc -/// files. +/// Declares that template instantiations exist for Drake's default nonsymbolic +/// scalars. This should only be used in .h files, never in .cc files. #define \ DRAKE_DECLARE_CLASS_TEMPLATE_INSTANTIATIONS_ON_DEFAULT_NONSYMBOLIC_SCALARS( \ SomeType) \ diff --git a/common/trajectories/exponential_plus_piecewise_polynomial.h b/common/trajectories/exponential_plus_piecewise_polynomial.h index 5e3368b4686d..a46f8246c278 100644 --- a/common/trajectories/exponential_plus_piecewise_polynomial.h +++ b/common/trajectories/exponential_plus_piecewise_polynomial.h @@ -15,6 +15,8 @@ namespace trajectories { /** * y(t) = K * exp(A * (t - t_j)) * alpha.col(j) + piecewise_polynomial_part(t) + * + * @tparam_double_only */ template class ExponentialPlusPiecewisePolynomial final diff --git a/common/trajectories/piecewise_polynomial.h b/common/trajectories/piecewise_polynomial.h index 8a332f0bfb1d..1e4ae5baae00 100644 --- a/common/trajectories/piecewise_polynomial.h +++ b/common/trajectories/piecewise_polynomial.h @@ -57,11 +57,7 @@ namespace trajectories { * the range defined by the breaks. So `pp.value(-2.0, row, col)` in the example * above would evaluate to -1.0. See value(). * - * @tparam T is a scalar type. - * - * Explicit instantiations are provided for: - * - * - double + * @tparam_double_only */ template class PiecewisePolynomial final : public PiecewiseTrajectory { diff --git a/common/trajectories/piecewise_quaternion.h b/common/trajectories/piecewise_quaternion.h index 68a5a47e37a1..cfa2926b2407 100644 --- a/common/trajectories/piecewise_quaternion.h +++ b/common/trajectories/piecewise_quaternion.h @@ -26,8 +26,7 @@ namespace trajectories { * Another intuitive way to think about this is that consecutive quaternions * have the shortest geodesic distance on the unit sphere. * - * @tparam T, double. - * + * @tparam_double_only */ template class PiecewiseQuaternionSlerp final : public PiecewiseTrajectory { diff --git a/common/trajectories/piecewise_trajectory.h b/common/trajectories/piecewise_trajectory.h index 7362d71156f7..2a5152a2ab78 100644 --- a/common/trajectories/piecewise_trajectory.h +++ b/common/trajectories/piecewise_trajectory.h @@ -15,11 +15,7 @@ namespace trajectories { /// segments of time (delimited by `breaks`) to implement a trajectory that /// is represented by simpler logic in each segment or "piece". /// -/// @tparam T is the scalar type. -/// -/// Instantiated templates for the following kinds of T's are provided: -/// -/// - double +/// @tparam_double_only template class PiecewiseTrajectory : public Trajectory { public: diff --git a/doc/Doxyfile_CXX.in b/doc/Doxyfile_CXX.in index 6c998d6856b7..5f520956f5ad 100644 --- a/doc/Doxyfile_CXX.in +++ b/doc/Doxyfile_CXX.in @@ -43,6 +43,9 @@ ALIASES = "default=@n @a Default: " \ "system{3}=
\2
\1\3
" \ "input_port{1}=\1 →" \ "output_port{1}=→ \1" \ + "tparam_default_scalar=@tparam T The scalar type, which must be one of the @ref default_scalars \"default scalars\". "\ + "tparam_nonsymbolic_scalar=@tparam T The scalar type, which must be one of the @ref default_scalars \"default nonsymbolic scalars\". "\ + "tparam_double_only=@tparam T The scalar type, which must be `double`. "\ "pydrake_mkdoc_identifier{1}= " \ "exclude_from_pydrake_mkdoc{1}= " TCL_SUBST = diff --git a/examples/acrobot/acrobot_plant.h b/examples/acrobot/acrobot_plant.h index 8be14e0528c2..7ccab5a51e35 100644 --- a/examples/acrobot/acrobot_plant.h +++ b/examples/acrobot/acrobot_plant.h @@ -28,14 +28,7 @@ namespace acrobot { /// @input_port{elbow_torque}, /// @output_port{acrobot_state} } /// -/// @tparam T The vector element type, which must be a valid Eigen scalar. -/// -/// Instantiated templates for the following kinds of T's are provided: -/// -/// - double -/// - drake::AutoDiffXd -/// - symbolic::Expression -/// +/// @tparam_default_scalar /// @ingroup acrobot_systems template class AcrobotPlant : public systems::LeafSystem { diff --git a/examples/bead_on_a_wire/bead_on_a_wire.h b/examples/bead_on_a_wire/bead_on_a_wire.h index c1cab07aa11b..31aa378361d6 100644 --- a/examples/bead_on_a_wire/bead_on_a_wire.h +++ b/examples/bead_on_a_wire/bead_on_a_wire.h @@ -62,14 +62,6 @@ namespace bead_on_a_wire { /// class expects that this inverse function may be ill-defined). /// g(x) = 0 will only be satisfied if x corresponds to a point on the wire. /// -/// @tparam T The vector element type, which must be a valid Eigen scalar. -/// -/// Instantiated templates for the following scalar types @p T are provided: -/// -/// - double -/// -/// They are already available to link against in the library implementation. -/// /// Inputs: One input (generalized external force) for the bead on a wire /// simulated in minimal coordinates, three inputs (three dimensional /// external force applied to the center of mass) for the bead on a @@ -82,6 +74,8 @@ namespace bead_on_a_wire { /// m/s, respectively, for the bead simulated in absolute coordinates. /// /// Outputs: same as state. +/// +/// @tparam_double_only template class BeadOnAWire : public systems::LeafSystem { public: diff --git a/examples/bouncing_ball/bouncing_ball.h b/examples/bouncing_ball/bouncing_ball.h index fc0cb0541809..cf428aac143d 100644 --- a/examples/bouncing_ball/bouncing_ball.h +++ b/examples/bouncing_ball/bouncing_ball.h @@ -14,21 +14,13 @@ namespace bouncing_ball { /// Dynamical representation of the idealized hybrid dynamics /// of a ball dropping from a height and bouncing on a surface. /// -/// Instantiated templates for the following scalar types @p T are provided: -/// -/// - double -/// - drake::AutoDiffXd -/// - symbolic::Expression -/// -/// @tparam T The vector element type, which must be a valid Eigen scalar. -/// -/// They are already available to link against in the containing library. -/// /// Inputs: no inputs. /// States: vertical position (state index 0) and velocity (state index 1) in /// units of m and m/s, respectively. /// Outputs: vertical position (state index 0) and velocity (state index 1) in /// units of m and m/s, respectively. +/// +/// @tparam_default_scalar template class BouncingBall final : public systems::LeafSystem { public: diff --git a/examples/compass_gait/compass_gait.h b/examples/compass_gait/compass_gait.h index fcf84ae360a3..9f81a99068ac 100644 --- a/examples/compass_gait/compass_gait.h +++ b/examples/compass_gait/compass_gait.h @@ -40,13 +40,7 @@ namespace compass_gait { /// Discrete State: stance toe position.
/// Abstract State: left support indicator.
/// -/// @tparam T The vector element type, which must be a valid Eigen scalar. -/// -/// Instantiated templates for the following scalar types @p T are provided: -/// -/// - double -/// - AutoDiffXd -/// - symbolic::Expression +/// @tparam_default_scalar template class CompassGait final : public systems::LeafSystem { public: diff --git a/examples/manipulation_station/manipulation_station.h b/examples/manipulation_station/manipulation_station.h index 6ae67eae131e..c0df805126b5 100644 --- a/examples/manipulation_station/manipulation_station.h +++ b/examples/manipulation_station/manipulation_station.h @@ -121,12 +121,7 @@ enum class Setup { kNone, kManipulationClass, kClutterClearing, kPlanarIiwa }; /// Note that you *must* call Finalize() before you can use this class as a /// System. /// -/// @tparam T The scalar type. Must be a valid Eigen scalar. -/// -/// Instantiated templates for the following kinds of T's are provided: -/// -/// - double -/// +/// @tparam_double_only /// @ingroup manipulation_station_systems template class ManipulationStation : public systems::Diagram { diff --git a/examples/particles/particle.h b/examples/particles/particle.h index f8cc5af6e1b5..061996b9c804 100644 --- a/examples/particles/particle.h +++ b/examples/particles/particle.h @@ -18,14 +18,7 @@ namespace particles { /// - linear position (state/output index 0), in @f$ m @f$ units. /// - linear velocity (state/output index 1), in @f$ m/s @f$ units. /// -/// @tparam T must be a valid Eigen ScalarType. -/// -/// @note -/// Instantiated templates for the following scalar types -/// @p T are provided: -/// -/// - double -/// +/// @tparam_double_only template class Particle final : public systems::LeafSystem { public: diff --git a/examples/pendulum/pendulum_plant.h b/examples/pendulum/pendulum_plant.h index 916ab18c5603..f1c706dfb4bb 100644 --- a/examples/pendulum/pendulum_plant.h +++ b/examples/pendulum/pendulum_plant.h @@ -17,13 +17,7 @@ namespace pendulum { /// @output_port{state} /// } /// -/// @tparam T The vector element type, which must be a valid Eigen scalar. -/// -/// Instantiated templates for the following kinds of T's are provided: -/// -/// - double -/// - AutoDiffXd -/// - symbolic::Expression +/// @tparam_default_scalar template class PendulumPlant final : public systems::LeafSystem { public: diff --git a/examples/planar_gripper/planar_gripper_common.h b/examples/planar_gripper/planar_gripper_common.h index d32d8ecde403..6b2c80385f50 100644 --- a/examples/planar_gripper/planar_gripper_common.h +++ b/examples/planar_gripper/planar_gripper_common.h @@ -44,8 +44,8 @@ constexpr int kNumJoints = kNumFingers * 2; * fingertips. This method welds the planar-gripper such that all motion lies in * the Y-Z plane (in frame G). Note: The planar gripper frame G perfectly * coincides with the world coordinate frame W when welded via this method. - * @tparam T The scalar type. Currently only supports double. * @param plant The plant containing the planar-gripper. + * @tparam_double_only */ template void WeldGripperFrames(MultibodyPlant* plant); diff --git a/examples/rimless_wheel/rimless_wheel.h b/examples/rimless_wheel/rimless_wheel.h index 3d555e84a118..3f12016c8984 100644 --- a/examples/rimless_wheel/rimless_wheel.h +++ b/examples/rimless_wheel/rimless_wheel.h @@ -36,12 +36,7 @@ namespace rimless_wheel { /// Parameters: mass, length, number of spokes, etc, are all set as Context /// parameters using RimlessWheelParams. /// -/// @tparam T The vector element type, which must be a valid Eigen scalar. -/// Instantiated templates for the following scalar types @p T are provided: -/// -/// - double -/// - AutoDiffXd -/// +/// @tparam_nonsymbolic_scalar template class RimlessWheel final : public systems::LeafSystem { public: diff --git a/examples/rod2d/rod2d.h b/examples/rod2d/rod2d.h index 191ce6e6e55a..1fbfc342388d 100644 --- a/examples/rod2d/rod2d.h +++ b/examples/rod2d/rod2d.h @@ -129,14 +129,6 @@ Coulomb friction. The problem is well known to correspond to an *inconsistent rigid contact configuration*, where impulsive forces are necessary to resolve the problem. -@tparam T The vector element type, which must be a valid Eigen scalar. - -Instantiated templates for the following scalar types @p T are provided: - -- double - -They are already available to link against in the containing library. - Inputs: planar force (two-dimensional) and torque (scalar), which are arbitrary "external" forces (expressed in the world frame) applied at the center-of-mass of the rod. @@ -152,7 +144,10 @@ Outputs: Output Port 0 corresponds to the state vector; Output Port 1 frame. - [Stewart, 2000] D. Stewart, "Rigid-Body Dynamics with Friction and - Impact". SIAM Rev., 42(1), 3-39, 2000. */ + Impact". SIAM Rev., 42(1), 3-39, 2000. + +@tparam_double_only +*/ template class Rod2D : public systems::LeafSystem { public: diff --git a/examples/scene_graph/bouncing_ball_plant.h b/examples/scene_graph/bouncing_ball_plant.h index dcf42cc2d7c0..e6dd3cf8c1a8 100644 --- a/examples/scene_graph/bouncing_ball_plant.h +++ b/examples/scene_graph/bouncing_ball_plant.h @@ -18,10 +18,8 @@ namespace bouncing_ball { /** A model of a bouncing ball with Hunt-Crossley compliant contact model. The model supports 1D motion in a 3D world. - @tparam T The vector element type, which must be a valid Eigen scalar. - - Instantiated templates for the following kinds of T's are provided: - - double */ + @tparam_double_only +*/ template class BouncingBallPlant : public systems::LeafSystem { public: diff --git a/examples/scene_graph/solar_system.h b/examples/scene_graph/solar_system.h index 9833b55f19f2..22055109e561 100644 --- a/examples/scene_graph/solar_system.h +++ b/examples/scene_graph/solar_system.h @@ -86,11 +86,7 @@ X_OₑOₗ→├───┘ │ S │ X_OₘOₚ → ├── The frame of orbit's origin lies at the circle's center and it's z-axis is perpendicular to the plane of the circle. - @tparam T The vector element type, which must be a valid Eigen scalar. - - Instantiated templates for the following kinds of T's are provided: - - - double + @tparam_double_only */ template class SolarSystem : public systems::LeafSystem { diff --git a/examples/van_der_pol/van_der_pol.h b/examples/van_der_pol/van_der_pol.h index 94c87b4df5f6..328a0dffb9b7 100644 --- a/examples/van_der_pol/van_der_pol.h +++ b/examples/van_der_pol/van_der_pol.h @@ -20,13 +20,7 @@ namespace van_der_pol { /// the stationary distribution of the oscillator under process /// noise are coming soon). /// -/// @tparam T The vector element type, which must be a valid Eigen scalar. -/// -/// Instantiated templates for the following kinds of T's are provided: -/// -/// - double -/// - AutoDiffXd -/// - symbolic::Expression +/// @tparam_default_scalar template class VanDerPolOscillator final : public systems::LeafSystem { public: diff --git a/geometry/frame_kinematics_vector.h b/geometry/frame_kinematics_vector.h index 9830cba43e90..1dce0aca2815 100644 --- a/geometry/frame_kinematics_vector.h +++ b/geometry/frame_kinematics_vector.h @@ -159,16 +159,7 @@ class FrameKinematicsVector { /** Class for communicating _pose_ information to SceneGraph for registered frames. - @tparam T The scalar type. Must be a valid Eigen scalar. - - Instantiated templates for the following kinds of T's are provided: - - - double - - AutoDiffXd - - Expression - - They are already available to link against in the containing library. - No other values for T are currently supported. + @tparam_default_scalar */ template using FramePoseVector = FrameKinematicsVector>; diff --git a/geometry/geometry_state.h b/geometry/geometry_state.h index fb9ecdf03dd0..7b9f6599d2c2 100644 --- a/geometry/geometry_state.h +++ b/geometry/geometry_state.h @@ -60,15 +60,8 @@ using FrameIdSet = std::unordered_set; @note This is intended as an internal class only. - @tparam T The scalar type. Must be a valid Eigen scalar. - - Instantiated templates for the following kinds of T's are provided: - - - double - - AutoDiffXd - - They are already available to link against in the containing library. - No other values for T are currently supported. */ + @tparam_nonsymbolic_scalar +*/ template class GeometryState { public: diff --git a/geometry/proximity_engine.h b/geometry/proximity_engine.h index af2cf8882b0d..019cd26cae74 100644 --- a/geometry/proximity_engine.h +++ b/geometry/proximity_engine.h @@ -57,15 +57,7 @@ class GeometryStateCollisionFilterAttorney;

Geometry proximity properties

--> - @tparam T The scalar type. Must be a valid Eigen scalar. - - Instantiated templates for the following kinds of T's are provided: - - - double - - AutoDiffXd - - They are already available to link against in the containing library. - No other values for T are currently supported. + @tparam_nonsymbolic_scalar @internal Historically, this replaces the DrakeCollision::Model class. */ template diff --git a/geometry/query_object.h b/geometry/query_object.h index fb97903d0c5d..9285d3b0446b 100644 --- a/geometry/query_object.h +++ b/geometry/query_object.h @@ -60,15 +60,8 @@ class SceneGraph; restrictions. If a query has restricted scalar support, it is included in the query's documentation. - @tparam T The scalar type. Must be a valid Eigen scalar. - - Instantiated templates for the following kinds of T's are provided: - - - double - - AutoDiffXd - - They are already available to link against in the containing library. - No other values for T are currently supported. */ + @tparam_nonsymbolic_scalar +*/ template class QueryObject { public: diff --git a/geometry/query_results/contact_surface.h b/geometry/query_results/contact_surface.h index a0b0eba9507a..b73945c6d341 100644 --- a/geometry/query_results/contact_surface.h +++ b/geometry/query_results/contact_surface.h @@ -124,7 +124,7 @@ namespace geometry { We use the barycentric coordinates to evaluate the field values. - @tparam T the underlying scalar type. Must be a valid Eigen scalar. + @tparam_nonsymbolic_scalar */ template class ContactSurface { diff --git a/geometry/scene_graph.h b/geometry/scene_graph.h index fc9186c687b4..b6bcbaa9b7fe 100644 --- a/geometry/scene_graph.h +++ b/geometry/scene_graph.h @@ -212,16 +212,7 @@ class QueryObject; // - Finalizing API for topology changes at discrete events. @endcond - @tparam T The scalar type. Must be a valid Eigen scalar. - - Instantiated templates for the following kinds of T's are provided: - - - double - - AutoDiffXd - - They are already available to link against in the containing library. - No other values for T are currently supported. - + @tparam_nonsymbolic_scalar @ingroup systems */ template diff --git a/math/barycentric.h b/math/barycentric.h index 8faff5eade99..eea481f010e4 100644 --- a/math/barycentric.h +++ b/math/barycentric.h @@ -22,11 +22,7 @@ namespace math { /// Remi Munos and Andrew Moore, "Barycentric Interpolators for Continuous /// Space and Time Reinforcement Learning", NIPS 1998 /// -/// @tparam T The vector element type, which must be a valid Eigen scalar. -/// -/// Instantiated templates for the following kinds of T's are provided: -/// -/// - double +/// @tparam_double_only template class BarycentricMesh { // TODO(russt): This is also an instance of a "linear function approximator" diff --git a/math/rigid_transform.h b/math/rigid_transform.h index b94b832bd3f8..a80b4cb20854 100644 --- a/math/rigid_transform.h +++ b/math/rigid_transform.h @@ -63,7 +63,7 @@ namespace math { /// @authors Paul Mitiguy (2018) Original author. /// @authors Drake team (see https://drake.mit.edu/credits). /// -/// @tparam T The underlying scalar type. Must be a valid Eigen scalar. +/// @tparam_default_scalar template class RigidTransform { public: diff --git a/math/roll_pitch_yaw.h b/math/roll_pitch_yaw.h index dc1614e05318..44751d82a971 100644 --- a/math/roll_pitch_yaw.h +++ b/math/roll_pitch_yaw.h @@ -52,13 +52,7 @@ class RotationMatrix; /// @note This class does not store the frames associated with this rotation /// sequence. /// -/// @tparam T The underlying scalar type. Must be a valid Eigen scalar. -/// -/// Instantiated templates for the following kinds of T's are provided: -/// -/// - double -/// - AutoDiffXd -/// - symbolic::Expression +/// @tparam_default_scalar template class RollPitchYaw { public: diff --git a/math/rotation_matrix.h b/math/rotation_matrix.h index 6750c10cd63c..6e3d7dbb2b02 100644 --- a/math/rotation_matrix.h +++ b/math/rotation_matrix.h @@ -44,13 +44,7 @@ namespace math { /// @authors Paul Mitiguy (2018) Original author. /// @authors Drake team (see https://drake.mit.edu/credits). /// -/// @tparam T The underlying scalar type. Must be a valid Eigen scalar. -/// -/// Instantiated templates for the following kinds of T's are provided: -/// -/// - double -/// - AutoDiffXd -/// - symbolic::Expression +/// @tparam_default_scalar template class RotationMatrix { public: diff --git a/multibody/benchmarks/acrobot/BUILD.bazel b/multibody/benchmarks/acrobot/BUILD.bazel index 450d5a4d5f30..76e18c36dede 100644 --- a/multibody/benchmarks/acrobot/BUILD.bazel +++ b/multibody/benchmarks/acrobot/BUILD.bazel @@ -23,7 +23,7 @@ drake_cc_library( srcs = ["acrobot.cc"], hdrs = ["acrobot.h"], deps = [ - "//common:autodiff", + "//common:default_scalars", "//common:extract_double", "//math:geometric_transform", ], diff --git a/multibody/benchmarks/acrobot/acrobot.cc b/multibody/benchmarks/acrobot/acrobot.cc index a5668fb2879d..9fbc700fe9bf 100644 --- a/multibody/benchmarks/acrobot/acrobot.cc +++ b/multibody/benchmarks/acrobot/acrobot.cc @@ -1,6 +1,6 @@ #include "drake/multibody/benchmarks/acrobot/acrobot.h" -#include "drake/common/autodiff.h" +#include "drake/common/default_scalars.h" #include "drake/common/drake_assert.h" #include "drake/common/extract_double.h" @@ -249,9 +249,9 @@ T Acrobot::CalcPotentialEnergy(const T& theta1, const T& theta2) const { return (m1_ * p_WL1cm.y() + m2_ * p_WL2cm.y()) * g_; } -template class Acrobot; -template class Acrobot; - } // namespace benchmarks } // namespace multibody } // namespace drake + +DRAKE_DEFINE_CLASS_TEMPLATE_INSTANTIATIONS_ON_DEFAULT_NONSYMBOLIC_SCALARS( + class drake::multibody::benchmarks::Acrobot) diff --git a/multibody/benchmarks/acrobot/acrobot.h b/multibody/benchmarks/acrobot/acrobot.h index c6610518456d..f352233e6945 100644 --- a/multibody/benchmarks/acrobot/acrobot.h +++ b/multibody/benchmarks/acrobot/acrobot.h @@ -18,12 +18,7 @@ namespace benchmarks { /// parameterized by angle theta1 and Link 2 is connected to Link 1 by an /// "elbow" revolute joint parameterized by angle theta2. /// -/// @tparam T The vector element type, which must be a valid Eigen scalar. -/// -/// Instantiated templates for the following kinds of T's are provided: -/// -/// - double -/// - AutoDiffXd +/// @tparam_nonsymbolic_scalar template class Acrobot { public: diff --git a/multibody/benchmarks/mass_damper_spring/BUILD.bazel b/multibody/benchmarks/mass_damper_spring/BUILD.bazel index 440e2451a415..4f6e8698fcea 100644 --- a/multibody/benchmarks/mass_damper_spring/BUILD.bazel +++ b/multibody/benchmarks/mass_damper_spring/BUILD.bazel @@ -28,6 +28,7 @@ drake_cc_library( "mass_damper_spring_analytical_solution.h", ], deps = [ + "//common:default_scalars", "//common:essential", "//math:autodiff", ], diff --git a/multibody/benchmarks/mass_damper_spring/mass_damper_spring_analytical_solution.cc b/multibody/benchmarks/mass_damper_spring/mass_damper_spring_analytical_solution.cc index 0449e8c39907..7b6bf7d1a513 100644 --- a/multibody/benchmarks/mass_damper_spring/mass_damper_spring_analytical_solution.cc +++ b/multibody/benchmarks/mass_damper_spring/mass_damper_spring_analytical_solution.cc @@ -2,7 +2,7 @@ #include -#include "drake/common/autodiff.h" +#include "drake/common/default_scalars.h" #include "drake/common/drake_assert.h" namespace drake { @@ -104,10 +104,9 @@ Vector3 MassDamperSpringAnalyticalSolution::CalculateOutputImpl( return output; } -template class MassDamperSpringAnalyticalSolution; -template class MassDamperSpringAnalyticalSolution; - } // namespace benchmarks } // namespace multibody } // namespace drake +DRAKE_DEFINE_CLASS_TEMPLATE_INSTANTIATIONS_ON_DEFAULT_NONSYMBOLIC_SCALARS( + class drake::multibody::benchmarks::MassDamperSpringAnalyticalSolution) diff --git a/multibody/benchmarks/mass_damper_spring/mass_damper_spring_analytical_solution.h b/multibody/benchmarks/mass_damper_spring/mass_damper_spring_analytical_solution.h index 7e917d4ff36f..6916aa007829 100644 --- a/multibody/benchmarks/mass_damper_spring/mass_damper_spring_analytical_solution.h +++ b/multibody/benchmarks/mass_damper_spring/mass_damper_spring_analytical_solution.h @@ -19,15 +19,11 @@ namespace benchmarks { /// constant. The damper force on Q is -b*ẋ*Nx where b is a damper constant /// and ẋ is the time-derivative of x. /// -/// Instantiated templates for the following kinds of T's are provided and -/// available to link against in the containing library: -/// -/// - double -/// - AutoDiffXd -/// /// @note All units must be self-consistent (e.g., standard SI with MKS units). /// The solution provided herein is also applicable to a rotating system, /// e.g., having rigid-body inertia, rotational damper, rotational spring. +/// +/// @tparam_nonsymbolic_scalar template class MassDamperSpringAnalyticalSolution { public: diff --git a/multibody/constraint/constraint_solver.h b/multibody/constraint/constraint_solver.h index e349b739d618..b38e96c518ee 100644 --- a/multibody/constraint/constraint_solver.h +++ b/multibody/constraint/constraint_solver.h @@ -64,13 +64,7 @@ namespace constraint { /// Algorithm and its extension to deal with upper and lower /// bounds. Mathematical Programming Study, 7, 1978. /// -/// @tparam T The vector element type, which must be a valid Eigen scalar. -/// -/// Instantiated templates for the following scalar types @p T are provided: -/// -/// - double -/// -/// They are already available to link against in the containing library. +/// @tparam_double_only template class ConstraintSolver { public: diff --git a/multibody/math/spatial_acceleration.h b/multibody/math/spatial_acceleration.h index 709a5f477f3e..f187536ac115 100644 --- a/multibody/math/spatial_acceleration.h +++ b/multibody/math/spatial_acceleration.h @@ -47,7 +47,7 @@ namespace multibody { /// /// [Mitiguy 2016] Mitiguy, P., 2016. Advanced Dynamics & Motion Simulation. /// -/// @tparam T The underlying scalar type. Must be a valid Eigen scalar. +/// @tparam_default_scalar template class SpatialAcceleration : public SpatialVector { // We need the fully qualified class name below for the clang compiler to diff --git a/multibody/math/spatial_force.h b/multibody/math/spatial_force.h index 0180d2515e17..7278ea22287b 100644 --- a/multibody/math/spatial_force.h +++ b/multibody/math/spatial_force.h @@ -35,7 +35,7 @@ template class SpatialVelocity; /// For a more detailed introduction on spatial vectors and the monogram /// notation please refer to section @ref multibody_spatial_vectors. /// -/// @tparam T The underlying scalar type. Must be a valid Eigen scalar. +/// @tparam_default_scalar template class SpatialForce : public SpatialVector { // We need the fully qualified class name below for the clang compiler to diff --git a/multibody/math/spatial_momentum.h b/multibody/math/spatial_momentum.h index 9c085db8820c..b3fb66bb42a7 100644 --- a/multibody/math/spatial_momentum.h +++ b/multibody/math/spatial_momentum.h @@ -59,7 +59,7 @@ template class SpatialVelocity; /// - [Featherstone 2008] Featherstone, R., 2008. Rigid body dynamics /// algorithms. Springer. /// -/// @tparam T The underlying scalar type. Must be a valid Eigen scalar. +/// @tparam_default_scalar template class SpatialMomentum : public SpatialVector { // We need the fully qualified class name below for the clang compiler to diff --git a/multibody/math/spatial_vector.h b/multibody/math/spatial_vector.h index b60ca8afee1d..c15cdb2f41d4 100644 --- a/multibody/math/spatial_vector.h +++ b/multibody/math/spatial_vector.h @@ -21,7 +21,7 @@ namespace multibody { /// /// @tparam SV The type of the more specialized spatial vector class. /// It must be a template on the scalar type T. -/// @tparam T The underlying scalar type. Must be a valid Eigen scalar. +/// @tparam_default_scalar template