Skip to content

Commit

Permalink
doc: Use doxygen macro for tparam scalartype boilerplate (RobotLocomo…
Browse files Browse the repository at this point in the history
  • Loading branch information
jwnimmer-tri authored Mar 9, 2020
1 parent 448f987 commit 8592c35
Show file tree
Hide file tree
Showing 166 changed files with 249 additions and 970 deletions.
67 changes: 33 additions & 34 deletions common/default_scalars.h
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand All @@ -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
/// `<T>` 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 <typename T>
/// class MySystem final : public LeafSystem<T> {
/// class MySystem final : public drake::systems::LeafSystem<T> {
/// ...
/// };
/// } // namespace sample
Expand All @@ -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<double>; \
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<double>; \
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<double>; \
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) \
Expand Down
2 changes: 2 additions & 0 deletions common/trajectories/exponential_plus_piecewise_polynomial.h
Original file line number Diff line number Diff line change
Expand Up @@ -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 <typename T>
class ExponentialPlusPiecewisePolynomial final
Expand Down
6 changes: 1 addition & 5 deletions common/trajectories/piecewise_polynomial.h
Original file line number Diff line number Diff line change
Expand Up @@ -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 <typename T>
class PiecewisePolynomial final : public PiecewiseTrajectory<T> {
Expand Down
3 changes: 1 addition & 2 deletions common/trajectories/piecewise_quaternion.h
Original file line number Diff line number Diff line change
Expand Up @@ -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<typename T>
class PiecewiseQuaternionSlerp final : public PiecewiseTrajectory<T> {
Expand Down
6 changes: 1 addition & 5 deletions common/trajectories/piecewise_trajectory.h
Original file line number Diff line number Diff line change
Expand Up @@ -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 <typename T>
class PiecewiseTrajectory : public Trajectory<T> {
public:
Expand Down
3 changes: 3 additions & 0 deletions doc/Doxyfile_CXX.in
Original file line number Diff line number Diff line change
Expand Up @@ -43,6 +43,9 @@ ALIASES = "default=@n @a Default: " \
"system{3}=<table align=center cellpadding=0 cellspacing=0><tr align=center><td><table cellspacing=0 cellpadding=0>\2</table></td><td align=center style=\"border:solid;padding-left:20px;padding-right:20px\" bgcolor=#F0F0F0>\1</td><td><table cellspacing=0 cellpadding=0>\3</table></td></tr></table>" \
"input_port{1}=<tr><td align=right style=\"padding:5px 0px 5px 0px\">\1 &rarr;</td></tr>" \
"output_port{1}=<tr><td align=left style=\"padding:5px 0px 5px 0px\">&rarr; \1</td></tr>" \
"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 =
Expand Down
9 changes: 1 addition & 8 deletions examples/acrobot/acrobot_plant.h
Original file line number Diff line number Diff line change
Expand Up @@ -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 <typename T>
class AcrobotPlant : public systems::LeafSystem<T> {
Expand Down
10 changes: 2 additions & 8 deletions examples/bead_on_a_wire/bead_on_a_wire.h
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand All @@ -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 <typename T>
class BeadOnAWire : public systems::LeafSystem<T> {
public:
Expand Down
12 changes: 2 additions & 10 deletions examples/bouncing_ball/bouncing_ball.h
Original file line number Diff line number Diff line change
Expand Up @@ -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 <typename T>
class BouncingBall final : public systems::LeafSystem<T> {
public:
Expand Down
8 changes: 1 addition & 7 deletions examples/compass_gait/compass_gait.h
Original file line number Diff line number Diff line change
Expand Up @@ -40,13 +40,7 @@ namespace compass_gait {
/// Discrete State: stance toe position.<br/>
/// Abstract State: left support indicator.<br/>
///
/// @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 <typename T>
class CompassGait final : public systems::LeafSystem<T> {
public:
Expand Down
7 changes: 1 addition & 6 deletions examples/manipulation_station/manipulation_station.h
Original file line number Diff line number Diff line change
Expand Up @@ -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 <typename T>
class ManipulationStation : public systems::Diagram<T> {
Expand Down
9 changes: 1 addition & 8 deletions examples/particles/particle.h
Original file line number Diff line number Diff line change
Expand Up @@ -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 <typename T>
class Particle final : public systems::LeafSystem<T> {
public:
Expand Down
8 changes: 1 addition & 7 deletions examples/pendulum/pendulum_plant.h
Original file line number Diff line number Diff line change
Expand Up @@ -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 <typename T>
class PendulumPlant final : public systems::LeafSystem<T> {
public:
Expand Down
2 changes: 1 addition & 1 deletion examples/planar_gripper/planar_gripper_common.h
Original file line number Diff line number Diff line change
Expand Up @@ -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 <typename T>
void WeldGripperFrames(MultibodyPlant<T>* plant);
Expand Down
7 changes: 1 addition & 6 deletions examples/rimless_wheel/rimless_wheel.h
Original file line number Diff line number Diff line change
Expand Up @@ -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 <typename T>
class RimlessWheel final : public systems::LeafSystem<T> {
public:
Expand Down
13 changes: 4 additions & 9 deletions examples/rod2d/rod2d.h
Original file line number Diff line number Diff line change
Expand Up @@ -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.
Expand All @@ -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 <typename T>
class Rod2D : public systems::LeafSystem<T> {
public:
Expand Down
6 changes: 2 additions & 4 deletions examples/scene_graph/bouncing_ball_plant.h
Original file line number Diff line number Diff line change
Expand Up @@ -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 <typename T>
class BouncingBallPlant : public systems::LeafSystem<T> {
public:
Expand Down
6 changes: 1 addition & 5 deletions examples/scene_graph/solar_system.h
Original file line number Diff line number Diff line change
Expand Up @@ -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 <typename T>
class SolarSystem : public systems::LeafSystem<T> {
Expand Down
8 changes: 1 addition & 7 deletions examples/van_der_pol/van_der_pol.h
Original file line number Diff line number Diff line change
Expand Up @@ -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 <typename T>
class VanDerPolOscillator final : public systems::LeafSystem<T> {
public:
Expand Down
Loading

0 comments on commit 8592c35

Please sign in to comment.