Skip to content

Commit

Permalink
Make various lists in Doxygen both Markdown and reST friendly
Browse files Browse the repository at this point in the history
  • Loading branch information
Jamie Snape committed Oct 10, 2018
1 parent 9db8c3e commit ea73c12
Show file tree
Hide file tree
Showing 136 changed files with 524 additions and 322 deletions.
1 change: 1 addition & 0 deletions attic/multibody/rigid_body_frame.h
Original file line number Diff line number Diff line change
Expand Up @@ -21,6 +21,7 @@ class XMLElement;
/// @tparam T The type being integrated. Must be a valid Eigen scalar.
///
/// Instantiated templates for the following kinds of T's are provided:
///
/// - double
/// - AutoDiffXd
///
Expand Down
1 change: 1 addition & 0 deletions attic/multibody/rigid_body_loop.h
Original file line number Diff line number Diff line change
Expand Up @@ -19,6 +19,7 @@
/// @tparam T The type being integrated. Must be a valid Eigen scalar.
///
/// Instantiated templates for the following kinds of T's are provided:
///
/// - double
/// - AutoDiffXd
///
Expand Down
1 change: 1 addition & 0 deletions attic/multibody/rigid_body_plant/compliant_contact_model.h
Original file line number Diff line number Diff line change
Expand Up @@ -24,6 +24,7 @@ struct CompliantContactModelParameters {
/// described in detail in @ref drake_contacts.
///
/// Instantiated templates for the following kinds of T's are provided:
///
/// - double
/// - AutoDiffXd
///
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -11,6 +11,7 @@ namespace multibody {
/// visual geometries attached to the world body.
///
/// Instantiated templates for the following ScalarTypes are provided:
///
/// - double
///
/// They are already available to link against in the containing library.
Expand Down
1 change: 1 addition & 0 deletions attic/multibody/rigid_body_plant/kinematics_results.h
Original file line number Diff line number Diff line change
Expand Up @@ -17,6 +17,7 @@ class RigidBodyPlant;
/// @tparam T The scalar type. Must be a valid Eigen scalar.
///
/// Instantiated templates for the following ScalarTypes are provided:
///
/// - double
/// - AutoDiffXd
///
Expand Down
2 changes: 2 additions & 0 deletions attic/multibody/rigid_body_plant/rigid_body_plant.h
Original file line number Diff line number Diff line change
Expand Up @@ -117,7 +117,9 @@ namespace systems {
/// where `N(q)` is a transformation matrix only dependent on the positions.
///
/// @tparam T The scalar type. Must be a valid Eigen scalar.
///
/// Instantiated templates for the following kinds of T's are provided:
///
/// - double
/// - AutoDiffXd
///
Expand Down
1 change: 1 addition & 0 deletions automotive/automotive_simulator.h
Original file line number Diff line number Diff line change
Expand Up @@ -37,6 +37,7 @@ namespace automotive {
/// @tparam T must be a valid Eigen ScalarType.
///
/// Instantiated templates for the following ScalarTypes are provided:
///
/// - double
///
/// They are already available to link against in the containing library.
Expand Down
30 changes: 17 additions & 13 deletions automotive/bicycle_car.h
Original file line number Diff line number Diff line change
Expand Up @@ -22,30 +22,34 @@ namespace automotive {
/// dynamics.
///
/// The states of the model are:
/// - yaw angle Ψ [rad]
/// - yaw rate Ψ_dot [rad/s]
/// - slip angle at the center of mass β [rad]
/// - velocity magnitude (vector magnitude at the slip angle) vel [m/s]
/// - x-position of the center of mass sx [m]
/// - y-position of the center of mass sy [m]
///
/// - yaw angle Ψ [rad]
/// - yaw rate Ψ_dot [rad/s]
/// - slip angle at the center of mass β [rad]
/// - velocity magnitude (vector magnitude at the slip angle) vel [m/s]
/// - x-position of the center of mass sx [m]
/// - y-position of the center of mass sy [m]
///
/// @note "slip angle" (β) is the angle made between the body and the velocity
/// vector. Thus, the velocity vector can be resolved into the body-relative
/// componenets `vx_body = cos(β)` and `vy_body = sin(β)`. `β = 0` means the
/// velocity vector is pointing along the bicycle's longitudinal axis.
///
/// Inputs:
/// - Angle of the front wheel of the bicycle δ [rad]
/// (InputPort getter: get_steering_input_port())
/// - Force acting on the rigid body F_in [N]
/// (InputPort getter: get_force_input_port())
///
/// - Angle of the front wheel of the bicycle δ [rad]
/// (InputPort getter: get_steering_input_port())
/// - Force acting on the rigid body F_in [N]
/// (InputPort getter: get_force_input_port())
///
/// Output:
/// - A BicycleCarState containing the 6-dimensional state vector of the
/// bicycle.
/// (OutputPort getter: get_state_output_port())
///
/// - A BicycleCarState containing the 6-dimensional state vector of the
/// bicycle.
/// (OutputPort getter: get_state_output_port())
///
/// Instantiated templates for the following kinds of T's are provided:
///
/// - double
/// - drake::AutoDiffXd
/// - drake::symbolic::Expression
Expand Down
1 change: 1 addition & 0 deletions automotive/calc_ongoing_road_position.h
Original file line number Diff line number Diff line change
Expand Up @@ -16,6 +16,7 @@ namespace automotive {
/// road.
///
/// Instantiated templates for the following scalar types `T` are provided:
///
/// - double
/// - drake::AutoDiffXd
///
Expand Down
1 change: 1 addition & 0 deletions automotive/calc_smooth_acceleration.h
Original file line number Diff line number Diff line change
Expand Up @@ -12,6 +12,7 @@ namespace automotive {
/// constant except for @p current_velocity.
///
/// Instantiated templates for the following ScalarTypes are provided:
///
/// - double
/// - drake::AutoDiffXd
/// - drake::symbolic::Expression
Expand Down
2 changes: 2 additions & 0 deletions automotive/curve2.h
Original file line number Diff line number Diff line change
Expand Up @@ -17,6 +17,7 @@ namespace automotive {
/// list of waypoints, it traces a path between them.
///
/// Instantiated templates for the following kinds of T's are provided:
///
/// - double
/// - drake::AutoDiffXd
///
Expand Down Expand Up @@ -62,6 +63,7 @@ class Curve2 {
/// respect to @p path_distance.
///
/// The @p path_distance is clipped to the ends of the curve:
///
/// - A negative @p path_distance is interpreted as a @p path_distance
/// of zero.
/// - A @p path_distance that exceeds the @p path_length() of the curve
Expand Down
1 change: 1 addition & 0 deletions automotive/driving_command_mux.h
Original file line number Diff line number Diff line change
Expand Up @@ -20,6 +20,7 @@ namespace automotive {
/// @tparam T The vector element type, which must be a valid Eigen scalar.
///
/// Instantiated templates for the following `T` values are provided:
///
/// - double
/// - AutoDiffXd
/// - symbolic::Expression
Expand Down
24 changes: 14 additions & 10 deletions automotive/dynamic_bicycle_car.h
Original file line number Diff line number Diff line change
Expand Up @@ -27,26 +27,30 @@ namespace automotive {
/// with Lz being gravity aligned (gravity acts in the negative Lz direction).
///
/// The states of the model are:
/// - Lx measure of the location of Cp from Lo `p_LoCp_x` [m]
/// - Ly measure of the location of Cp from Lo `p_LoCp_y` [m]
/// - Yaw angle from Lx to Cx with positive Lz sense `yaw_LC` [rad]
/// - Cx measure of Cp's velocity in L `v_LCp_x` [m/s]
/// - Cy measure of Cp's velocity in L `v_LCp_y` [m/s]
/// - C's angular velocity in frame L `yawDt_LC` [rad/s]
///
/// - Lx measure of the location of Cp from Lo `p_LoCp_x` [m]
/// - Ly measure of the location of Cp from Lo `p_LoCp_y` [m]
/// - Yaw angle from Lx to Cx with positive Lz sense `yaw_LC` [rad]
/// - Cx measure of Cp's velocity in L `v_LCp_x` [m/s]
/// - Cy measure of Cp's velocity in L `v_LCp_y` [m/s]
/// - C's angular velocity in frame L `yawDt_LC` [rad/s]
///
/// Inputs to this system:
/// - Steer angle from Cx to Dx with positive Cz sense `steer_CD` [rad]
/// - The Cx measure of the Longitudinal force on body C at Cp `f_Cp_x` [N]
///
/// - Steer angle from Cx to Dx with positive Cz sense `steer_CD` [rad]
/// - The Cx measure of the Longitudinal force on body C at Cp `f_Cp_x` [N]
///
/// Outputs of this system:
/// - A DynamicBicycleCarState containing the 6-dimensional state vector of
/// the vehicle.
///
/// - A DynamicBicycleCarState containing the 6-dimensional state vector of
/// the vehicle.
///
/// Note that the vehicle's angular velocity in L `yawDt_LC` is sometimes
/// referred to as the yaw rate `r`, and the tire angle is sometimes referred
/// to as δ.
///
/// Instantiated templates for the following kinds of T's are provided:
///
/// - double
/// - drake::AutoDiffXd
/// - drake::symbolic::Expression
Expand Down
2 changes: 2 additions & 0 deletions automotive/idm_controller.h
Original file line number Diff line number Diff line change
Expand Up @@ -25,6 +25,7 @@ namespace automotive {
/// passed as a command to the vehicle.
///
/// Instantiated templates for the following kinds of T's are provided:
///
/// - double
///
/// They are already available to link against in the containing library.
Expand All @@ -44,6 +45,7 @@ namespace automotive {
///
///
/// Instantiated templates for the following kinds of T's are provided:
///
/// - double
/// - AutoDiffXd
///
Expand Down
16 changes: 9 additions & 7 deletions automotive/idm_planner.h
Original file line number Diff line number Diff line change
Expand Up @@ -15,17 +15,19 @@ namespace automotive {
///
/// The IDM equation produces accelerations that realize smooth transitions
/// between the following three modes:
/// - Free-road behavior: when the distance to the leading car is large, the
/// IDM regulates acceleration to match the desired speed `v_0`.
/// - Fast-closing-speed behavior: when the target distance decreases, an
/// interaction term compensates for the velocity difference, while keeping
/// deceleration comfortable according to parameter `b`.
/// - Small-distance behavior: within small net distances to the lead vehicle,
/// comfort is ignored in favor of increasing this distance to `s_0`.
///
/// - Free-road behavior: when the distance to the leading car is large, the
/// IDM regulates acceleration to match the desired speed `v_0`.
/// - Fast-closing-speed behavior: when the target distance decreases, an
/// interaction term compensates for the velocity difference, while keeping
/// deceleration comfortable according to parameter `b`.
/// - Small-distance behavior: within small net distances to the lead vehicle,
/// comfort is ignored in favor of increasing this distance to `s_0`.
///
/// See the corresponding .cc file for details about the IDM equation.
///
/// Instantiated templates for the following kinds of T's are provided:
///
/// - double
/// - drake::AutoDiffXd
/// - drake::symbolic::Expression
Expand Down
2 changes: 2 additions & 0 deletions automotive/maliput/api/lane.h
Original file line number Diff line number Diff line change
Expand Up @@ -114,6 +114,7 @@ class Lane {
/// same quantity as the i-th derviative of another variable.
///
/// Instantiated templates for the following kinds of T's are provided:
///
/// - double
/// - drake::AutoDiffXd
/// - drake::symbolic::Expression
Expand Down Expand Up @@ -160,6 +161,7 @@ class Lane {
/// geo_pos's partial derivatives.
///
/// Instantiated templates for the following kinds of T's are provided:
///
/// - double
/// - drake::AutoDiffXd
/// - drake::symbolic::Expression
Expand Down
2 changes: 2 additions & 0 deletions automotive/maliput/api/lane_data.h
Original file line number Diff line number Diff line change
Expand Up @@ -126,6 +126,7 @@ std::ostream& operator<<(std::ostream& out, const Rotation& rotation);
/// frame, consisting of three components x, y, and z.
///
/// Instantiated templates for the following kinds of T's are provided:
///
/// - double
/// - drake::AutoDiffXd
/// - drake::symbolic::Expression
Expand Down Expand Up @@ -208,6 +209,7 @@ auto operator!=(const GeoPositionT<T>& lhs, const GeoPositionT<T>& rhs) {
/// * h is height above the road surface.
///
/// Instantiated templates for the following kinds of T's are provided:
///
/// - double
/// - drake::AutoDiffXd
/// - drake::symbolic::Expression
Expand Down
27 changes: 14 additions & 13 deletions automotive/maliput/multilane/builder.h
Original file line number Diff line number Diff line change
Expand Up @@ -502,14 +502,15 @@ class BuilderFactoryBase {
/// network.
///
/// multilane is a simple road-network implementation:
/// - multiple lanes per segment;
/// - constant lane width, lane_bounds, and elevation_bounds, same for all
/// lanes;
/// - only linear and constant-curvature-arc primitives in XY-plane;
/// - cubic polynomials (parameterized on XY-arc-length) for elevation
/// and superelevation;
/// - superelevation (bank of road) rotates around the reference line (r = 0)
/// of the path.
///
/// - multiple lanes per segment;
/// - constant lane width, lane_bounds, and elevation_bounds, same for all
/// lanes;
/// - only linear and constant-curvature-arc primitives in XY-plane;
/// - cubic polynomials (parameterized on XY-arc-length) for elevation
/// and superelevation;
/// - superelevation (bank of road) rotates around the reference line (r = 0)
/// of the path.
///
/// The Builder class simplifies the assembly of multilane road network
/// components into a valid RoadGeometry. In the Builder model, an Endpoint
Expand All @@ -526,11 +527,11 @@ class BuilderFactoryBase {
/// Specific suffixes are used to name Maliput entities. The following list
/// explains the naming convention:
///
/// - Junctions: "j:" + Group::id(), or "j" + Connection::id() for an
/// ungrouped Connection.
/// - Segments: "s:" + Connection::id()
/// - Lanes: "l:" + Connection::id() + "_" + lane_index
/// - BranchPoints: "bp:" + branch_point_index
/// - Junctions: "j:" + Group::id(), or "j" + Connection::id() for an
/// ungrouped Connection.
/// - Segments: "s:" + Connection::id()
/// - Lanes: "l:" + Connection::id() + "_" + lane_index
/// - BranchPoints: "bp:" + branch_point_index
///
/// @note 'lane_index' is the index in the Segment, and 'branch_point_index' is
/// is the index in the RoadGeometry.
Expand Down
30 changes: 16 additions & 14 deletions automotive/maliput/multilane/connection.h
Original file line number Diff line number Diff line change
Expand Up @@ -20,10 +20,11 @@ namespace multilane {
/// the world frame.
///
/// The three components are:
/// - x: x position
/// - y: y position
/// - heading: counter-clockwise around z=cross(x,y). It is the heading of
/// reference path (radians, zero == x-direction).
///
/// - x: x position
/// - y: y position
/// - heading: counter-clockwise around z=cross(x,y). It is the heading of
/// reference path (radians, zero == x-direction).
class EndpointXy {
public:
DRAKE_DEFAULT_COPY_AND_MOVE_AND_ASSIGN(EndpointXy)
Expand Down Expand Up @@ -61,16 +62,17 @@ std::ostream& operator<<(std::ostream& out, const EndpointXy& endpoint_xy);
/// the world frame.
///
/// The four components are:
/// - z: elevation
/// - z_dot: grade (rate of change of elevation with respect to
/// arc length of the reference path)
/// - theta: superelevation (rotation of road surface around r = 0 centerline;
/// when theta > 0, elevation at r > 0 is above elevation at r < 0)
/// - theta_dot: rate of change of superelevation with respect to arc length
/// of the reference path. It is optional because it may be
/// unknown when building a RoadGeometry and the Builder may need
/// to adjust it to force the same orientation for all r at a
/// certain s coordinate of the Segment surface.
///
/// - z: elevation
/// - z_dot: grade (rate of change of elevation with respect to
/// arc length of the reference path)
/// - theta: superelevation (rotation of road surface around r = 0 centerline;
/// when theta > 0, elevation at r > 0 is above elevation at r < 0)
/// - theta_dot: rate of change of superelevation with respect to arc length
/// of the reference path. It is optional because it may be
/// unknown when building a RoadGeometry and the Builder may need
/// to adjust it to force the same orientation for all r at a
/// certain s coordinate of the Segment surface.
class EndpointZ {
public:
DRAKE_DEFAULT_COPY_AND_MOVE_AND_ASSIGN(EndpointZ)
Expand Down
Loading

0 comments on commit ea73c12

Please sign in to comment.