Skip to content

Commit

Permalink
Retire many more duplicated-word typos (RobotLocomotion#15533)
Browse files Browse the repository at this point in the history
* Retire many more duplicated-word typos

These were harvested with `pcregrep`, which has perl-compatible regular
expressions. This command gives some raw data:

    $ git ls-files | egrep -v '\.(obj|mtl|sdf|urdf)' \
      | xargs pcregrep -Min --color=auto '\b([a-z][a-z]+)[[:space:]]+\1\b'

Results were curated by hand and many were left untouched, since the regex
filter was insensitive to transitions between comments and text, various
documentation conventions, etc. In some cases, word wrap was updated. In other
cases, wording was adjusted to clarify things that might have looked like
typos.
  • Loading branch information
rpoyner-tri authored Aug 2, 2021
1 parent aa126f4 commit 5d30288
Show file tree
Hide file tree
Showing 44 changed files with 81 additions and 82 deletions.
2 changes: 1 addition & 1 deletion bindings/pydrake/systems/system_sliders.py
Original file line number Diff line number Diff line change
Expand Up @@ -141,7 +141,7 @@ def set_position(self, q):
# context, which is why we can get away with it. However, it would
# be better to add a discrete state vector that gets updated values
# from the sliders (and handles the slider update at that time) and
# update that in in a DiscreteUpdate.
# update that in a DiscreteUpdate.
def _update_window(self, context, event):
# GUI functionality is not automatically tested
# Must manually test this function to ensure updates run properly
Expand Down
2 changes: 1 addition & 1 deletion bindings/pydrake/systems/test/general_test.py
Original file line number Diff line number Diff line change
Expand Up @@ -67,7 +67,7 @@
ZeroOrderHold,
)

# TODO(eric.cousineau): The scope of this test file and and `custom_test.py`
# TODO(eric.cousineau): The scope of this test file and `custom_test.py`
# is poor. Move these tests into `framework_test` and `analysis_test`, and
# ensure that the tests reflect this, even if there is some coupling.

Expand Down
4 changes: 2 additions & 2 deletions common/symbolic_expression_cell.h
Original file line number Diff line number Diff line change
Expand Up @@ -296,8 +296,8 @@ class ExpressionAddFactory {
[[nodiscard]] Expression GetExpression() const;

private:
/* Adds constant to this factory.
* Adding constant constant into an add factory representing
/* Adds a constant @p constant to this factory.
* Adding constant into an add factory representing
*
* c0 + c1 * t1 + ... + cn * tn
*
Expand Down
2 changes: 1 addition & 1 deletion common/test/reset_after_move_test.cc
Original file line number Diff line number Diff line change
Expand Up @@ -157,7 +157,7 @@ GTEST_TEST(DefaultValueTest, Move) {
EXPECT_EQ(w, 3);
}

// Make sure that our wrapper is is sufficiently nothrow, e.g., so that it can
// Make sure that our wrapper is sufficiently nothrow, e.g., so that it can
// be moved (not copied) when an STL container is resized.
GTEST_TEST(DefaultValueTest, Nothrow) {
// Default constructor.
Expand Down
36 changes: 18 additions & 18 deletions common/test/symbolic_simplification_test.cc
Original file line number Diff line number Diff line change
Expand Up @@ -68,7 +68,7 @@ TEST_F(SymbolicUnificationTest, ConstantFailure) {
// Rule: 3 => 5.
const RewritingRule rule{3, 5};
const Rewriter rewriter = MakeRuleRewriter(rule);
// Fails to match 4 with with the above rule.
// Fails to match 4 with the above rule.
const Expression e{4};
EXPECT_PRED2(ExprEqual, rewriter(e), e /* no change */);
}
Expand Down Expand Up @@ -108,28 +108,28 @@ TEST_F(SymbolicUnificationTest, AdditionFailureNonZeroCoeff) {
const RewritingRule rule{2 + sin(x_) + cos(y_), 3 + 4 * x_ + 5 * y_};
const Rewriter rewriter = MakeRuleRewriter(rule);

// Fails to match the following with with the above rule (constant
// Fails to match the following with the above rule (constant
// mismatched).
// Example of Case 4 in UnificationVisitor::VisitAddition.
const Expression e1{5 + sin(a_) + cos(b_)};
EXPECT_PRED2(ExprEqual, rewriter(e1), e1 /* no change */);

// Fails to match the following with with the above rule (length).
// Fails to match the following with the above rule (length).
// Example of Case 4 in UnificationVisitor::VisitAddition.
const Expression e2{2 + sin(a_)};
EXPECT_PRED2(ExprEqual, rewriter(e2), e2 /* no change */);

// Fails to match the following with with the above rule (sin != cos).
// Fails to match the following with the above rule (sin != cos).
// Example of Case 4 in UnificationVisitor::VisitAddition.
const Expression e3{2 + cos(a_) + cos(b_)};
EXPECT_PRED2(ExprEqual, rewriter(e3), e3 /* no change */);

// Fails to match the following with with the above rule (cos != tan).
// Fails to match the following with the above rule (cos != tan).
// Example of Case 4 in UnificationVisitor::VisitAddition.
const Expression e4{2 + sin(a_) + tan(b_)};
EXPECT_PRED2(ExprEqual, rewriter(e4), e4 /* no change */);

// Fails to match the following with with the above rule (coefficient
// Fails to match the following with the above rule (coefficient
// mismatched).
// Example of Case 3 in UnificationVisitor::VisitAddition.
const Expression e5{sin(a_) + cos(b_)};
Expand All @@ -141,21 +141,21 @@ TEST_F(SymbolicUnificationTest, AdditionFailureZeroCoeff) {
const RewritingRule rule{sin(x_) + cos(y_) + sin(z_), x_ + y_ + z_};
const Rewriter rewriter = MakeRuleRewriter(rule);

// Fails to match the following with with the above rule (not addition).
// Fails to match the following with the above rule (not addition).
const Expression e1{cos(a_)};
EXPECT_PRED2(ExprEqual, rewriter(e1), e1 /* no change */);

// Fails to match the following with with the above rule (length).
// Fails to match the following with the above rule (length).
// Example of Case 2 in UnificationVisitor::VisitAddition.
const Expression e2{3 + cos(a_)};
EXPECT_PRED2(ExprEqual, rewriter(e2), e2 /* no change */);

// Fails to match the following with with the above rule (sin(x) vs 1).
// Fails to match the following with the above rule (sin(x) vs 1).
// Example of Case 2 in UnificationVisitor::VisitAddition.
const Expression e3{1 + log(a_) + abs(b_)};
EXPECT_PRED2(ExprEqual, rewriter(e3), e3 /* no change */);

// Fails to match the following with with the above rule (sin != tan).
// Fails to match the following with the above rule (sin != tan).
// Example of Case 1 in UnificationVisitor::VisitAddition.
const Expression e4{sin(b_) + cos(a_) + tan(c_)};
EXPECT_PRED2(ExprEqual, rewriter(e4), e4 /* no change */);
Expand Down Expand Up @@ -216,7 +216,7 @@ TEST_F(SymbolicUnificationTest, MultiplicationFailure1) {
4 * pow(x_, y_) * pow(2, z_)};
const Rewriter rewriter = MakeRuleRewriter(rule);

// Fails to match the following with with the above rule.
// Fails to match the following with the above rule.
// Example of Case 3 in UnificationVisitor::VisitMultiplication.
const Expression e{pow(cos(a_), c_) * cos(b_)};
EXPECT_PRED2(ExprEqual, rewriter(e), e /* no change */);
Expand All @@ -227,19 +227,19 @@ TEST_F(SymbolicUnificationTest, MultiplicationFailure2) {
// => x + y + z
const RewritingRule rule{sin(x_) * cos(y_) * tan(z_), x_ + y_ + z_};
const Rewriter rewriter = MakeRuleRewriter(rule);
// Fails to match the following with with the above rule.
// Fails to match the following with the above rule.
// Example of Case 1 in UnificationVisitor::VisitMultiplication.
const Expression e1{sin(a_) * acos(b_) * tan(c_)};
EXPECT_PRED2(ExprEqual, rewriter(e1), e1 /* no change */);
// Fails to match the following with with the above rule.
// Fails to match the following with the above rule.
// Example of Case 1 in UnificationVisitor::VisitMultiplication.
const Expression e2{a_ * sin(b_)};
EXPECT_PRED2(ExprEqual, rewriter(e2), e2 /* no change */);
// Fails to match the following with with the above rule.
// Fails to match the following with the above rule.
// Example of Case 2 in UnificationVisitor::VisitMultiplication.
const Expression e3{5 * cos(b_) * tan(z_)};
EXPECT_PRED2(ExprEqual, rewriter(e3), e3 /* no change */);
// Fails to match the following with with the above rule.
// Fails to match the following with the above rule.
const Expression e4{5};
EXPECT_PRED2(ExprEqual, rewriter(e4), e4 /* no change */);
}
Expand All @@ -248,11 +248,11 @@ TEST_F(SymbolicUnificationTest, MultiplicationFailure3) {
// Rule: 2 * x * y * z => x + y + z.
const RewritingRule rule{2 * x_ * y_ * z_, x_ + y_ + z_};
const Rewriter rewriter = MakeRuleRewriter(rule);
// Fails to match the following with with the above rule (coefficients).
// Fails to match the following with the above rule (coefficients).
// Example of Case 4 in UnificationVisitor::VisitMultiplication.
const Expression e1{3 * a_ * b_ * c_};
EXPECT_PRED2(ExprEqual, rewriter(e1), e1 /* no change */);
// Fails to match the following with with the above rule (length).
// Fails to match the following with the above rule (length).
// Example of Case 4 in UnificationVisitor::VisitMultiplication.
const Expression e2{3 * a_ * b_};
EXPECT_PRED2(ExprEqual, rewriter(e2), e2 /* no change */);
Expand All @@ -262,7 +262,7 @@ TEST_F(SymbolicUnificationTest, MultiplicationFailure4) {
// Rule: x * y * z => x + y + z.
const RewritingRule rule{x_ * y_ * z_, x_ + y_ + z_};
const Rewriter rewriter = MakeRuleRewriter(rule);
// Fails to match the following with with the above rule.
// Fails to match the following with the above rule.
// Example of Case 2 in UnificationVisitor::VisitMultiplication.
const Expression e{3 * a_};
EXPECT_PRED2(ExprEqual, rewriter(e), e /* no change */);
Expand Down
2 changes: 1 addition & 1 deletion common/test_utilities/expect_throws_message.h
Original file line number Diff line number Diff line change
Expand Up @@ -19,7 +19,7 @@ Usage example: @code
@endcode
The regular expression must match the entire error message. If there is
boilerplate you don't care to match at the beginning and end, surround with
with `.*` to ignore in single-line messages or `[\s\S]*` for multiline
`.*` to ignore in single-line messages or `[\s\S]*` for multiline
messages.
The "exception" argument is optional and defaults to "std::exception" when
Expand Down
2 changes: 1 addition & 1 deletion common/test_utilities/test/limit_malloc_test.cc
Original file line number Diff line number Diff line change
Expand Up @@ -159,7 +159,7 @@ TEST_P(LimitMallocDeathTest, MaxLimitTest) {
}

TEST_P(LimitMallocDeathTest, ObservationTest) {
// Though not actually a death test, this is is a convenient place to test
// Though not actually a death test, this is a convenient place to test
// that the getter returns a correct count. We must check within a unit test
// that is known to be disabled via the BUILD file for platforms without a
// working implementation.
Expand Down
2 changes: 1 addition & 1 deletion common/type_safe_index.h
Original file line number Diff line number Diff line change
Expand Up @@ -421,7 +421,7 @@ class TypeSafeIndex {
return index_ <= other.index_;
}

/// Allow less than or equals test test with unsigned integers.
/// Allow less than or equals test with unsigned integers.
template <typename U>
typename std::enable_if_t<
std::is_integral_v<U> && std::is_unsigned_v<U>, bool>
Expand Down
4 changes: 2 additions & 2 deletions common/yaml/yaml_read_archive.h
Original file line number Diff line number Diff line change
Expand Up @@ -114,8 +114,8 @@ class YamlReadArchive final {
}

/// (Advanced.) Sets the value pointed to by `nvp.value()` based on the YAML
/// file associated with this archive. Most users should should call Accept,
/// not Visit.
/// file associated with this archive. Most users should call Accept, not
/// Visit.
template <typename NameValuePair>
void Visit(const NameValuePair& nvp) {
this->Visit(nvp, VisitShouldMemorizeType::kYes);
Expand Down
2 changes: 1 addition & 1 deletion common/yaml/yaml_write_archive.h
Original file line number Diff line number Diff line change
Expand Up @@ -118,7 +118,7 @@ class YamlWriteArchive final {
void EraseMatchingMaps(const YamlWriteArchive& other);

/// (Advanced.) Copies the value pointed to by `nvp.value()` into the YAML
/// object. Most users should should call Accept, not Visit.
/// object. Most users should call Accept, not Visit.
template <typename NameValuePair>
void Visit(const NameValuePair& nvp) {
// Use int32_t for the final argument to prefer the specialized overload.
Expand Down
2 changes: 1 addition & 1 deletion doc/_pages/developers.md
Original file line number Diff line number Diff line change
Expand Up @@ -247,7 +247,7 @@ Please subscribe to the ``drake`` tag by following these instructions:
Please also monitor for [unanswered StackOverflow posts](https://stackoverflow.com/unanswered/tagged/drake?tab=noanswers)
once per day. If there are unanswered questions that you are unsure of the
answer, consider posting on the Slack ``#onramp`` channel to see if someone
can can look into the question.
can look into the question.

# Continuous Integration Notes

Expand Down
2 changes: 1 addition & 1 deletion geometry/drake_visualizer.cc
Original file line number Diff line number Diff line change
Expand Up @@ -221,7 +221,7 @@ DrakeVisualizer<T>::DrakeVisualizer(lcm::DrakeLcmInterface* lcm,
}
if (params_.role == Role::kUnassigned) {
throw std::runtime_error(
"DrakeVisualizer cannot be be used for geometries with the "
"DrakeVisualizer cannot be used for geometries with the "
"Role::kUnassigned value. Please choose proximity, perception, or "
"illustration");
}
Expand Down
2 changes: 1 addition & 1 deletion geometry/drake_visualizer.h
Original file line number Diff line number Diff line change
Expand Up @@ -76,7 +76,7 @@ struct DynamicFrameData {
specified.
The appearance of the geometry in the visualizer is typically defined by the
the geometry's properties for the visualized role.
geometry's properties for the visualized role.
- For the visualized role, if a geometry has the ("phong", "diffuse")
property described in the table below, that value is used.
Expand Down
10 changes: 5 additions & 5 deletions geometry/optimization/graph_of_convex_sets.h
Original file line number Diff line number Diff line change
Expand Up @@ -151,10 +151,10 @@ class GraphOfConvexSets {
std::pair<symbolic::Variable, solvers::Binding<solvers::Cost>> AddCost(
const symbolic::Expression& e);

/** Adds a cost to this edge. @p binding must must contain *only*
elements of xu() and xv() as variables. For technical
reasons relating to being able to "turn-off" the cost on inactive edges, all
costs are eventually implemented with a slack variable and a constraint:
/** Adds a cost to this edge. @p binding must contain *only* elements of
xu() and xv() as variables. For technical reasons relating to being able to
"turn-off" the cost on inactive edges, all costs are eventually implemented
with a slack variable and a constraint:
@verbatim
min g(xu, xv) ⇒ min ℓ, s.t. ℓ ≥ g(xu,xv)
@endverbatim
Expand All @@ -172,7 +172,7 @@ class GraphOfConvexSets {
solvers::Binding<solvers::Constraint> AddConstraint(
const symbolic::Formula& f);

/** Adds a constraint to this edge. @p binding must must contain *only*
/** Adds a constraint to this edge. @p binding must contain *only*
elements of xu() and xv() as variables.
@throws std::exception if binding.variables() is not a subset of xu() ∪
xv(). */
Expand Down
2 changes: 1 addition & 1 deletion geometry/proximity/test/mesh_plane_intersection_test.cc
Original file line number Diff line number Diff line change
Expand Up @@ -1052,7 +1052,7 @@ TEST_F(SliceTetWithPlaneTest, NoDoubleCounting) {
1. No intersection returns nullptr.
2. The resulting contact surface is a function of the tets provided; they
are all considered and only those that actually intersect contribute to
to the final output.
the final output.
3. Duplicates handled correctly; if the input mesh has no duplicates, the
result has none. Alternatively, if the input has duplicates, the output
does as well.
Expand Down
2 changes: 1 addition & 1 deletion geometry/query_object.h
Original file line number Diff line number Diff line change
Expand Up @@ -635,7 +635,7 @@ class QueryObject {
box if it lies within a certain tolerance from them.
@note For a box B, if a point p is inside the box, and it is equidistant to
to multiple nearest faces, the signed distance function φᵢ(p) at p will have
multiple nearest faces, the signed distance function φᵢ(p) at p will have
an undefined gradient vector. There is a nearest point candidate associated
with each nearest face. In this case, we arbitrarily pick the point Nᵢ
associated with one of the nearest faces. Please note that, due to the
Expand Down
2 changes: 1 addition & 1 deletion geometry/shape_specification.h
Original file line number Diff line number Diff line change
Expand Up @@ -107,7 +107,7 @@ class Sphere final : public Shape {

/** Constructs a sphere with the given `radius`.
@throws std::exception if `radius` is negative. Note that a zero radius is
is considered valid. */
considered valid. */
explicit Sphere(double radius);

double radius() const { return radius_; }
Expand Down
11 changes: 5 additions & 6 deletions lcm/drake_lcm.h
Original file line number Diff line number Diff line change
Expand Up @@ -36,12 +36,11 @@ class DrakeLcm : public DrakeLcmInterface {
* launching the receive thread.
*
* @param defer_initialization controls whether or not LCM's background
* receive thread will be launched immediately during the constructor
* (when false) or deferred until the first time it's needed (when true).
* This can be useful if the scheduling configuration for new threads varies
* between the construction time and and first use. For other constructor
* overloads, this setting defaults to `false` -- the thread is launched
* immediately.
* receive thread will be launched immediately during the constructor (when
* false) or deferred until the first time it's needed (when true). This can
* be useful if the scheduling configuration for new threads varies between
* the construction time and first use. For other constructor overloads,
* this setting defaults to `false` -- the thread is launched immediately.
*/
DrakeLcm(std::string lcm_url, bool defer_initialization);

Expand Down
2 changes: 1 addition & 1 deletion manipulation/kinova_jaco/jaco_command_receiver.cc
Original file line number Diff line number Diff line change
Expand Up @@ -54,7 +54,7 @@ void JacoCommandReceiver::set_initial_position(

// Returns (in "result") the command message input, or if a message has not
// been received yet returns the initial command (as optionally set by the
// user). The result will always have have num_joints_ positions and torques.
// user). The result will always have num_joints_ positions and torques.
void JacoCommandReceiver::CalcInput(
const Context<double>& context, lcmt_jaco_command* result) const {
if (!get_input_port().HasValue(context)) {
Expand Down
2 changes: 1 addition & 1 deletion math/autodiff.h
Original file line number Diff line number Diff line change
Expand Up @@ -193,7 +193,7 @@ struct ResizeDerivativesToMatchScalarImpl<Derived,
};
} // namespace internal

/** Resize derivatives vector of each element of a matrix to to match the size
/** Resize derivatives vector of each element of a matrix to match the size
* of the derivatives vector of a given scalar.
* \brief If the mat and scalar inputs are AutoDiffScalars, resize the
* derivatives vector of each element of the matrix mat to match
Expand Down
4 changes: 2 additions & 2 deletions math/roll_pitch_yaw.h
Original file line number Diff line number Diff line change
Expand Up @@ -221,8 +221,8 @@ class RollPitchYaw {
/// More specifically, returns true if `abs(cos_pitch_angle)` is less than an
/// internally-defined tolerance of gimbal-lock.
/// @param[in] cos_pitch_angle cosine of the pitch angle, i.e., `cos(p)`.
/// @note Pitch-angles close to gimbal-lock can can cause problems with
/// numerical precision and numerical integration.
/// @note Pitch-angles close to gimbal-lock can cause problems with numerical
/// precision and numerical integration.
static boolean<T> DoesCosPitchAngleViolateGimbalLockTolerance(
const T& cos_pitch_angle) {
using std::abs;
Expand Down
2 changes: 1 addition & 1 deletion math/rotation_matrix.h
Original file line number Diff line number Diff line change
Expand Up @@ -515,7 +515,7 @@ class RotationMatrix {
return matrix() * v_B;
}

/// Returns how close the matrix R is to to being a 3x3 orthonormal matrix by
/// Returns how close the matrix R is to being a 3x3 orthonormal matrix by
/// computing `‖R ⋅ Rᵀ - I‖∞` (i.e., the maximum absolute value of the
/// difference between the elements of R ⋅ Rᵀ and the 3x3 identity matrix).
/// @param[in] R matrix being checked for orthonormality.
Expand Down
2 changes: 1 addition & 1 deletion multibody/constraint/constraint_doxygen.h
Original file line number Diff line number Diff line change
Expand Up @@ -127,7 +127,7 @@ Algebraic Equation or Differential Complementarity Problem index
<pre>
d/dt gₚ(t; q) = ġₚ(t, q; v)
</pre>
vs. equations that **must** be posed at at the velocity-level
vs. equations that **must** be posed at the velocity-level
(i.e., nonholonomic constraints):<pre>
gᵥ(t, q; v).
</pre>
Expand Down
2 changes: 1 addition & 1 deletion multibody/constraint/constraint_problem_data.h
Original file line number Diff line number Diff line change
Expand Up @@ -413,7 +413,7 @@ struct ConstraintVelProblemData {
/// along the nr vectors that span the contact tangents at the nc
/// point contacts (these nc * nr vectors are denoted nnr for brevity). For
/// contact problems in two dimensions, nr will be one and nnr would equal nc.
/// For a friction pyramid at each point contact in in three dimensions, nr
/// For a friction pyramid at each point contact in three dimensions, nr
/// would be two and nnr would equation 2nc. While the definition of the
/// dimension of the Jacobian matrix above indicates that every one of the nc
/// contacts uses the same "nr", the code imposes no such requirement.
Expand Down
4 changes: 2 additions & 2 deletions multibody/plant/hydroelastic_traction_calculator.cc
Original file line number Diff line number Diff line change
Expand Up @@ -231,8 +231,8 @@ HydroelasticTractionCalculator<T>::CalcTractionAtQHelper(
// We now divide the numerator and denominator of Eq. (3) by vₛ (that is, we
// effectively multiply by 1) to write:
// fₜ = −μ 2/π atan(‖vₜ‖/vₛ)(vₜ/vₛ)/(‖vₜ‖/vₛ)fₙ (4)
// Finally we make make the substitution x = ‖vₜ‖/vₛ and group together the
// terms in x to get:
// Finally we make the substitution x = ‖vₜ‖/vₛ and group together the terms
// in x to get:
// fₜ =−μ 2/π vₜ/vₛ fₙ (atan(x)/x)
// We then make the observation that the function atan(x)/x is continuosly
// differentiable (that is the limits from both sides are exist and are
Expand Down
2 changes: 1 addition & 1 deletion multibody/plant/multibody_plant.h
Original file line number Diff line number Diff line change
Expand Up @@ -2814,7 +2814,7 @@ class MultibodyPlant : public internal::MultibodyTreeSystem<T> {
/// @param[in] context
/// The context containing the state of the model.
/// @param[in] v
/// A vector of of generalized velocities for this model.
/// A vector of generalized velocities for this model.
/// This method aborts if v is not of size num_velocities().
/// @param[out] qdot
/// A valid (non-null) pointer to a vector in `ℝⁿ` with n being the number
Expand Down
2 changes: 1 addition & 1 deletion multibody/tree/articulated_body_inertia.h
Original file line number Diff line number Diff line change
Expand Up @@ -285,7 +285,7 @@ class ArticulatedBodyInertia {
/// about point R, expressed in the same frame E `this`
/// articulated body inertia is expressed in.
/// @retval P_AR_E This same articulated body inertia for articulated body
/// A but now computed about about a new point R.
/// A but now computed about a new point R.
ArticulatedBodyInertia<T> Shift(const Vector3<T>& p_QR_E) const {
return ArticulatedBodyInertia<T>(*this).ShiftInPlace(p_QR_E);
}
Expand Down
Loading

0 comments on commit 5d30288

Please sign in to comment.