Skip to content

Commit

Permalink
[trajectories] Use per-scalar translation units (RobotLocomotion#21605)
Browse files Browse the repository at this point in the history
This reduces long-pole build times for large, scalar-dependent files.
  • Loading branch information
jwnimmer-tri authored Sep 18, 2024
1 parent cb3be21 commit 0d5cbd9
Show file tree
Hide file tree
Showing 4 changed files with 143 additions and 1 deletion.
89 changes: 88 additions & 1 deletion common/default_scalars.h
Original file line number Diff line number Diff line change
Expand Up @@ -73,21 +73,64 @@
/// See also @ref system_scalar_conversion.
/// @{

// In support of the macros below, we define a struct template that provides
// the per-phase typedef `scalar_phase_t<DRAKE_ONCE_PER_SCALAR_PHASE>::type`.
// If more scalar types are added, also fix drake/tools/skylark/drake_cc.bzl
// to reflect the new count of default scalars.
namespace drake {
namespace internal {
template <int>
struct scalar_phase_t {};
template <>
struct scalar_phase_t<0> {
using type = double;
};
template <>
struct scalar_phase_t<1> {
using type = ::drake::AutoDiffXd;
};
template <>
struct scalar_phase_t<2> {
using type = ::drake::symbolic::Expression;
};
} // namespace internal
} // namespace drake

#ifndef DRAKE_ONCE_PER_SCALAR_PHASE
/// 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) \
template SomeType<double>; \
template SomeType<::drake::AutoDiffXd>; \
template SomeType<::drake::symbolic::Expression>;
#else
#define DRAKE_DEFINE_CLASS_TEMPLATE_INSTANTIATIONS_ON_DEFAULT_SCALARS( \
SomeType) \
template SomeType< \
::drake::internal::scalar_phase_t<DRAKE_ONCE_PER_SCALAR_PHASE>::type>;
#endif

#ifndef DRAKE_ONCE_PER_SCALAR_PHASE
/// 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>;
#elif DRAKE_ONCE_PER_SCALAR_PHASE <= 1 /* Skip phase 2 (Expression). */
#define \
DRAKE_DEFINE_CLASS_TEMPLATE_INSTANTIATIONS_ON_DEFAULT_NONSYMBOLIC_SCALARS( \
SomeType) \
template SomeType< \
::drake::internal::scalar_phase_t<DRAKE_ONCE_PER_SCALAR_PHASE>::type>;
#else
#define \
DRAKE_DEFINE_CLASS_TEMPLATE_INSTANTIATIONS_ON_DEFAULT_NONSYMBOLIC_SCALARS( \
SomeType) \
static_assert(true);
#endif

/// Declares that template instantiations exist for Drake's default scalars.
/// This should only be used in .h files, never in .cc files.
Expand Down Expand Up @@ -184,6 +227,7 @@ extern template SomeType<::drake::AutoDiffXd>;
// can't use a namespace because we need to allow for easy friendship in case a
// member function does not have public access.

#ifndef DRAKE_ONCE_PER_SCALAR_PHASE
/// Defines template instantiations for Drake's default scalars.
/// This should only be used in .cc files, never in .h files.
#define DRAKE_DEFINE_FUNCTION_TEMPLATE_INSTANTIATIONS_ON_DEFAULT_SCALARS( \
Expand All @@ -200,12 +244,31 @@ template<typename... Ts> \
constexpr auto Make_Function_Pointers_Pack1() { \
return std::tuple_cat(Make_Function_Pointers_Pack2<Ts, Ts...>()...); \
} \
static constexpr auto Function_Femplates __attribute__((used)) = \
static constexpr auto Function_Templates __attribute__((used)) = \
Make_Function_Pointers_Pack1< \
double, \
::drake::AutoDiffXd, \
::drake::symbolic::Expression>();
#else
#define DRAKE_DEFINE_FUNCTION_TEMPLATE_INSTANTIATIONS_ON_DEFAULT_SCALARS( \
FunctionPointersTuple) \
template<typename T, typename U> \
constexpr auto Make_Function_Pointers() { \
return std::make_tuple FunctionPointersTuple ; \
} \
template<typename T, typename... Us> \
constexpr auto Make_Function_Pointers_Pack2() { \
return std::tuple_cat(Make_Function_Pointers<T, Us>()...); \
} \
static constexpr auto Function_Templates __attribute__((used)) = \
Make_Function_Pointers_Pack2< \
::drake::internal::scalar_phase_t<DRAKE_ONCE_PER_SCALAR_PHASE>::type, \
double, \
::drake::AutoDiffXd, \
::drake::symbolic::Expression>(); /* NOLINT(whitespace/operators) */
#endif

#ifndef DRAKE_ONCE_PER_SCALAR_PHASE
/// Defines template instantiations for Drake's default nonsymbolic scalars.
/// This should only be used in .cc files, never in .h files.
#define \
Expand All @@ -228,5 +291,29 @@ static constexpr auto Function_Templates_Nonsym __attribute__((used)) = \
Make_Function_Pointers_Nonsym_Pack1< \
double, \
::drake::AutoDiffXd>();
#elif DRAKE_ONCE_PER_SCALAR_PHASE <= 1 /* Skip phase 2 (Expression). */
#define \
DRAKE_DEFINE_FUNCTION_TEMPLATE_INSTANTIATIONS_ON_DEFAULT_NONSYMBOLIC_SCALARS( \
FunctionPointersTuple) \
template<typename T, typename U> \
constexpr auto Make_Function_Pointers_Nonsym() { \
return std::make_tuple FunctionPointersTuple ; \
} \
template<typename T, typename... Us> \
constexpr auto Make_Function_Pointers_Nonsym_Pack2() { \
return std::tuple_cat(Make_Function_Pointers_Nonsym<T, Us>()...); \
} \
/* NOLINTNEXTLINE(readability/fn_size) */ \
static constexpr auto Function_Templates_Nonsym __attribute__((used)) = \
Make_Function_Pointers_Nonsym_Pack2< \
::drake::internal::scalar_phase_t<DRAKE_ONCE_PER_SCALAR_PHASE>::type, \
double, \
::drake::AutoDiffXd>();
#else
#define \
DRAKE_DEFINE_FUNCTION_TEMPLATE_INSTANTIATIONS_ON_DEFAULT_NONSYMBOLIC_SCALARS( \
FunctionPointersTuple) \
static_assert(true);
#endif

/// @}
1 change: 1 addition & 0 deletions common/trajectories/BUILD.bazel
Original file line number Diff line number Diff line change
Expand Up @@ -119,6 +119,7 @@ drake_cc_library(
"exponential_plus_piecewise_polynomial.h",
"piecewise_polynomial.h",
],
compile_once_per_scalar = True,
deps = [
":piecewise_trajectory",
"//common:default_scalars",
Expand Down
4 changes: 4 additions & 0 deletions common/trajectories/exponential_plus_piecewise_polynomial.cc
Original file line number Diff line number Diff line change
@@ -1,5 +1,7 @@
#include "drake/common/trajectories/exponential_plus_piecewise_polynomial.h"

#if DRAKE_ONCE_PER_SCALAR_PHASE == 0 // We are @tparam_double_only.

#include <memory>

#include <unsupported/Eigen/MatrixFunctions>
Expand Down Expand Up @@ -75,3 +77,5 @@ template class ExponentialPlusPiecewisePolynomial<double>;

} // namespace trajectories
} // namespace drake

#endif
50 changes: 50 additions & 0 deletions tools/skylark/drake_cc.bzl
Original file line number Diff line number Diff line change
Expand Up @@ -392,6 +392,7 @@ def _raw_drake_cc_library(
tags = None,
testonly = None,
visibility = None,
compile_once_per_scalar = False,
declare_installed_headers = None,
install_hdrs_exclude = None,
deprecation = None):
Expand Down Expand Up @@ -423,6 +424,44 @@ def _raw_drake_cc_library(
visibility = ["//visibility:public"],
)

# When compiling using once_per_scalar, we need to replace the srcs with
# small stub files that set the scalar type first. (Note that this block of
# code will crash if srcs uses a `select`; that usage is not supported.)
textual_hdrs = None
if compile_once_per_scalar:
new_srcs = []
for src in srcs:
for i in range(3):
stub_name = "{}_{}".format(i, src)
generate_file(
name = stub_name,
content = (
("#define DRAKE_ONCE_PER_SCALAR_PHASE {}\n" +
"#include \"{}/{}\"\n").format(
i,
native.package_name(),
src,
)
),
visibility = ["//visibility:private"],
)
new_srcs.append(stub_name)

# Don't lint the stubs; instead, use a dummy rule to do the linting.
# We use hdrs for everything so that the linter can see it but nothing
# will actually be compiled.
cc_library(
name = "{}_for_linting".format(name),
hdrs = (hdrs or []) + (srcs or []),
tags = ["manual", "exclude_from_package"],
visibility = ["//visibility:private"],
)
tags = (tags or []) + ["nolint"]

# The old srcs convert to textual_hdrs; the stubs are the new srcs.
textual_hdrs = srcs
srcs = new_srcs

# If we're using implementation_deps, then the result of compiling our srcs
# needs to use an intermediate label name. The actual `name` label will be
# used for the "implementation sandwich", below.
Expand All @@ -441,6 +480,7 @@ def _raw_drake_cc_library(
name = compiled_name,
srcs = srcs,
hdrs = hdrs,
textual_hdrs = textual_hdrs,
strip_include_prefix = strip_include_prefix,
include_prefix = include_prefix,
copts = copts,
Expand All @@ -464,6 +504,7 @@ def _raw_drake_cc_library(
cc_library(
name = headers_name,
hdrs = hdrs,
textual_hdrs = None,
strip_include_prefix = strip_include_prefix,
include_prefix = include_prefix,
defines = defines,
Expand Down Expand Up @@ -538,6 +579,7 @@ def drake_cc_library(
gcc_copts = [],
linkstatic = 1,
internal = False,
compile_once_per_scalar = False,
declare_installed_headers = 1,
install_hdrs_exclude = [],
**kwargs):
Expand Down Expand Up @@ -579,6 +621,13 @@ def drake_cc_library(
Libraries marked with `internal = True` should generally be listed only as
deps of _other_ libraries marked as internal, or as "implementation deps"
(see paragraphs above) of non-internal libraries.
Setting `compile_once_per_scalar = True` shards the library rule to build
each file three times (once per scalar, as separate translation units),
instead of compiling all scalars within the same translation unit. This
reduces build latency for especially large source files. Code in cc files
that is not templated (and therefore should be not be compiled three times)
should be surrounded with `#if DRAKE_ONCE_PER_SCALAR_PHASE == 0`.
"""
new_copts = _platform_copts(copts, gcc_copts, clang_copts)
new_tags = kwargs.pop("tags", None) or []
Expand Down Expand Up @@ -625,6 +674,7 @@ def drake_cc_library(
linkstatic = linkstatic,
declare_installed_headers = declare_installed_headers,
install_hdrs_exclude = install_hdrs_exclude,
compile_once_per_scalar = compile_once_per_scalar,
tags = new_tags,
**kwargs
)
Expand Down

0 comments on commit 0d5cbd9

Please sign in to comment.