Skip to content

Commit

Permalink
Remove support for C++14 and require C++17 (RobotLocomotion#12240)
Browse files Browse the repository at this point in the history
Also update pycps for C++17 support.
  • Loading branch information
jamiesnape authored Oct 25, 2019
1 parent f1bd708 commit 78bdef9
Show file tree
Hide file tree
Showing 26 changed files with 34 additions and 176 deletions.
4 changes: 2 additions & 2 deletions .clang-format
Original file line number Diff line number Diff line change
Expand Up @@ -30,8 +30,8 @@ IncludeCategories:
# C system headers.
- Regex: '^[<"](aio|arpa/inet|assert|complex|cpio|ctype|curses|dirent|dlfcn|errno|fcntl|fenv|float|fmtmsg|fnmatch|ftw|glob|grp|iconv|inttypes|iso646|langinfo|libgen|limits|locale|math|monetary|mqueue|ndbm|netdb|net/if|netinet/in|netinet/tcp|nl_types|poll|pthread|pwd|regex|sched|search|semaphore|setjmp|signal|spawn|stdalign|stdarg|stdatomic|stdbool|stddef|stdint|stdio|stdlib|stdnoreturn|string|strings|stropts|sys/ipc|syslog|sys/mman|sys/msg|sys/resource|sys/select|sys/sem|sys/shm|sys/socket|sys/stat|sys/statvfs|sys/time|sys/times|sys/types|sys/uio|sys/un|sys/utsname|sys/wait|tar|term|termios|tgmath|threads|time|trace|uchar|ulimit|uncntrl|unistd|utime|utmpx|wchar|wctype|wordexp)\.h[">]$'
Priority: 20
# C++ system headers (as of C++14).
- Regex: '^[<"](algorithm|array|atomic|bitset|cassert|ccomplex|cctype|cerrno|cfenv|cfloat|chrono|cinttypes|ciso646|climits|clocale|cmath|codecvt|complex|condition_variable|csetjmp|csignal|cstdalign|cstdarg|cstdbool|cstddef|cstdint|cstdio|cstdlib|cstring|ctgmath|ctime|cuchar|cwchar|cwctype|deque|exception|forward_list|fstream|functional|future|initializer_list|iomanip|ios|iosfwd|iostream|istream|iterator|limits|list|locale|map|memory|mutex|new|numeric|ostream|queue|random|ratio|regex|scoped_allocator|set|shared_mutex|sstream|stack|stdexcept|streambuf|string|strstream|system_error|thread|tuple|type_traits|typeindex|typeinfo|unordered_map|unordered_set|utility|valarray|vector)[">]$'
# C++ system headers (as of C++17).
- Regex: '^[<"](algorithm|any|array|atomic|bitset|cassert|ccomplex|cctype|cerrno|cfenv|cfloat|charconv|chrono|cinttypes|ciso646|climits|clocale|cmath|codecvt|complex|condition_variable|csetjmp|csignal|cstdalign|cstdarg|cstdbool|cstddef|cstdint|cstdio|cstdlib|cstring|ctgmath|ctime|cuchar|cwchar|cwctype|deque|exception|filesystem|forward_list|fstream|functional|future|initializer_list|iomanip|ios|iosfwd|iostream|istream|iterator|limits|list|locale|map|memory|memory_resource|mutex|new|numeric|optional|ostream|queue|random|ratio|regex|scoped_allocator|set|shared_mutex|sstream|stack|stdexcept|streambuf|string|string_view|strstream|system_error|thread|tuple|type_traits|typeindex|typeinfo|unordered_map|unordered_set|utility|valarray|variant|vector)[">]$'
Priority: 30
# Other libraries' h files (with angles).
- Regex: '^<'
Expand Down
35 changes: 6 additions & 29 deletions CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -103,7 +103,7 @@ endif()

# The minimum compiler versions should match those listed in both
# doc/developers.rst and tools/workspace/cc/repository.bzl.
set(MINIMUM_APPLE_CLANG_VERSION 10)
set(MINIMUM_APPLE_CLANG_VERSION 11)
set(MINIMUM_CLANG_VERSION 6)
set(MINIMUM_GNU_VERSION 7.4)

Expand Down Expand Up @@ -153,12 +153,12 @@ elseif(CMAKE_CXX_COMPILER_ID STREQUAL GNU)
else()
# Check flag added in tools/cc_toolchain/bazel.rc is supported.
include(CheckCXXCompilerFlag)
set(FLAG_STD_CXX14 -std=c++14)
check_cxx_compiler_flag(${FLAG_STD_CXX14} CXX_COMPILER_SUPPORTS_FLAG_STD_CXX14)
if(NOT CXX_COMPILER_SUPPORTS_FLAG_STD_CXX14)
set(FLAG_STD_CXX17 -std=c++17)
check_cxx_compiler_flag(${FLAG_STD_CXX17} CXX_COMPILER_SUPPORTS_FLAG_STD_CXX17)
if(NOT CXX_COMPILER_SUPPORTS_FLAG_STD_CXX17)
message(FATAL_ERROR
"Compilation with ${CMAKE_CXX_COMPILER_ID} is NOT supported because it "
"does not accept the ${FLAG_STD_CXX14} flag"
"does not accept the ${FLAG_STD_CXX17} flag"
)
endif()
message(WARNING
Expand Down Expand Up @@ -189,32 +189,9 @@ else()
endif()
endif()

set(MINIMUM_SUPPORTED_CXX_VERSION 14)
set(MAXIMUM_SUPPORTED_CXX_VERSION 17)
set(DEFAULT_CXX_VERSION 14)
set(CMAKE_CXX_EXTENSIONS OFF)
set(CMAKE_CXX_STANDARD_REQUIRED ON)
if(NOT CMAKE_CXX_STANDARD)
set(CMAKE_CXX_STANDARD ${DEFAULT_CXX_VERSION})
endif()
if(CMAKE_CXX_STANDARD LESS MINIMUM_SUPPORTED_CXX_VERSION)
message(FATAL_ERROR
"Compilation with C++ standard ${CMAKE_CXX_STANDARD} is NOT supported"
)
endif()
if(CMAKE_CXX_STANDARD GREATER MAXIMUM_SUPPORTED_CXX_VERSION)
message(WARNING
"Compilation with C++ standard ${CMAKE_CXX_STANDARD} is NOT supported. "
"Compilation of project drake_cxx_python may fail."
)
endif()
if(CMAKE_CXX${CMAKE_CXX_STANDARD}_STANDARD_COMPILE_OPTION)
set(MAYBE_BAZEL_CXXOPT_STD
"build --cxxopt=${CMAKE_CXX${CMAKE_CXX_STANDARD}_STANDARD_COMPILE_OPTION} --host_cxxopt=${CMAKE_CXX${CMAKE_CXX_STANDARD}_STANDARD_COMPILE_OPTION}"
)
else()
set(MAYBE_BAZEL_CXXOPT_STD)
endif()
set(CMAKE_CXX_STANDARD 17)

# The supported Python major/minor versions should match those listed in both
# doc/developers.rst and tools/workspace/python/repository.bzl.
Expand Down
7 changes: 0 additions & 7 deletions attic/multibody/rigid_body_tree_alias_groups.cc
Original file line number Diff line number Diff line change
Expand Up @@ -2,13 +2,6 @@

#include <set>

#if __cplusplus < 201703L
template <typename T>
constexpr char RigidBodyTreeAliasGroups<T>::kBodyGroupsKeyword[];
template <typename T>
constexpr char RigidBodyTreeAliasGroups<T>::kJointGroupsKeyword[];
#endif

namespace {
// Inserts @p vec into @p mapping if @p key does not exist, or appends @p vec
// to the existing vector in @p map. This function also guarantees the newly
Expand Down
4 changes: 2 additions & 2 deletions bindings/pydrake/.clang-format
Original file line number Diff line number Diff line change
Expand Up @@ -49,8 +49,8 @@ IncludeCategories:
# C system headers.
- Regex: '^[<"](aio|arpa/inet|assert|complex|cpio|ctype|curses|dirent|dlfcn|errno|fcntl|fenv|float|fmtmsg|fnmatch|ftw|glob|grp|iconv|inttypes|iso646|langinfo|libgen|limits|locale|math|monetary|mqueue|ndbm|netdb|net/if|netinet/in|netinet/tcp|nl_types|poll|pthread|pwd|regex|sched|search|semaphore|setjmp|signal|spawn|stdalign|stdarg|stdatomic|stdbool|stddef|stdint|stdio|stdlib|stdnoreturn|string|strings|stropts|sys/ipc|syslog|sys/mman|sys/msg|sys/resource|sys/select|sys/sem|sys/shm|sys/socket|sys/stat|sys/statvfs|sys/time|sys/times|sys/types|sys/uio|sys/un|sys/utsname|sys/wait|tar|term|termios|tgmath|threads|time|trace|uchar|ulimit|uncntrl|unistd|utime|utmpx|wchar|wctype|wordexp)\.h[">]$'
Priority: 20
# C++ system headers (as of C++14).
- Regex: '^[<"](algorithm|array|atomic|bitset|cassert|ccomplex|cctype|cerrno|cfenv|cfloat|chrono|cinttypes|ciso646|climits|clocale|cmath|codecvt|complex|condition_variable|csetjmp|csignal|cstdalign|cstdarg|cstdbool|cstddef|cstdint|cstdio|cstdlib|cstring|ctgmath|ctime|cuchar|cwchar|cwctype|deque|exception|forward_list|fstream|functional|future|initializer_list|iomanip|ios|iosfwd|iostream|istream|iterator|limits|list|locale|map|memory|mutex|new|numeric|ostream|queue|random|ratio|regex|scoped_allocator|set|shared_mutex|sstream|stack|stdexcept|streambuf|string|strstream|system_error|thread|tuple|type_traits|typeindex|typeinfo|unordered_map|unordered_set|utility|valarray|vector)[">]$'
# C++ system headers (as of C++17).
- Regex: '^[<"](algorithm|any|array|atomic|bitset|cassert|ccomplex|cctype|cerrno|cfenv|cfloat|charconv|chrono|cinttypes|ciso646|climits|clocale|cmath|codecvt|complex|condition_variable|csetjmp|csignal|cstdalign|cstdarg|cstdbool|cstddef|cstdint|cstdio|cstdlib|cstring|ctgmath|ctime|cuchar|cwchar|cwctype|deque|exception|filesystem|forward_list|fstream|functional|future|initializer_list|iomanip|ios|iosfwd|iostream|istream|iterator|limits|list|locale|map|memory|memory_resource|mutex|new|numeric|optional|ostream|queue|random|ratio|regex|scoped_allocator|set|shared_mutex|sstream|stack|stdexcept|streambuf|string|string_view|strstream|system_error|thread|tuple|type_traits|typeindex|typeinfo|unordered_map|unordered_set|utility|valarray|variant|vector)[">]$'
Priority: 30
# Other libraries' h files (with angles).
- Regex: '^<'
Expand Down
1 change: 0 additions & 1 deletion cmake/bazel.rc.in
Original file line number Diff line number Diff line change
Expand Up @@ -17,7 +17,6 @@ build --subcommands=@BAZEL_SUBCOMMANDS@
build --symlink_prefix=/

@MAYBE_BAZEL_CONFIG@
@MAYBE_BAZEL_CXXOPT_STD@

build:Debug --compilation_mode=dbg
build:MinSizeRel --compilation_mode=opt @MAYBE_BAZEL_COPT_OS@
Expand Down
4 changes: 0 additions & 4 deletions common/drake_optional.h
Original file line number Diff line number Diff line change
Expand Up @@ -9,25 +9,21 @@
// though STX would otherwise do so by default) because its API often differs
// from std::optional.
#define STX_NO_STD_OPTIONAL
#if __cplusplus >= 201703L
#if defined(__has_include)
#if __has_include(<optional>)
#include <optional>
#undef STX_NO_STD_OPTIONAL
#endif
#endif
#endif

// If the current toolchain offers a working std::variant, then use it.
#define STX_NO_STD_VARIANT
#if __cplusplus >= 201703L
#if defined(__has_include)
#if __has_include(<variant>)
#include <variant>
#undef STX_NO_STD_VARIANT
#endif
#endif
#endif

// Due to https://github.com/tcbrindle/cpp17_headers/issues/4, we must always
// include variant before optional. Rather than leaving that up to our users,
Expand Down
11 changes: 2 additions & 9 deletions common/hash.cc
Original file line number Diff line number Diff line change
@@ -1,11 +1,4 @@
#include "drake/common/hash.h"

namespace drake {
namespace internal {

#if __cplusplus < 201703L
constexpr size_t FNV1aHasher::kFnvPrime;
#endif

} // namespace internal
} // namespace drake
// For now, this is an empty .cc file that only serves to confirm
// hash.h is a stand-alone header.
9 changes: 2 additions & 7 deletions common/random.cc
Original file line number Diff line number Diff line change
@@ -1,9 +1,4 @@
#include "drake/common/random.h"

namespace drake {

#if __cplusplus < 201703L
constexpr RandomGenerator::result_type RandomGenerator::default_seed;
#endif

} // namespace drake
// For now, this is an empty .cc file that only serves to confirm
// random.h is a stand-alone header.
2 changes: 1 addition & 1 deletion common/test/drake_assert_test_compile_variants.sh
Original file line number Diff line number Diff line change
Expand Up @@ -27,7 +27,7 @@ if [[ ! -e ./drake ]]; then
fi

# Confirm that it compiles successfully, whether or not assertions are enabled.
TESTING_CXXFLAGS="$BAZEL_CC_FLAGS -std=c++14 -I . \
TESTING_CXXFLAGS="$BAZEL_CC_FLAGS -std=c++17 -I . \
-c $drake_assert_test_compile_cc \
-o /dev/null"
"$BAZEL_CC" $TESTING_CXXFLAGS
Expand Down
4 changes: 0 additions & 4 deletions common/trajectories/piecewise_trajectory.h
Original file line number Diff line number Diff line change
Expand Up @@ -76,9 +76,5 @@ class PiecewiseTrajectory : public Trajectory<T> {
std::vector<double> breaks_;
};

#if __cplusplus < 201703L
template <typename T>
constexpr double PiecewiseTrajectory<T>::kEpsilonTime;
#endif
} // namespace trajectories
} // namespace drake
4 changes: 0 additions & 4 deletions common/value.h
Original file line number Diff line number Diff line change
Expand Up @@ -538,10 +538,6 @@ struct TypeHash {
// (Such failures are expected to be rare.)
static constexpr size_t value = calc();
};
#if __cplusplus < 201703L
template <typename T>
constexpr size_t TypeHash<T>::value;
#endif

// This is called once per process per T whose type_hash is 0. It logs a
// TypeHash failure message to Drake's text log.
Expand Down
2 changes: 1 addition & 1 deletion doc/developers.rst
Original file line number Diff line number Diff line change
Expand Up @@ -73,7 +73,7 @@ The following table shows the configurations and platforms that Drake
officially supports. Supported configurations are tested in continuous
integration. All other configurations are provided on a best-effort basis.

Drake requires a compiler running in C++14 mode or greater.
Drake requires a compiler running in C++17 mode.

+----------------------------------+-------+-------+---------------------+-------------------+-----------------+
| Operating System | Bazel | CMake | C/C++ Compiler | Java | Python |
Expand Down
4 changes: 0 additions & 4 deletions manipulation/planner/robot_plan_interpolator.cc
Original file line number Diff line number Diff line change
Expand Up @@ -34,10 +34,6 @@ constexpr int kAbsStateIdxInitFlag = 1;

} // namespace

#if __cplusplus < 201703L
constexpr double RobotPlanInterpolator::kDefaultPlanUpdateInterval;
#endif

// TODO(sammy-tri) If we had version of Trajectory which supported
// outputting the derivatives in value(), we could avoid keeping track
// of multiple polynomials below.
Expand Down
5 changes: 0 additions & 5 deletions math/roll_pitch_yaw.cc
Original file line number Diff line number Diff line change
Expand Up @@ -10,11 +10,6 @@
namespace drake {
namespace math {

#if __cplusplus < 201703L
template <class T>
constexpr double RollPitchYaw<T>::kGimbalLockToleranceCosPitchAngle;
#endif

template <typename T>
RotationMatrix<T> RollPitchYaw<T>::ToRotationMatrix() const {
return RotationMatrix<T>(*this);
Expand Down
5 changes: 0 additions & 5 deletions solvers/mathematical_program.cc
Original file line number Diff line number Diff line change
Expand Up @@ -52,11 +52,6 @@ using internal::CreateBinding;
using internal::DecomposeLinearExpression;
using internal::SymbolicError;

#if __cplusplus < 201703L
constexpr double MathematicalProgram::kGlobalInfeasibleCost;
constexpr double MathematicalProgram::kUnboundedCost;
#endif

MathematicalProgram::MathematicalProgram()
: x_initial_guess_(0),
optimal_cost_(numeric_limits<double>::quiet_NaN()),
Expand Down
8 changes: 4 additions & 4 deletions systems/framework/test/diagram_builder_test.cc
Original file line number Diff line number Diff line change
Expand Up @@ -207,21 +207,21 @@ GTEST_TEST(DiagramBuilderTest, FinalizeWhenEmpty) {
GTEST_TEST(DiagramBuilderTest, SystemsThatAreNotAddedThrow) {
DiagramBuilder<double> builder;
Adder<double> adder(1 /* inputs */, 1 /* size */);
adder.set_name("x");
adder.set_name("adder");
DRAKE_EXPECT_THROWS_MESSAGE(
builder.Connect(adder, adder),
std::logic_error,
"DiagramBuilder: Cannot operate on ports of System x "
"DiagramBuilder: Cannot operate on ports of System adder "
"until it has been registered using AddSystem");
DRAKE_EXPECT_THROWS_MESSAGE(
builder.ExportInput(adder.get_input_port(0)),
std::logic_error,
"DiagramBuilder: Cannot operate on ports of System x "
"DiagramBuilder: Cannot operate on ports of System adder "
"until it has been registered using AddSystem");
DRAKE_EXPECT_THROWS_MESSAGE(
builder.ExportOutput(adder.get_output_port()),
std::logic_error,
"DiagramBuilder: Cannot operate on ports of System x "
"DiagramBuilder: Cannot operate on ports of System adder "
"until it has been registered using AddSystem");
}

Expand Down
3 changes: 0 additions & 3 deletions systems/framework/test/vector_system_test.cc
Original file line number Diff line number Diff line change
Expand Up @@ -136,9 +136,6 @@ class TestVectorSystem : public VectorSystem<double> {
mutable int time_derivatives_count_{0};
mutable int discrete_variable_updates_count_{0};
};
#if __cplusplus < 201703L
constexpr int TestVectorSystem::kSize;
#endif

class VectorSystemTest : public ::testing::Test {
// Not yet needed, but placeholder for future common code.
Expand Down
4 changes: 0 additions & 4 deletions systems/rendering/frame_velocity.cc
Original file line number Diff line number Diff line change
Expand Up @@ -6,10 +6,6 @@ namespace drake {
namespace systems {
namespace rendering {

#if __cplusplus < 201703L
template <typename T> constexpr int FrameVelocity<T>::kSize;
#endif

template <typename T>
FrameVelocity<T>::FrameVelocity()
: FrameVelocity<T>::FrameVelocity(
Expand Down
4 changes: 0 additions & 4 deletions systems/rendering/pose_vector.cc
Original file line number Diff line number Diff line change
Expand Up @@ -6,10 +6,6 @@ namespace drake {
namespace systems {
namespace rendering {

#if __cplusplus < 201703L
template <typename T> constexpr int PoseVector<T>::kSize;
#endif

template <typename T>
PoseVector<T>::PoseVector()
: PoseVector<T>::PoseVector(Eigen::Quaternion<T>::Identity(),
Expand Down
17 changes: 2 additions & 15 deletions systems/sensors/image.cc
Original file line number Diff line number Diff line change
@@ -1,17 +1,4 @@
#include "drake/systems/sensors/image.h"

namespace drake {
namespace systems {
namespace sensors {

#if __cplusplus < 201703L
constexpr float InvalidDepth::kTooFar;
constexpr float InvalidDepth::kTooClose;

constexpr int16_t Label::kNoBody;
constexpr int16_t Label::kFlatTerrain;
#endif

} // namespace sensors
} // namespace systems
} // namespace drake
// For now, this is an empty .cc file that only serves to confirm
// image.h is a stand-alone header.
11 changes: 0 additions & 11 deletions systems/sensors/image.h
Original file line number Diff line number Diff line change
Expand Up @@ -184,17 +184,6 @@ class Label {
std::numeric_limits<int16_t>::max() - 1};
};

#if __cplusplus < 201703L
template <PixelType kPixelType>
constexpr int Image<kPixelType>::kNumChannels;

template <PixelType kPixelType>
constexpr int Image<kPixelType>::kPixelSize;

template <PixelType kPixelType>
constexpr PixelFormat Image<kPixelType>::kPixelFormat;
#endif

} // namespace sensors
} // namespace systems
} // namespace drake
42 changes: 2 additions & 40 deletions systems/sensors/pixel_types.cc
Original file line number Diff line number Diff line change
@@ -1,42 +1,4 @@
#include "drake/systems/sensors/pixel_types.h"

namespace drake {
namespace systems {
namespace sensors {

#if __cplusplus < 201703L
constexpr int ImageTraits<PixelType::kRgb8U>::kNumChannels;
constexpr PixelFormat ImageTraits<PixelType::kRgb8U>::kPixelFormat;

constexpr int ImageTraits<PixelType::kBgr8U>::kNumChannels;
constexpr PixelFormat ImageTraits<PixelType::kBgr8U>::kPixelFormat;

constexpr int ImageTraits<PixelType::kRgba8U>::kNumChannels;
constexpr PixelFormat ImageTraits<PixelType::kRgba8U>::kPixelFormat;

constexpr int ImageTraits<PixelType::kBgra8U>::kNumChannels;
constexpr PixelFormat ImageTraits<PixelType::kBgra8U>::kPixelFormat;

constexpr int ImageTraits<PixelType::kDepth32F>::kNumChannels;
constexpr PixelFormat ImageTraits<PixelType::kDepth32F>::kPixelFormat;
constexpr ImageTraits<PixelType::kDepth32F>::ChannelType ImageTraits<PixelType::kDepth32F>::kTooClose; // NOLINT
constexpr ImageTraits<PixelType::kDepth32F>::ChannelType ImageTraits<PixelType::kDepth32F>::kTooFar; // NOLINT

constexpr int ImageTraits<PixelType::kDepth16U>::kNumChannels;
constexpr PixelFormat ImageTraits<PixelType::kDepth16U>::kPixelFormat;
constexpr ImageTraits<PixelType::kDepth16U>::ChannelType ImageTraits<PixelType::kDepth16U>::kTooClose; // NOLINT
constexpr ImageTraits<PixelType::kDepth16U>::ChannelType ImageTraits<PixelType::kDepth16U>::kTooFar; // NOLINT

constexpr int ImageTraits<PixelType::kLabel16I>::kNumChannels;
constexpr PixelFormat ImageTraits<PixelType::kLabel16I>::kPixelFormat;

constexpr int ImageTraits<PixelType::kGrey8U>::kNumChannels;
constexpr PixelFormat ImageTraits<PixelType::kGrey8U>::kPixelFormat;

constexpr int ImageTraits<PixelType::kExpr>::kNumChannels;
constexpr PixelFormat ImageTraits<PixelType::kExpr>::kPixelFormat;
#endif // __cplusplus

} // namespace sensors
} // namespace systems
} // namespace drake
// For now, this is an empty .cc file that only serves to confirm
// pixel_types.h is a stand-alone header.
6 changes: 3 additions & 3 deletions tools/cc_toolchain/bazel.rc
Original file line number Diff line number Diff line change
@@ -1,9 +1,9 @@
# Disable ccache due to incompatibility with Bazel.
build --action_env=CCACHE_DISABLE=1

# Add C++14 compiler flags.
build --cxxopt=-std=c++14
build --host_cxxopt=-std=c++14
# Add C++17 compiler flags.
build --cxxopt=-std=c++17
build --host_cxxopt=-std=c++17

# When compiling with Drake as the main WORKSPACE (i.e., if and only if this
# rcfile is loaded), we enable -Werror by default for Drake's *own* targets,
Expand Down
Loading

0 comments on commit 78bdef9

Please sign in to comment.