Skip to content

Commit

Permalink
Clean up Doxygen to prune junk from overview pages (RobotLocomotion#1…
Browse files Browse the repository at this point in the history
…2796)

Only parse headers, not cc files.
Exclude all unit tests.
Exclude all internal namespaces.
Exclude MG (autogenerated MotionGenesis sources).
Exclude top-level namespaces other than drake (Eigen, pybind11,
  false positives from using-statements, etc.)

Use correct bouncing_ball namespace in code.
Use correct free_body namespace in code.
Use correct pose_aggregator_internal namespace in code.
Use correct spelling for RenderLabel hashing.
Hide csdp namespace in code.
  • Loading branch information
jwnimmer-tri authored Mar 2, 2020
1 parent c587248 commit e36afc8
Showing 13 changed files with 44 additions and 17 deletions.
2 changes: 2 additions & 0 deletions bindings/pydrake/common/wrap_pybind.h
Original file line number Diff line number Diff line change
@@ -15,6 +15,7 @@
namespace drake {
namespace pydrake {

#ifndef DRAKE_DOXYGEN_CXX
namespace internal {

template <typename T, typename = void>
@@ -43,6 +44,7 @@ struct wrap_callback<std::function<Signature>>
: public wrap_callback<const std::function<Signature>&> {};

} // namespace internal
#endif // DRAKE_DOXYGEN_CXX

/// Ensures that any `std::function<>` arguments are wrapped such that any `T&`
/// (which can infer for `T = const U`) is wrapped as `U*` (and conversely
2 changes: 1 addition & 1 deletion common/eigen_autodiff_limits.h
Original file line number Diff line number Diff line change
@@ -13,7 +13,7 @@
namespace std {
template <typename T>
class numeric_limits<Eigen::AutoDiffScalar<T>>
: public numeric_limits<typename T::Scalar> {};
: public std::numeric_limits<typename T::Scalar> {};

} // namespace std

2 changes: 1 addition & 1 deletion common/symbolic_expression.h
Original file line number Diff line number Diff line change
@@ -797,7 +797,7 @@ struct equal_to<drake::symbolic::Expression> {
/* Provides std::numeric_limits<drake::symbolic::Expression>. */
template <>
struct numeric_limits<drake::symbolic::Expression>
: public numeric_limits<double> {};
: public std::numeric_limits<double> {};

/// Provides std::uniform_real_distribution, U(a, b), for symbolic expressions.
///
21 changes: 13 additions & 8 deletions doc/Doxyfile_CXX.in
Original file line number Diff line number Diff line change
@@ -122,21 +122,26 @@ WARN_LOGFILE = "@WARN_LOGFILE@"
#---------------------------------------------------------------------------
INPUT = "@INPUT_ROOT@"
INPUT_ENCODING = UTF-8
FILE_PATTERNS = *.c \
*.cc \
*.cxx \
*.cpp \
*.c++ \
*.h \
FILE_PATTERNS = *.h \
*.hh \
*.hxx \
*.hpp \
*.h++
RECURSIVE = YES
EXCLUDE =
EXCLUDE_SYMLINKS = NO
EXCLUDE_PATTERNS = "@INPUT_ROOT@/*/dev/*" "@INPUT_ROOT@/drake/attic/*"
EXCLUDE_SYMBOLS =
EXCLUDE_PATTERNS = "@INPUT_ROOT@/*/dev/*" \
"@INPUT_ROOT@/*/test/*" \
"@INPUT_ROOT@/*/MG/*" \
"@INPUT_ROOT@/drake/attic/*"
EXCLUDE_SYMBOLS = "*::internal" "pybind11"
# Sometimes using-statements confuse Doxygen and end up placing forward
# declarations into a namespace that lacks the intiial "drake::" prefix.
# Tell Doxygen to fully omit some top-level namespaces that will never
# have any real documentation inside them.
EXCLUDE_SYMBOLS += "internal" "lcm" "manipulation"
# Don't document our (obvious) Eigen overloads like "isinf", etc.
EXCLUDE_SYMBOLS += "Eigen"
EXAMPLE_PATH =
EXAMPLE_PATTERNS =
EXAMPLE_RECURSIVE = NO
2 changes: 1 addition & 1 deletion examples/bouncing_ball/bouncing_ball.cc
Original file line number Diff line number Diff line change
@@ -3,4 +3,4 @@
#include "drake/common/default_scalars.h"

DRAKE_DEFINE_CLASS_TEMPLATE_INSTANTIATIONS_ON_DEFAULT_SCALARS(
class ::drake::bouncing_ball::BouncingBall)
class ::drake::examples::bouncing_ball::BouncingBall)
2 changes: 2 additions & 0 deletions examples/bouncing_ball/bouncing_ball.h
Original file line number Diff line number Diff line change
@@ -8,6 +8,7 @@
#include "drake/systems/framework/witness_function.h"

namespace drake {
namespace examples {
namespace bouncing_ball {

/// Dynamical representation of the idealized hybrid dynamics
@@ -151,4 +152,5 @@ class BouncingBall final : public systems::LeafSystem<T> {
};

} // namespace bouncing_ball
} // namespace examples
} // namespace drake
2 changes: 2 additions & 0 deletions examples/bouncing_ball/test/bouncing_ball_test.cc
Original file line number Diff line number Diff line change
@@ -9,6 +9,7 @@
#include "drake/systems/framework/test_utilities/scalar_conversion.h"

namespace drake {
namespace examples {
namespace bouncing_ball {
namespace {

@@ -221,4 +222,5 @@ TEST_F(BouncingBallTest, Simulate) {

} // namespace
} // namespace bouncing_ball
} // namespace examples
} // namespace drake
10 changes: 9 additions & 1 deletion geometry/render/render_label.h
Original file line number Diff line number Diff line change
@@ -103,6 +103,14 @@ class RenderLabel {
return value_ < other.value_;
}

/** Implements the @ref hash_append concept. */
template <class HashAlgorithm>
friend void hash_append(
HashAlgorithm& hasher, const RenderLabel& item) noexcept {
using drake::hash_append;
hash_append(hasher, item.value_);
}

/** @name The reserved render labels
See class documentation on
@@ -171,6 +179,6 @@ namespace std {
@relates RenderLabel */
template <>
struct hash<drake::geometry::render::RenderLabel>
: public hash<drake::geometry::render::RenderLabel::ValueType> {};
: public drake::DefaultHash {};

} // namespace std
2 changes: 2 additions & 0 deletions multibody/benchmarks/free_body/free_body.cc
Original file line number Diff line number Diff line change
@@ -7,6 +7,7 @@
#include "drake/math/quaternion.h"

namespace drake {
namespace multibody {
namespace benchmarks {
namespace free_body {

@@ -131,4 +132,5 @@ FreeBody::CalculateExactTranslationalSolution(const double t) const {

} // namespace free_body
} // namespace benchmarks
} // namespace multibody
} // namespace drake
2 changes: 2 additions & 0 deletions multibody/benchmarks/free_body/free_body.h
Original file line number Diff line number Diff line change
@@ -10,6 +10,7 @@
#include "drake/math/rotation_matrix.h"

namespace drake {
namespace multibody {
namespace benchmarks {
namespace free_body {

@@ -244,4 +245,5 @@ class FreeBody {

} // namespace free_body
} // namespace benchmarks
} // namespace multibody
} // namespace drake
Original file line number Diff line number Diff line change
@@ -23,6 +23,7 @@
#include "drake/systems/analysis/simulator.h"

namespace drake {
namespace multibody {
namespace benchmarks {
namespace free_body {
namespace {
@@ -483,4 +484,5 @@ GTEST_TEST(uniformSolidCylinderTorqueFree, testKaneExactSolution) {
} // namespace
} // namespace free_body
} // namespace benchmarks
} // namespace multibody
} // namespace drake
2 changes: 2 additions & 0 deletions solvers/csdp_solver_internal.h
Original file line number Diff line number Diff line change
@@ -6,12 +6,14 @@
#include <unordered_map>
#include <vector>

#ifndef DRAKE_DOXYGEN_CXX
namespace csdp {
extern "C" {
// TODO(Jeremy.Nimmer): include this header as <csdp/declarations.h>
#include <declarations.h>
} // extern C
} // namespace csdp
#endif // DOXYGEN_CXX

#include <Eigen/Core>
#include <Eigen/Sparse>
10 changes: 5 additions & 5 deletions systems/rendering/pose_aggregator.h
Original file line number Diff line number Diff line change
@@ -13,7 +13,7 @@ namespace drake {
namespace systems {
namespace rendering {

namespace pose_aggregator_internal { struct InputRecord; }
namespace internal { struct PoseAggregatorInputRecord; }

/// A container with references to the input port for the pose input, and a
/// reference to the input port for the velocity input.
@@ -126,7 +126,7 @@ class PoseAggregator : public LeafSystem<T> {
// This is the method used by the allocator for the output port.
PoseBundle<T> MakePoseBundle() const;

using InputRecord = pose_aggregator_internal::InputRecord;
using InputRecord = internal::PoseAggregatorInputRecord;

// Returns an InputRecord for a generic single pose input.
static InputRecord MakeSinglePoseInputRecord(const std::string& name,
@@ -151,12 +151,12 @@ class PoseAggregator : public LeafSystem<T> {
};

/** @cond */
namespace pose_aggregator_internal {
namespace internal {

// A private data structure of PoseAggregator. It is not nested within
// PoseAggregator because it does not (and should not) depend on the type
// parameter @p T.
struct InputRecord {
struct PoseAggregatorInputRecord {
enum PoseInputType {
kSinglePose = 1,
kSingleVelocity = 2,
@@ -171,7 +171,7 @@ struct InputRecord {
int model_instance_id{-1};
};

} // namespace pose_aggregator_internal
} // namespace internal
/** @endcond */

} // namespace rendering

0 comments on commit e36afc8

Please sign in to comment.