Skip to content

Commit

Permalink
Clean up exception specification in doxygen
Browse files Browse the repository at this point in the history
  • Loading branch information
Jamie Snape committed Oct 9, 2018
1 parent f1de40b commit 7591bdc
Show file tree
Hide file tree
Showing 77 changed files with 357 additions and 323 deletions.
4 changes: 2 additions & 2 deletions attic/multibody/collision/model.h
Original file line number Diff line number Diff line change
Expand Up @@ -39,8 +39,8 @@ class Model {
@return A pointer to the added element.
@throws A runtime_error if there was a problem (e.g., duplicate element id,
error configuring collision model, etc.) **/
@throws std::runtime_error if there was a problem (e.g., duplicate element
id, error configuring collision model, etc.) **/
Element* AddElement(std::unique_ptr<Element> element);

/** Removes a collision element from this model.
Expand Down
16 changes: 8 additions & 8 deletions attic/multibody/global_inverse_kinematics.h
Original file line number Diff line number Diff line change
Expand Up @@ -64,19 +64,19 @@ class GlobalInverseKinematics : public solvers::MathematicalProgram {
* with the specified index. This is the orientation of body i's frame
* measured and expressed in the world frame.
* @param body_index The index of the queried body. Notice that body 0 is
* the world, and thus not a decision variable. Throws a runtime_error if
* the index is smaller than 1, or no smaller than the total number of bodies
* in the robot.
* the world, and thus not a decision variable.
* @throws std::runtime_error if the index is smaller than 1, or no smaller
* than the total number of bodies in the robot.
*/
const solvers::MatrixDecisionVariable<3, 3>& body_rotation_matrix(
int body_index) const;

/** Getter for the decision variables on the position p_WBo of the body B's
* origin measured and expressed in the world frame.
* @param body_index The index of the queried body. Notice that body 0 is
* the world, and thus not a decision variable. Throws a runtime_error if
* the index is smaller than 1, or greater than or equal to the total number
* of bodies in the robot.
* the world, and thus not a decision variable.
* @throws std::runtime_error if the index is smaller than 1, or greater than
* or equal to the total number of bodies in the robot.
*/
const solvers::VectorDecisionVariable<3>& body_position(int body_index) const;

Expand Down Expand Up @@ -205,13 +205,13 @@ class GlobalInverseKinematics : public solvers::MathematicalProgram {
* 1. body_position_cost.rows() == robot->get_num_bodies(), where `robot`
* is the input argument in the constructor of the class.
* 2. body_position_cost(i) is non-negative.
* @throw a runtime error if the precondition is not satisfied.
* @throws std::runtime_error if the precondition is not satisfied.
* @param body_orientation_cost The cost for each body's orientation error.
* @pre
* 1. body_orientation_cost.rows() == robot->get_num_bodies() , where
* `robot` is the input argument in the constructor of the class.
* 2. body_position_cost(i) is non-negative.
* @throw a runtime_error if the precondition is not satisfied.
* @throws std::runtime_error if the precondition is not satisfied.
*/
void AddPostureCost(
const Eigen::Ref<const Eigen::VectorXd>& q_desired,
Expand Down
4 changes: 2 additions & 2 deletions attic/multibody/parsers/model_instance_id_table.h
Original file line number Diff line number Diff line change
Expand Up @@ -27,8 +27,8 @@ namespace parsers {
typedef std::map<std::string, int> ModelInstanceIdTable;

/**
* Adds the model instances in @p source_table to @p dest_table. Throws a
* `std::runtime_error` if there is a collision in the model names.
* Adds the model instances in @p source_table to @p dest_table.
* @throws std::runtime_error if there is a collision in the model names.
*/
void AddModelInstancesToTable(
const drake::parsers::ModelInstanceIdTable& source_table,
Expand Down
2 changes: 1 addition & 1 deletion attic/multibody/parsers/parser_common.h
Original file line number Diff line number Diff line change
Expand Up @@ -53,7 +53,7 @@ struct FloatingJointConstants {
*
* @return The number of floating joint added to this rigid body tree.
*
* @throws A std::runtime_error if the floating_base_type is unrecognized or
* @throws std::runtime_error if the floating_base_type is unrecognized or
* zero floating joints were added to the model.
*/
int AddFloatingJoint(
Expand Down
6 changes: 3 additions & 3 deletions attic/multibody/rigid_body_plant/compliant_material.h
Original file line number Diff line number Diff line change
Expand Up @@ -112,9 +112,9 @@ class CompliantMaterial {
/** Reset the dissipation value to report the default value. */
void set_dissipation_to_default() { dissipation_ = nullopt; }

/** Sets *both* coefficients of friction to the same value. Throws an
exception if the value is negative. Returns a reference to `*this` so that
multiple invocations of `set` can be chained together. */
/** Sets *both* coefficients of friction to the same value.
@throws std::exception if the value is negative. Returns a reference to
`*this` so that multiple invocations of `set` can be chained together. */
CompliantMaterial& set_friction(double value);

/** Sets the two coefficients of friction. The `dynamic_friction` values must
Expand Down
12 changes: 7 additions & 5 deletions attic/multibody/rigid_body_plant/rigid_body_plant.h
Original file line number Diff line number Diff line change
Expand Up @@ -341,10 +341,12 @@ class RigidBodyPlant : public LeafSystem<T> {
}

/// Returns the output port containing the state of a
/// particular model with instance ID equal to `model_instance_id`. Throws a
/// std::runtime_error if `model_instance_id` does not exist. This method can
/// only be called when this class is instantiated with constructor parameter
/// `export_model_instance_centric_ports` equal to `true`.
/// particular model with instance ID equal to `model_instance_id`.
/// @throws std::runtime_error if `model_instance_id` does not exist.
///
/// This method can only be called when this class is instantiated with
/// constructor parameter `export_model_instance_centric_ports` equal to
/// `true`.
const OutputPort<T>& model_instance_state_output_port(
int model_instance_id) const;

Expand Down Expand Up @@ -401,7 +403,7 @@ class RigidBodyPlant : public LeafSystem<T> {
std::unique_ptr<const RigidBodyTree<double>> tree,
double timestep = 0.0);

// Evaluates the actuator command input ports and throws a runtime_error
// Evaluates the actuator command input ports and throws a std::runtime_error
// exception if at least one of the ports is not connected.
VectorX<T> EvaluateActuatorInputs(const Context<T>& context) const;

Expand Down
10 changes: 6 additions & 4 deletions automotive/automotive_simulator.h
Original file line number Diff line number Diff line change
Expand Up @@ -265,17 +265,19 @@ class AutomotiveSimulator {
///
const maliput::api::Lane* FindLane(const std::string& name) const;

/// Returns the System whose name matches @p name. Throws an exception if no
/// such system has been added, or multiple such systems have been added.
/// Returns the System whose name matches @p name.
/// @throws std::exception if no such system has been added, or multiple
/// such systems have been added.
//
/// This is the builder variant of the method. It can only be used prior to
/// Start() being called.
///
/// @pre Start() has NOT been called.
systems::System<T>& GetBuilderSystemByName(std::string name);

/// Returns the System whose name matches @p name. Throws an exception if no
/// such system has been added, or multiple such systems have been added.
/// Returns the System whose name matches @p name.
/// @throws std::exception if no such system has been added, or multiple such
/// systems have been added.
///
/// This is the diagram variant of the method, which can only be used after
/// Start() is called.
Expand Down
2 changes: 1 addition & 1 deletion automotive/curve2.h
Original file line number Diff line number Diff line change
Expand Up @@ -37,7 +37,7 @@ class Curve2 {
typedef Eigen::Matrix<T, 2, 1, Eigen::DontAlign> Point2T;

/// Constructor that traces through the given @p waypoints in order.
/// Throws an error if @p waypoints.size() == 1.
/// @throws std::exception if @p waypoints.size() == 1.
explicit Curve2(const std::vector<Point2>& waypoints)
: waypoints_(waypoints), path_length_(GetLength(waypoints_)) {
// TODO(jwnimmer-tri) We should reject duplicate adjacent
Expand Down
13 changes: 7 additions & 6 deletions automotive/maliput/api/basic_id_index.h
Original file line number Diff line number Diff line change
Expand Up @@ -25,33 +25,34 @@ class BasicIdIndex : public RoadGeometry::IdIndex {

/// Adds @p lane to the index.
///
/// @throws if @p lane's id() already exists in the index.
/// @throws std::exception if @p lane's id() already exists in the index.
/// @pre @p lane is not nullptr.
void AddLane(const Lane* lane);

/// Adds @p segment to the index.
///
/// @throws if @p segment's id() already exists in the index.
/// @throws std::exception if @p segment's id() already exists in the index.
/// @pre @p segment is not nullptr.
void AddSegment(const Segment* segment);

/// Adds @p junction to the index.
///
/// @throws if @p junction's id() already exists in the index.
/// @throws std::exception if @p junction's id() already exists in the index.
/// @pre @p junction is not nullptr.
void AddJunction(const Junction* junction);

/// Adds @p branch_point to the index.
///
/// @throws if @p branch_point's id() already exists in the index.
/// @throws std::exception if @p branch_point's id() already exists in the
/// index.
/// @pre @p branch_point is not nullptr.
void AddBranchPoint(const BranchPoint* branch_point);

/// Walks the object graph rooted at @p road_geometry and adds all
/// components (Lane, Segment, Junction, BranchPoint) to the index.
///
/// @throws if the graph of @p road_geometry contains any duplicate id's,
/// or if any of its id's already exist in the index.
/// @throws std::exception if the graph of @p road_geometry contains any
/// duplicate id's, or if any of its id's already exist in the index.
/// @pre @p road_geometry is not nullptr.
void WalkAndAddAll(const RoadGeometry* road_geometry);

Expand Down
4 changes: 2 additions & 2 deletions automotive/maliput/api/rules/right_of_way_rule.h
Original file line number Diff line number Diff line change
Expand Up @@ -118,7 +118,7 @@ class RightOfWayRule final {
/// @param controlled_zone LaneSRoute to which this rule applies
/// @param type the static semantics of this rule
///
/// Throws a std::exception if `states` is empty or if `states` contains
/// @throws std::exception if `states` is empty or if `states` contains
/// duplicate State::Id's.
RightOfWayRule(const Id& id,
const LaneSRoute& zone,
Expand Down Expand Up @@ -155,7 +155,7 @@ class RightOfWayRule final {
///
/// This is a convenience function for returning a static rule's single state.
///
/// Throws a std::exception if `is_static()` is false.
/// @throws std::exception if `is_static()` is false.
const State& static_state() const {
DRAKE_THROW_UNLESS(is_static());
return states_.begin()->second;
Expand Down
4 changes: 2 additions & 2 deletions automotive/maliput/api/rules/road_rulebook.h
Original file line number Diff line number Diff line change
Expand Up @@ -52,14 +52,14 @@ class RoadRulebook {

/// Returns the RightOfWayRule with the specified `id`.
///
/// Throws std::out_of_range if `id` is unknown.
/// @throws std::out_of_range if `id` is unknown.
RightOfWayRule GetRule(const RightOfWayRule::Id& id) const {
return DoGetRule(id);
}

/// Returns the SpeedLimitRule with the specified `id`.
///
/// Throws std::out_of_range if `id` is unknown.
/// @throws std::out_of_range if `id` is unknown.
SpeedLimitRule GetRule(const SpeedLimitRule::Id& id) const {
return DoGetRule(id);
}
Expand Down
2 changes: 1 addition & 1 deletion automotive/maliput/api/rules/speed_limit_rule.h
Original file line number Diff line number Diff line change
Expand Up @@ -41,7 +41,7 @@ class SpeedLimitRule {
/// @param max maximum speed
///
/// `min` and `max` must be non-negative, and `min` must be less than
/// or equal to `max`, otherwise a runtime_error is thrown.
/// or equal to `max`, otherwise a std::runtime_error is thrown.
SpeedLimitRule(const Id& id, const LaneSRange& zone, Severity severity,
double min, double max)
: id_(id), zone_(zone), severity_(severity), min_(min), max_(max) {
Expand Down
7 changes: 4 additions & 3 deletions automotive/maliput/multilane/arc_road_curve.h
Original file line number Diff line number Diff line change
Expand Up @@ -39,9 +39,10 @@ class ArcRoadCurve : public RoadCurve {
/// @param computation_policy Policy to guide all computations. If geared
/// towards speed, computations will make use of analytical expressions even
/// if not actually correct for the curve as specified.
/// @throw std::runtime_error if @p radius is not a positive number.
/// @throw std::runtime_error if @p linear_tolerance is not a positive number.
/// @throw std::runtime_error if @p scale_length is not a positive number.
/// @throws std::runtime_error if @p radius is not a positive number.
/// @throws std::runtime_error if @p linear_tolerance is not a positive
/// number.
/// @throws std::runtime_error if @p scale_length is not a positive number.
explicit ArcRoadCurve(
const Vector2<double>& center, double radius,
double theta0, double d_theta,
Expand Down
5 changes: 3 additions & 2 deletions automotive/maliput/multilane/line_road_curve.h
Original file line number Diff line number Diff line change
Expand Up @@ -38,8 +38,9 @@ class LineRoadCurve : public RoadCurve {
/// @param computation_policy Policy to guide all computations. If geared
/// towards speed, computations will make use of analytical expressions even
/// if not actually correct for the curve as specified.
/// @throw std::runtime_error if @p linear_tolerance is not a positive number.
/// @throw std::runtime_error if @p scale_length is not a positive number.
/// @throws std::runtime_error if @p linear_tolerance is not a positive
/// number.
/// @throws std::runtime_error if @p scale_length is not a positive number.
explicit LineRoadCurve(
const Vector2<double>& xy0, const Vector2<double>& dxy,
const CubicPolynomial& elevation,
Expand Down
4 changes: 2 additions & 2 deletions automotive/maliput/multilane/road_curve.cc
Original file line number Diff line number Diff line change
Expand Up @@ -29,7 +29,7 @@ struct ArcLengthDerivativeFunction {
// @return The arc length derivative value at the specified point.
// @pre The given parameter vector @p k is bi-dimensional (holding r and h
// coordinates only).
// @throw std::logic_error if preconditions are not met.
// @throws std::logic_error if preconditions are not met.
double operator()(const double& p, const VectorX<double>& k) const {
if (k.size() != 2) {
throw std::logic_error("Arc length derivative expects only r and"
Expand Down Expand Up @@ -62,7 +62,7 @@ struct InverseArcLengthODEFunction {
// @return The inverse arc length derivative value at the specified point.
// @pre The given parameter vector @p k is bi-dimensional (holding r and h
// coordinates only).
// @throw std::logic_error if preconditions are not met.
// @throws std::logic_error if preconditions are not met.
double operator()(const double& s, const double& p,
const VectorX<double>& k) {
unused(s);
Expand Down
8 changes: 4 additions & 4 deletions automotive/maliput/multilane/road_curve.h
Original file line number Diff line number Diff line change
Expand Up @@ -132,7 +132,7 @@ class RoadCurve {
/// defined for all `s` values between 0 and the total path length of
/// the parallel curve (and throwing for any given value outside this
/// interval).
/// @throw std::runtime_error When `r` makes the radius of curvature be a non
/// @throws std::runtime_error When `r` makes the radius of curvature be a non
/// positive number.
std::function<double(double)> OptimizeCalcPFromS(double r) const;

Expand All @@ -143,7 +143,7 @@ class RoadCurve {
/// curve to longitudinal position s at the specified parallel curve,
/// defined for all p between 0 and 1 (and throwing for any given
/// value outside this interval).
/// @throw std::runtime_error When `r` makes the radius of curvature be a non
/// @throws std::runtime_error When `r` makes the radius of curvature be a non
/// positive number.
std::function<double(double)> OptimizeCalcSFromP(double r) const;

Expand Down Expand Up @@ -275,7 +275,7 @@ class RoadCurve {
/// and accuracy. Actual behavior may vary across implementations.
/// @pre The given @p scale_length is a positive number.
/// @pre The given @p linear_tolerance is a positive number.
/// @throw std::runtime_error if any of the preconditions is not met.
/// @throws std::runtime_error if any of the preconditions is not met.
///
/// @p elevation and @p superelevation are cubic-polynomial functions which
/// define the elevation and superelevation as a function of position along
Expand Down Expand Up @@ -323,7 +323,7 @@ class RoadCurve {
// curve using numerical methods.
// @return The path length integral of the curve composed with the elevation
// polynomial.
// @throw std::runtime_error When `r` makes the radius of curvature be a non
// @throws std::runtime_error When `r` makes the radius of curvature be a non
// positive number.
double CalcSFromP(double p, double r) const;

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -27,7 +27,7 @@ namespace test {
// the given lower integration bound @p p_0.
// @pre Given lower integration bound @p p_0 is greater than or equal to 0.
// @pre Given @p k_order for the linear approximation is a non-negative number.
// @throw std::runtime_error if preconditions are not met.
// @throws std::runtime_error if preconditions are not met.
double BruteForcePathLengthIntegral(const RoadCurve& road_curve,
double p_0, double p_1, double r,
double h, int k_order,
Expand Down Expand Up @@ -68,7 +68,7 @@ double BruteForcePathLengthIntegral(const RoadCurve& road_curve,
// @pre Given tolerance is a positive real number.
// @pre If given, the order suggested by @p k_order_hint is a non-negative
// number.
// @throw std::runtime_error if preconditions are not met.
// @throws std::runtime_error if preconditions are not met.
double AdaptiveBruteForcePathLengthIntegral(
const RoadCurve& rc, double p_0, double p_1,
double r, double h, double tolerance,
Expand Down
12 changes: 6 additions & 6 deletions automotive/maliput/rndf/builder.h
Original file line number Diff line number Diff line change
Expand Up @@ -159,8 +159,8 @@ class Builder {
/// @param segment_id The RNDF segment ID.
/// @param connections A collection of Connections representing each RNDF lane
/// in the segment.
/// @throw std::runtime_error When @p connections is a nullptr.
/// @throw std::runtime_error When @p connections is an empty collection.
/// @throws std::runtime_error When @p connections is a nullptr.
/// @throws std::runtime_error When @p connections is an empty collection.
void CreateSegmentConnections(int segment_id,
std::vector<Connection>* connections);

Expand All @@ -176,8 +176,8 @@ class Builder {
/// fake inner lanes' lane bounds).
/// @param perimeter_waypoints A collection of DirectedWaypoint objects
/// describing the zone's perimeter.
/// @throw std::runtime_error When @p perimeter_waypoints is a nullptr.
/// @throw std::runtime_error When @p perimeter_waypoints is an empty
/// @throws std::runtime_error When @p perimeter_waypoints is a nullptr.
/// @throws std::runtime_error When @p perimeter_waypoints is an empty
/// collection.
void CreateConnectionsForZones(
double width, std::vector<DirectedWaypoint>* perimeter_waypoints);
Expand All @@ -188,7 +188,7 @@ class Builder {
/// @param width The connection's width.
/// @param exit_id The start waypoint ID of the connection.
/// @param entry_id The end waypoint ID of the connection.
/// @throw std::runtime_error When neither @p exit_id nor @p entry_id are
/// @throws std::runtime_error When neither @p exit_id nor @p entry_id are
/// found.
void CreateConnection(double width, const ignition::rndf::UniqueId& exit_id,
const ignition::rndf::UniqueId& entry_id);
Expand All @@ -200,7 +200,7 @@ class Builder {
/// a Lane is added to the Segment. BranchPoints are updated as needed.
/// @param id ID of the api::RoadGeometry to be built.
/// @return The built api::RoadGeometry.
/// @throw std::runtime_error When the built RoadGeometry does not satisfy
/// @throws std::runtime_error When the built RoadGeometry does not satisfy
/// Maliput roads' constraints (see api::RoadGeometry::CheckInvariants()).
std::unique_ptr<const api::RoadGeometry> Build(const api::RoadGeometryId& id);

Expand Down
4 changes: 2 additions & 2 deletions automotive/maliput/rndf/loader.h
Original file line number Diff line number Diff line change
Expand Up @@ -50,8 +50,8 @@ struct RoadCharacteristics {
/// @param road_characteristics The common geometrical aspects to comply with
/// when building the api::RoadGeometry.
/// @return The built api::RoadGeometry.
/// @throw std::runtime_error When the given file is not a valid RNDF.
/// @throw std::runtime_error When the given RNDF doesn't have at least
/// @throws std::runtime_error When the given file is not a valid RNDF.
/// @throws std::runtime_error When the given RNDF doesn't have at least
/// a single lane segment with one or more waypoints. RNDFs containing
/// only zones are not supported.
std::unique_ptr<const api::RoadGeometry> LoadFile(
Expand Down
6 changes: 3 additions & 3 deletions automotive/maliput/rndf/spline_helpers.h
Original file line number Diff line number Diff line change
Expand Up @@ -51,9 +51,9 @@ class InverseFunctionInterpolator {
/// function image, which is inside the codomain of the direct function.
/// @return interpolated @p derivative_order derivative
/// @f$ x^{(derivative_order)}(y) @f$ .
/// @throws when @p derivative_order is a negative integer.
/// @throws when @p y is larger than the maximum range of the function's
/// codomain as described in the constructor's documentation.
/// @throws std::exception when @p derivative_order is a negative integer.
/// @throws std::exception when @p y is larger than the maximum range of the
/// function's codomain as described in the constructor's documentation.
/// @throws std::runtime_error When @p y is smaller than the minimum range of
/// the function's codomain as described in the constructor's documentation.
double InterpolateMthDerivative(int derivative_order, double y);
Expand Down
Loading

0 comments on commit 7591bdc

Please sign in to comment.