From 82330e764277e14bbf3ca21aa136e1dba4fd0fc3 Mon Sep 17 00:00:00 2001 From: Kenji Miyake <31987104+kenji-miyake@users.noreply.github.com> Date: Mon, 18 Apr 2022 15:14:47 +0900 Subject: [PATCH] ci(pre-commit): clear the exclude option (#426) * ci(pre-commit): remove unnecessary excludes Signed-off-by: Kenji Miyake * ci(pre-commit): autofix * ci(pre-commit): autofix * address pre-commit for Markdown files Signed-off-by: Kenji Miyake * fix Python imports Signed-off-by: Kenji Miyake * address cpplint errors Signed-off-by: Kenji Miyake * fix broken package.xml Signed-off-by: Kenji Miyake * rename ROS parameter files Signed-off-by: Kenji Miyake * fix build Signed-off-by: Kenji Miyake * use autoware_lint_common Signed-off-by: Kenji Miyake Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> --- .pre-commit-config.yaml | 2 +- .../design/autoware_auto_cmake-design.md | 22 +- common/autoware_auto_cmake/package.xml | 4 +- common/autoware_auto_common/CMakeLists.txt | 5 - .../design/comparisons.md | 17 +- .../include/common/type_traits.hpp | 98 ++++--- .../include/common/types.hpp | 51 ++-- .../include/common/visibility_control.hpp | 24 +- .../include/helper_functions/angle_utils.hpp | 10 +- .../helper_functions/bool_comparisons.hpp | 2 +- .../include/helper_functions/byte_reader.hpp | 10 +- .../include/helper_functions/crtp.hpp | 6 +- .../helper_functions/float_comparisons.hpp | 22 +- .../helper_functions/mahalanobis_distance.hpp | 13 +- .../helper_functions/message_adapters.hpp | 30 +- .../helper_functions/template_utils.hpp | 34 ++- .../include/helper_functions/type_name.hpp | 10 +- common/autoware_auto_common/package.xml | 28 +- .../test/test_angle_utils.cpp | 5 +- .../test/test_bool_comparisons.cpp | 7 +- .../test/test_byte_reader.cpp | 11 +- .../test/test_float_comparisons.cpp | 28 +- .../test/test_mahalanobis_distance.cpp | 11 +- .../test/test_message_field_adapters.cpp | 14 +- .../test/test_template_utils.cpp | 87 +++--- .../test/test_type_name.cpp | 7 +- .../test/test_type_traits.cpp | 66 +++-- .../autoware_auto_geometry/design/interval.md | 55 ++-- .../design/polygon_intersection_2d-design.md | 45 +-- .../design/spatial-hash-design.md | 41 ++- .../geometry/bounding_box/eigenbox_2d.hpp | 38 +-- .../include/geometry/bounding_box/lfit.hpp | 35 +-- .../bounding_box/rotating_calipers.hpp | 54 ++-- .../include/geometry/bounding_box_2d.hpp | 2 +- .../include/geometry/common_2d.hpp | 93 +++---- .../include/geometry/common_3d.hpp | 6 +- .../include/geometry/convex_hull.hpp | 32 +-- .../include/geometry/hull_pockets.hpp | 30 +- .../include/geometry/intersection.hpp | 137 ++++----- .../include/geometry/interval.hpp | 89 +++--- .../include/geometry/lookup_table.hpp | 32 +-- .../include/geometry/spatial_hash.hpp | 135 +++------ .../include/geometry/spatial_hash_config.hpp | 100 ++----- .../include/geometry/visibility_control.hpp | 29 +- common/autoware_auto_geometry/package.xml | 38 +-- .../src/spatial_hash.cpp | 44 +-- .../test/include/test_bounding_box.hpp | 262 +++++------------- .../test/include/test_spatial_hash.hpp | 36 +-- .../test/src/lookup_table.cpp | 15 +- .../test/src/test_area.cpp | 28 +- .../test/src/test_common_2d.cpp | 95 ++++--- .../test/src/test_convex_hull.cpp | 158 +++++------ .../test/src/test_geometry.cpp | 4 +- .../test/src/test_hull_pockets.cpp | 98 +++---- .../test/src/test_intersection.cpp | 131 ++++----- .../test/src/test_interval.cpp | 58 ++-- .../README.md | 8 +- .../include/common/color_alpha_property.hpp | 6 +- .../detected_objects_display.hpp | 5 +- .../object_polygon_detail.hpp | 48 ++-- .../object_polygon_display_base.hpp | 36 +-- .../predicted_objects_display.hpp | 10 +- .../tracked_objects_display.hpp | 10 +- .../package.xml | 34 +-- .../src/common/color_alpha_property.cpp | 1 + .../detected_objects_display.cpp | 6 +- .../object_polygon_detail.cpp | 80 +++--- .../predicted_objects_display.cpp | 6 +- .../tracked_objects_display.cpp | 6 +- .../design/autoware-auto-tf2-design.md | 98 ++++--- .../tf2_autoware_auto_msgs.hpp | 69 +++-- common/autoware_auto_tf2/package.xml | 40 +-- .../test/test_tf2_autoware_auto_msgs.cpp | 18 +- .../autoware_testing/smoke_test.py | 54 ++-- .../design/autoware_testing-design.md | 31 ++- common/autoware_testing/package.xml | 4 +- common/autoware_testing/setup.py | 24 +- .../design/fake_test_node-design.md | 12 +- .../include/fake_test_node/fake_test_node.hpp | 39 +-- .../fake_test_node/visibility_control.hpp | 24 +- common/fake_test_node/package.xml | 36 +-- common/fake_test_node/src/fake_test_node.cpp | 20 +- .../test/test_fake_test_node.cpp | 29 +- .../had_map_utils/had_map_computation.hpp | 5 +- .../had_map_utils/had_map_conversion.hpp | 5 +- .../include/had_map_utils/had_map_query.hpp | 23 +- .../include/had_map_utils/had_map_utils.hpp | 9 +- .../had_map_utils/had_map_visualization.hpp | 93 +++---- .../had_map_utils/visibility_control.hpp | 24 +- common/had_map_utils/package.xml | 49 ++-- .../had_map_utils/src/had_map_computation.cpp | 56 ++-- .../had_map_utils/src/had_map_conversion.cpp | 9 +- common/had_map_utils/src/had_map_query.cpp | 14 +- common/had_map_utils/src/had_map_utils.cpp | 22 +- .../src/had_map_visualization.cpp | 192 +++++-------- .../include/motion_common/config.hpp | 57 ++-- .../include/motion_common/motion_common.hpp | 43 ++- .../motion_common/trajectory_common.hpp | 117 ++++---- .../motion_common/visibility_control.hpp | 24 +- common/motion_common/package.xml | 8 +- .../kinematic_bicycle.snippet.hpp | 5 +- .../linear_tire.snippet.hpp | 11 +- .../src/motion_common/config.cpp | 151 +++------- .../src/motion_common/motion_common.cpp | 56 ++-- .../src/motion_common/trajectory_common.cpp | 16 +- common/motion_common/test/interpolation.cpp | 127 ++++----- common/motion_common/test/sanity_checks.cpp | 10 +- common/motion_common/test/trajectory.cpp | 31 ++- .../include/motion_testing/motion_testing.hpp | 43 +-- .../motion_testing/visibility_control.hpp | 24 +- common/motion_testing/package.xml | 10 +- .../src/motion_testing/motion_testing.cpp | 86 ++---- .../test/constant_trajectory.cpp | 10 +- .../motion_testing/test/trajectory_checks.cpp | 9 +- .../design/osqp_interface-design.md | 69 +++-- .../osqp_interface/csc_matrix_conv.hpp | 4 +- .../include/osqp_interface/osqp_interface.hpp | 4 +- .../osqp_interface/visibility_control.hpp | 24 +- common/osqp_interface/package.xml | 2 +- common/osqp_interface/src/csc_matrix_conv.cpp | 13 +- common/osqp_interface/src/osqp_interface.cpp | 27 +- .../test/test_csc_matrix_conv.cpp | 43 ++- .../test/test_osqp_interface.cpp | 20 +- .../include/time_utils/stopwatch.hpp | 16 +- .../include/time_utils/time_utils.hpp | 8 +- .../include/time_utils/visibility_control.hpp | 24 +- common/time_utils/package.xml | 8 +- .../time_utils/src/time_utils/time_utils.cpp | 6 +- .../vehicle_constants_manager-design.md | 74 ++--- .../vehicle_constants_manager.hpp | 13 +- .../visibility_control.hpp | 24 +- common/vehicle_constants_manager/package.xml | 4 +- .../param/params_lexus_rx_hybrid_2016.yaml | 4 +- .../src/vehicle_constants_manager.cpp | 162 ++++++----- .../test/test_vehicle_constants_manager.cpp | 60 ++-- .../design/trajectory_follower-design.md | 19 +- .../design/trajectory_follower-mpc-design.md | 33 ++- .../design/trajectory_follower-pid-design.md | 27 +- .../trajectory_follower/debug_values.hpp | 13 +- .../trajectory_follower/interpolate.hpp | 8 +- .../longitudinal_controller_utils.hpp | 80 +++--- .../trajectory_follower/lowpass_filter.hpp | 16 +- .../include/trajectory_follower/mpc.hpp | 158 +++++------ .../trajectory_follower/mpc_trajectory.hpp | 11 +- .../include/trajectory_follower/mpc_utils.hpp | 50 ++-- .../include/trajectory_follower/pid.hpp | 11 +- .../qp_solver/qp_solver_osqp.hpp | 5 +- .../qp_solver/qp_solver_unconstr_fast.hpp | 7 +- .../trajectory_follower/smooth_stop.hpp | 21 +- .../vehicle_model_bicycle_dynamics.hpp | 32 +-- .../vehicle_model_bicycle_kinematics.hpp | 6 +- ...icle_model_bicycle_kinematics_no_delay.hpp | 3 +- .../vehicle_model/vehicle_model_interface.hpp | 6 +- .../visibility_control.hpp | 24 +- control/trajectory_follower/package.xml | 8 +- .../trajectory_follower/src/interpolate.cpp | 28 +- .../src/longitudinal_controller_utils.cpp | 25 +- .../src/lowpass_filter.cpp | 6 +- control/trajectory_follower/src/mpc.cpp | 165 +++++------ .../src/mpc_trajectory.cpp | 6 +- control/trajectory_follower/src/mpc_utils.cpp | 57 ++-- control/trajectory_follower/src/pid.cpp | 18 +- .../src/qp_solver/qp_solver_osqp.cpp | 11 +- .../src/qp_solver/qp_solver_unconstr_fast.cpp | 4 +- .../trajectory_follower/src/smooth_stop.cpp | 27 +- .../vehicle_model_bicycle_dynamics.cpp | 9 +- .../vehicle_model_bicycle_kinematics.cpp | 8 +- ...icle_model_bicycle_kinematics_no_delay.cpp | 2 +- .../vehicle_model/vehicle_model_interface.cpp | 15 +- .../test/test_debug_values.cpp | 3 +- .../test/test_interpolate.cpp | 49 +--- .../test_longitudinal_controller_utils.cpp | 78 +++--- .../test/test_lowpass_filter.cpp | 12 +- control/trajectory_follower/test/test_mpc.cpp | 115 ++++---- .../test/test_mpc_trajectory.cpp | 7 +- .../test/test_mpc_utils.cpp | 17 +- control/trajectory_follower/test/test_pid.cpp | 7 +- .../test/test_smooth_stop.cpp | 21 +- .../trajectory_follower_nodes/CMakeLists.txt | 6 +- .../plot_juggler_trajectory_follower.xml | 1 - .../design/lateral_controller-design.md | 65 +++-- .../design/latlon_muxer-design.md | 13 +- .../design/longitudinal_controller-design.md | 42 +-- .../design/trajectory_follower-design.md | 14 +- .../lateral_controller_node.hpp | 41 ++- .../latlon_muxer_node.hpp | 20 +- .../longitudinal_controller_node.hpp | 58 ++-- .../visibility_control.hpp | 24 +- control/trajectory_follower_nodes/package.xml | 10 +- .../lateral_controller_defaults.param.yaml | 67 +++++ .../param/lateral_controller_defaults.yaml | 68 ----- ....yaml => latlon_muxer_defaults.param.yaml} | 0 ...ngitudinal_controller_defaults.param.yaml} | 0 ...info.yaml => test_vehicle_info.param.yaml} | 0 .../src/lateral_controller_node.cpp | 196 ++++++------- .../src/latlon_muxer_node.cpp | 23 +- .../src/longitudinal_controller_node.cpp | 249 +++++++---------- .../test/test_lateral_controller_node.cpp | 147 +++++----- .../test/test_latlon_muxer_node.cpp | 87 +++--- .../test_longitudinal_controller_node.cpp | 156 ++++++----- .../test/trajectory_follower_test_utils.hpp | 31 +-- planning/costmap_generator/README.md | 2 +- .../launch/costmap_generator.launch.xml | 48 ++-- .../costmap_generator_node.cpp | 4 +- planning/costmap_generator/package.xml | 3 +- planning/freespace_planner/README.md | 2 +- .../freespace_planner_node.hpp | 4 +- .../launch/freespace_planner.launch.xml | 18 +- planning/freespace_planner/package.xml | 4 +- .../freespace_planner_node.cpp | 14 +- .../simple_planning_simulator-design.md | 124 ++++----- .../simple_planning_simulator_core.hpp | 88 +++--- .../vehicle_model/sim_model.hpp | 11 +- .../sim_model_delay_steer_acc.hpp | 15 +- .../sim_model_delay_steer_acc_geared.hpp | 19 +- .../sim_model_delay_steer_vel.hpp | 27 +- .../sim_model_ideal_steer_acc.hpp | 16 +- .../sim_model_ideal_steer_acc_geared.hpp | 22 +- .../sim_model_ideal_steer_vel.hpp | 15 +- .../vehicle_model/sim_model_interface.hpp | 38 +-- .../visibility_control.hpp | 4 +- .../simple_planning_simulator.launch.py | 80 +++--- .../simple_planning_simulator/package.xml | 23 +- .../simple_planning_simulator_core.cpp | 206 +------------- .../sim_model_delay_steer_acc.cpp | 16 +- .../sim_model_delay_steer_acc_geared.cpp | 24 +- .../sim_model_delay_steer_vel.cpp | 10 +- .../sim_model_ideal_steer_acc.cpp | 24 +- .../sim_model_ideal_steer_acc_geared.cpp | 26 +- .../sim_model_ideal_steer_vel.cpp | 19 +- .../vehicle_model/sim_model_interface.cpp | 51 +--- .../test/test_simple_planning_simulator.cpp | 19 +- 232 files changed, 3823 insertions(+), 4945 deletions(-) mode change 100755 => 100644 common/autoware_auto_tf2/test/test_tf2_autoware_auto_msgs.cpp create mode 100644 control/trajectory_follower_nodes/param/lateral_controller_defaults.param.yaml delete mode 100644 control/trajectory_follower_nodes/param/lateral_controller_defaults.yaml rename control/trajectory_follower_nodes/param/{latlon_muxer_defaults.yaml => latlon_muxer_defaults.param.yaml} (100%) rename control/trajectory_follower_nodes/param/{longitudinal_controller_defaults.yaml => longitudinal_controller_defaults.param.yaml} (100%) rename control/trajectory_follower_nodes/param/{test_vehicle_info.yaml => test_vehicle_info.param.yaml} (100%) diff --git a/.pre-commit-config.yaml b/.pre-commit-config.yaml index 733a842865802..f8273cebdd578 100644 --- a/.pre-commit-config.yaml +++ b/.pre-commit-config.yaml @@ -94,4 +94,4 @@ repos: args: [--quiet] exclude: .cu -exclude: .svg|control/trajectory_follower|control/trajectory_follower_nodes|common/autoware_auto_cmake|common/autoware_auto_common|common/autoware_auto_geometry|common/autoware_auto_tf2|common/autoware_testing|common/fake_test_node|common/had_map_utils|common/motion_common|common/motion_testing|common/time_utils|common/vehicle_constants_manager|common/autoware_auto_perception_rviz_plugin|common/osqp_interface|simulator/simple_planning_simulator|planning/freespace_planner|planning/astar_search|planning/costmap_generator +exclude: .svg diff --git a/common/autoware_auto_cmake/design/autoware_auto_cmake-design.md b/common/autoware_auto_cmake/design/autoware_auto_cmake-design.md index 62c82d6dd7db2..8946a02f8d951 100644 --- a/common/autoware_auto_cmake/design/autoware_auto_cmake-design.md +++ b/common/autoware_auto_cmake/design/autoware_auto_cmake-design.md @@ -1,10 +1,8 @@ -autoware_auto_cmake {#autoware-auto-cmake-design} -=========== +# autoware_auto_cmake {#autoware-auto-cmake-design} This is the design document for the `autoware_auto_cmake` package. - -# Purpose +## Purpose Provide common CMake variables and functions to Autoware packages. @@ -13,17 +11,17 @@ Those include: - Setting the language standard - Getting user-provided variables - Providing functions to: - + set compiler flags - + turn off optimizations + - set compiler flags + - turn off optimizations -# Design +## Design -## Usage +### Usage Add `autoware_auto_cmake` as a "build_depend" in the dependent packages. -### CMake variables {#cmake-config-variables} +#### CMake variables {#cmake-config-variables} -|Name|Type|Descritpion|Default| -|----|----|-----------|-------| -|`DOWNLOAD_ARTIFACTS`|*BOOL*|Allow downloading artifacts at build time.|`OFF`| +| Name | Type | Descritpion | Default | +| -------------------- | ------ | ------------------------------------------ | ------- | +| `DOWNLOAD_ARTIFACTS` | _BOOL_ | Allow downloading artifacts at build time. | `OFF` | diff --git a/common/autoware_auto_cmake/package.xml b/common/autoware_auto_cmake/package.xml index 6d8163eae6018..6c3df541c4095 100644 --- a/common/autoware_auto_cmake/package.xml +++ b/common/autoware_auto_cmake/package.xml @@ -12,11 +12,11 @@ ros_environment - ament_cmake_core - ament_cmake_lint_cmake ament_cmake_copyright + ament_cmake_core ament_cmake_cppcheck ament_cmake_cpplint + ament_cmake_lint_cmake ament_cmake_uncrustify ament_cmake_lint_cmake diff --git a/common/autoware_auto_common/CMakeLists.txt b/common/autoware_auto_common/CMakeLists.txt index 45284843f5644..54407c7a0facf 100644 --- a/common/autoware_auto_common/CMakeLists.txt +++ b/common/autoware_auto_common/CMakeLists.txt @@ -32,7 +32,6 @@ if(BUILD_TESTING) # Temporarily disable cpplint and uncrustify list(APPEND AMENT_LINT_AUTO_EXCLUDE ament_cmake_cpplint - ament_cmake_uncrustify ) ament_lint_auto_find_test_dependencies() @@ -46,10 +45,6 @@ if(BUILD_TESTING) find_package(ament_cmake_cpplint) ament_cpplint(${FILES_MINUS_SOME}) - # Re-enable uncrustify - find_package(ament_cmake_uncrustify) - ament_uncrustify(${FILES_MINUS_SOME}) - # Unit tests set(TEST_COMMON test_common_gtest) ament_add_gtest(${TEST_COMMON} diff --git a/common/autoware_auto_common/design/comparisons.md b/common/autoware_auto_common/design/comparisons.md index 6e1d2eb9db35e..d8c1ef6de17e8 100644 --- a/common/autoware_auto_common/design/comparisons.md +++ b/common/autoware_auto_common/design/comparisons.md @@ -1,5 +1,4 @@ -Comparisons {#helper-comparisons} -=========== +# Comparisons {#helper-comparisons} The `float_comparisons.hpp` library is a simple set of functions for performing approximate numerical comparisons. There are separate functions for performing comparisons using absolute bounds and relative bounds. Absolute comparison checks are prefixed with `abs_` and relative checks are prefixed with `rel_`. @@ -8,19 +7,19 @@ The `bool_comparisons.hpp` library additionally contains an XOR operator. The intent of the library is to improve readability of code and reduce likelihood of typographical errors when using numerical and boolean comparisons. -# Target use cases +## Target use cases The approximate comparisons are intended to be used to check whether two numbers lie within some absolute or relative interval. The `exclusive_or` function will test whether two values cast to different boolean values. -# Assumptions +## Assumptions -* The approximate comparisons all take an `epsilon` parameter. -The value of this parameter must be >= 0. -* The library is only intended to be used with floating point types. -A static assertion will be thrown if the library is used with a non-floating point type. +- The approximate comparisons all take an `epsilon` parameter. + The value of this parameter must be >= 0. +- The library is only intended to be used with floating point types. + A static assertion will be thrown if the library is used with a non-floating point type. -# Example Usage +## Example Usage ```c++ #include "common/bool_comparisons.hpp" diff --git a/common/autoware_auto_common/include/common/type_traits.hpp b/common/autoware_auto_common/include/common/type_traits.hpp index ed0ab1709d92c..44dfe92681017 100644 --- a/common/autoware_auto_common/include/common/type_traits.hpp +++ b/common/autoware_auto_common/include/common/type_traits.hpp @@ -41,28 +41,32 @@ namespace type_traits /// /// @return A boolean that should be false for any type passed into this function. /// -template +template constexpr inline autoware::common::types::bool8_t COMMON_PUBLIC impossible_branch() noexcept { return sizeof(T) == 0; } /// Find an index of a type in a tuple -template +template struct COMMON_PUBLIC index { static_assert(!std::is_same>::value, "Could not find QueryT in given tuple"); }; /// Specialization for a tuple that starts with the HeadT type. End of recursion. -template +template struct COMMON_PUBLIC index> - : std::integral_constant {}; +: std::integral_constant +{ +}; /// Specialization for a tuple with a type different to QueryT that calls the recursive step. -template +template struct COMMON_PUBLIC index> - : std::integral_constant>::value> {}; +: std::integral_constant>::value> +{ +}; /// /// @brief Visit every element in a tuple. @@ -75,13 +79,17 @@ struct COMMON_PUBLIC index> /// /// @return Does not return anything. Capture variables in a lambda to return any values. /// -template -COMMON_PUBLIC inline constexpr typename std::enable_if_t -visit(std::tuple &, Callable) noexcept {} +template +COMMON_PUBLIC inline constexpr typename std::enable_if_t visit( + std::tuple &, Callable) noexcept +{ +} /// @brief Same as the previous specialization but for const tuple. -template -COMMON_PUBLIC inline constexpr typename std::enable_if_t -visit(const std::tuple &, Callable) noexcept {} +template +COMMON_PUBLIC inline constexpr typename std::enable_if_t visit( + const std::tuple &, Callable) noexcept +{ +} /// /// @brief Visit every element in a tuple. @@ -98,32 +106,37 @@ visit(const std::tuple &, Callable) noexcept {} /// /// @return Does not return anything. Capture variables in a lambda to return any values. /// -template -COMMON_PUBLIC inline constexpr typename std::enable_if_t -visit(std::tuple & tuple, Callable callable) noexcept +template +COMMON_PUBLIC inline constexpr typename std::enable_if_t visit( + std::tuple & tuple, Callable callable) noexcept { callable(std::get(tuple)); visit(tuple, callable); } /// @brief Same as the previous specialization but for const tuple. -template -COMMON_PUBLIC inline constexpr typename std::enable_if_t -visit(const std::tuple & tuple, Callable callable) noexcept +template +COMMON_PUBLIC inline constexpr typename std::enable_if_t visit( + const std::tuple & tuple, Callable callable) noexcept { callable(std::get(tuple)); visit(tuple, callable); } /// @brief A class to compute a conjunction over given traits. -template -struct COMMON_PUBLIC conjunction : std::true_type {}; +template +struct COMMON_PUBLIC conjunction : std::true_type +{ +}; /// @brief A conjunction of another type shall derive from that type. -template -struct COMMON_PUBLIC conjunction: TraitT {}; -template +template +struct COMMON_PUBLIC conjunction : TraitT +{ +}; +template struct COMMON_PUBLIC conjunction - : std::conditional_t(TraitT::value), conjunction, TraitT> {}; - +: std::conditional_t(TraitT::value), conjunction, TraitT> +{ +}; /// /// @brief A trait to check if a tuple has a type. @@ -133,7 +146,7 @@ struct COMMON_PUBLIC conjunction /// @tparam QueryT A query type. /// @tparam TupleT A tuple to search the type in. /// -template +template struct has_type; /// @@ -142,8 +155,10 @@ struct has_type; /// /// @tparam QueryT Any type. /// -template -struct has_type>: std::false_type {}; +template +struct has_type> : std::false_type +{ +}; /// /// @brief Recursive override of the main trait. @@ -152,8 +167,10 @@ struct has_type>: std::false_type {}; /// @tparam HeadT Head type in the tuple. /// @tparam TailTs Rest of the tuple types. /// -template -struct has_type>: has_type> {}; +template +struct has_type> : has_type> +{ +}; /// /// @brief End of recursion for the main `has_type` trait. Becomes a `true_type` when the first @@ -162,9 +179,10 @@ struct has_type>: has_type -struct has_type>: std::true_type {}; - +template +struct has_type> : std::true_type +{ +}; /// /// @brief A trait used to intersect types stored in tuples at compile time. The resulting @@ -176,7 +194,7 @@ struct has_type>: std::true_type {}; /// @tparam TupleT1 Tuple 1 /// @tparam TupleT2 Tuple 2 /// -template +template struct intersect { /// @@ -185,18 +203,16 @@ struct intersect /// @details This function "iterates" over the types in TupleT1 and checks if those are in /// TupleT2. If this is true, these types are concatenated into a new tuple. /// - template + template static constexpr auto make_intersection(std::index_sequence) { - return std::tuple_cat( - std::conditional_t< - has_type, TupleT2>::value, - std::tuple>, - std::tuple<>>{} ...); + return std::tuple_cat(std::conditional_t< + has_type, TupleT2>::value, + std::tuple>, std::tuple<>>{}...); } /// The resulting tuple type. using type = - decltype(make_intersection(std::make_index_sequence::value> {})); + decltype(make_intersection(std::make_index_sequence::value>{})); }; } // namespace type_traits diff --git a/common/autoware_auto_common/include/common/types.hpp b/common/autoware_auto_common/include/common/types.hpp index f3d49fcea04ff..5c77449e30ff5 100644 --- a/common/autoware_auto_common/include/common/types.hpp +++ b/common/autoware_auto_common/include/common/types.hpp @@ -19,12 +19,12 @@ #ifndef COMMON__TYPES_HPP_ #define COMMON__TYPES_HPP_ +#include "common/visibility_control.hpp" +#include "helper_functions/float_comparisons.hpp" + #include -#include #include - -#include "helper_functions/float_comparisons.hpp" -#include "common/visibility_control.hpp" +#include namespace autoware { @@ -61,16 +61,12 @@ struct COMMON_PUBLIC PointXYZIF float32_t intensity{0}; uint16_t id{0}; static constexpr uint16_t END_OF_SCAN_ID = 65535u; - friend bool operator==( - const PointXYZIF & p1, - const PointXYZIF & p2) noexcept + friend bool operator==(const PointXYZIF & p1, const PointXYZIF & p2) noexcept { using autoware::common::helper_functions::comparisons::rel_eq; const auto epsilon = std::numeric_limits::epsilon(); - return rel_eq(p1.x, p2.x, epsilon) && - rel_eq(p1.y, p2.y, epsilon) && - rel_eq(p1.z, p2.z, epsilon) && - rel_eq(p1.intensity, p2.intensity, epsilon) && + return rel_eq(p1.x, p2.x, epsilon) && rel_eq(p1.y, p2.y, epsilon) && + rel_eq(p1.z, p2.z, epsilon) && rel_eq(p1.intensity, p2.intensity, epsilon) && (p1.id == p2.id); } }; @@ -82,16 +78,12 @@ struct COMMON_PUBLIC PointXYZF float32_t z{0}; uint16_t id{0}; static constexpr uint16_t END_OF_SCAN_ID = 65535u; - friend bool operator==( - const PointXYZF & p1, - const PointXYZF & p2) noexcept + friend bool operator==(const PointXYZF & p1, const PointXYZF & p2) noexcept { using autoware::common::helper_functions::comparisons::rel_eq; const auto epsilon = std::numeric_limits::epsilon(); - return rel_eq(p1.x, p2.x, epsilon) && - rel_eq(p1.y, p2.y, epsilon) && - rel_eq(p1.z, p2.z, epsilon) && - (p1.id == p2.id); + return rel_eq(p1.x, p2.x, epsilon) && rel_eq(p1.y, p2.y, epsilon) && + rel_eq(p1.z, p2.z, epsilon) && (p1.id == p2.id); } }; @@ -101,22 +93,19 @@ struct COMMON_PUBLIC PointXYZI float32_t y{0.0F}; float32_t z{0.0F}; float32_t intensity{0.0F}; - friend bool operator==( - const PointXYZI & p1, - const PointXYZI & p2) noexcept + friend bool operator==(const PointXYZI & p1, const PointXYZI & p2) noexcept { - return - helper_functions::comparisons::rel_eq( - p1.x, p2.x, std::numeric_limits::epsilon()) && + return helper_functions::comparisons::rel_eq( + p1.x, p2.x, std::numeric_limits::epsilon()) && - helper_functions::comparisons::rel_eq( - p1.y, p2.y, std::numeric_limits::epsilon()) && + helper_functions::comparisons::rel_eq( + p1.y, p2.y, std::numeric_limits::epsilon()) && - helper_functions::comparisons::rel_eq( - p1.z, p2.z, std::numeric_limits::epsilon()) && + helper_functions::comparisons::rel_eq( + p1.z, p2.z, std::numeric_limits::epsilon()) && - helper_functions::comparisons::rel_eq( - p1.intensity, p2.intensity, std::numeric_limits::epsilon()); + helper_functions::comparisons::rel_eq( + p1.intensity, p2.intensity, std::numeric_limits::epsilon()); } }; @@ -127,7 +116,7 @@ static constexpr uint16_t POINT_BLOCK_CAPACITY = 512U; // TODO(yunus.caliskan): switch to std::void_t when C++17 is available /// \brief `std::void_t<> implementation -template +template using void_t = void; } // namespace types } // namespace common diff --git a/common/autoware_auto_common/include/common/visibility_control.hpp b/common/autoware_auto_common/include/common/visibility_control.hpp index d2d3d89148d03..0a988d6407dfa 100644 --- a/common/autoware_auto_common/include/common/visibility_control.hpp +++ b/common/autoware_auto_common/include/common/visibility_control.hpp @@ -18,21 +18,21 @@ #define COMMON__VISIBILITY_CONTROL_HPP_ #if defined(_MSC_VER) && defined(_WIN64) - #if defined(COMMON_BUILDING_DLL) || defined(COMMON_EXPORTS) - #define COMMON_PUBLIC __declspec(dllexport) - #define COMMON_LOCAL - #else // defined(COMMON_BUILDING_DLL) || defined(COMMON_EXPORTS) - #define COMMON_PUBLIC __declspec(dllimport) - #define COMMON_LOCAL - #endif // defined(COMMON_BUILDING_DLL) || defined(COMMON_EXPORTS) +#if defined(COMMON_BUILDING_DLL) || defined(COMMON_EXPORTS) +#define COMMON_PUBLIC __declspec(dllexport) +#define COMMON_LOCAL +#else // defined(COMMON_BUILDING_DLL) || defined(COMMON_EXPORTS) +#define COMMON_PUBLIC __declspec(dllimport) +#define COMMON_LOCAL +#endif // defined(COMMON_BUILDING_DLL) || defined(COMMON_EXPORTS) #elif defined(__GNUC__) && defined(__linux__) - #define COMMON_PUBLIC __attribute__((visibility("default"))) - #define COMMON_LOCAL __attribute__((visibility("hidden"))) +#define COMMON_PUBLIC __attribute__((visibility("default"))) +#define COMMON_LOCAL __attribute__((visibility("hidden"))) #elif defined(__GNUC__) && defined(__APPLE__) - #define COMMON_PUBLIC __attribute__((visibility("default"))) - #define COMMON_LOCAL __attribute__((visibility("hidden"))) +#define COMMON_PUBLIC __attribute__((visibility("default"))) +#define COMMON_LOCAL __attribute__((visibility("hidden"))) #else // !(defined(__GNUC__) && defined(__APPLE__)) - #error "Unsupported Build Configuration" +#error "Unsupported Build Configuration" #endif // _MSC_VER #endif // COMMON__VISIBILITY_CONTROL_HPP_ diff --git a/common/autoware_auto_common/include/helper_functions/angle_utils.hpp b/common/autoware_auto_common/include/helper_functions/angle_utils.hpp index 39ee0bf657748..31a33ef2dab47 100644 --- a/common/autoware_auto_common/include/helper_functions/angle_utils.hpp +++ b/common/autoware_auto_common/include/helper_functions/angle_utils.hpp @@ -46,12 +46,16 @@ constexpr auto kDoublePi = 2.0 * M_PI; /// /// @return Angle wrapped to the chosen range. /// -template +template constexpr T wrap_angle(T angle) noexcept { auto help_angle = angle + T(M_PI); - while (help_angle < T{}) {help_angle += T(detail::kDoublePi);} - while (help_angle >= T(detail::kDoublePi)) {help_angle -= T(detail::kDoublePi);} + while (help_angle < T{}) { + help_angle += T(detail::kDoublePi); + } + while (help_angle >= T(detail::kDoublePi)) { + help_angle -= T(detail::kDoublePi); + } return help_angle - T(M_PI); } diff --git a/common/autoware_auto_common/include/helper_functions/bool_comparisons.hpp b/common/autoware_auto_common/include/helper_functions/bool_comparisons.hpp index dda752bf2f2b5..c6bf09365af4f 100644 --- a/common/autoware_auto_common/include/helper_functions/bool_comparisons.hpp +++ b/common/autoware_auto_common/include/helper_functions/bool_comparisons.hpp @@ -36,7 +36,7 @@ namespace comparisons * @brief Convenience method for performing logical exclusive or ops. * @return True iff exactly one of 'a' and 'b' is true. */ -template +template types::bool8_t exclusive_or(const T & a, const T & b) { return static_cast(a) != static_cast(b); diff --git a/common/autoware_auto_common/include/helper_functions/byte_reader.hpp b/common/autoware_auto_common/include/helper_functions/byte_reader.hpp index aa05e5c6a7be4..bef27ea310e26 100644 --- a/common/autoware_auto_common/include/helper_functions/byte_reader.hpp +++ b/common/autoware_auto_common/include/helper_functions/byte_reader.hpp @@ -40,14 +40,13 @@ class ByteReader /// \brief Default constructor, byte reader class /// \param[in] byte_vector A vector to read bytes from explicit ByteReader(const std::vector & byte_vector) - : byte_vector_(byte_vector), - index_(0U) + : byte_vector_(byte_vector), index_(0U) { } // brief Read bytes and store it in the argument passed in big-endian order /// \param[inout] value Read and store the bytes from the vector matching the size of the argument - template + template void read(T & value) { constexpr std::size_t kTypeSize = sizeof(T); @@ -65,10 +64,7 @@ class ByteReader index_ += kTypeSize; } - void skip(std::size_t count) - { - index_ += count; - } + void skip(std::size_t count) { index_ += count; } }; } // namespace helper_functions } // namespace common diff --git a/common/autoware_auto_common/include/helper_functions/crtp.hpp b/common/autoware_auto_common/include/helper_functions/crtp.hpp index 7cba8d0350829..707d522251dc2 100644 --- a/common/autoware_auto_common/include/helper_functions/crtp.hpp +++ b/common/autoware_auto_common/include/helper_functions/crtp.hpp @@ -25,7 +25,7 @@ namespace common { namespace helper_functions { -template +template class crtp { protected: @@ -33,7 +33,7 @@ class crtp { // This is the CRTP pattern for static polymorphism: this is related, static_cast is the only // way to do this - //lint -e{9005, 9176, 1939} NOLINT + // lint -e{9005, 9176, 1939} NOLINT return *static_cast(this); } @@ -41,7 +41,7 @@ class crtp { // This is the CRTP pattern for static polymorphism: this is related, static_cast is the only // way to do this - //lint -e{9005, 9176, 1939} NOLINT + // lint -e{9005, 9176, 1939} NOLINT return *static_cast(this); } }; diff --git a/common/autoware_auto_common/include/helper_functions/float_comparisons.hpp b/common/autoware_auto_common/include/helper_functions/float_comparisons.hpp index fcf1b90c59cf2..de1f459f21d0a 100644 --- a/common/autoware_auto_common/include/helper_functions/float_comparisons.hpp +++ b/common/autoware_auto_common/include/helper_functions/float_comparisons.hpp @@ -39,12 +39,11 @@ namespace comparisons * @pre eps >= 0 * @return True iff 'a' and 'b' are within 'eps' of each other. */ -template +template bool abs_eq(const T & a, const T & b, const T & eps) { static_assert( - std::is_floating_point::value, - "Float comparisons only support floating point types."); + std::is_floating_point::value, "Float comparisons only support floating point types."); return std::abs(a - b) <= eps; } @@ -54,7 +53,7 @@ bool abs_eq(const T & a, const T & b, const T & eps) * @pre eps >= 0 * @return True iff 'a' is less than 'b' minus 'eps'. */ -template +template bool abs_lt(const T & a, const T & b, const T & eps) { return !abs_eq(a, b, eps) && (a < b); @@ -65,7 +64,7 @@ bool abs_lt(const T & a, const T & b, const T & eps) * @pre eps >= 0 * @return True iff 'a' is less than or equal to 'b' plus 'eps'. */ -template +template bool abs_lte(const T & a, const T & b, const T & eps) { return abs_eq(a, b, eps) || (a < b); @@ -76,7 +75,7 @@ bool abs_lte(const T & a, const T & b, const T & eps) * @pre eps >= 0 * @return True iff 'a' is greater than or equal to 'b' minus 'eps'. */ -template +template bool abs_gte(const T & a, const T & b, const T & eps) { return !abs_lt(a, b, eps); @@ -87,7 +86,7 @@ bool abs_gte(const T & a, const T & b, const T & eps) * @pre eps >= 0 * @return True iff 'a' is greater than 'b' minus 'eps'. */ -template +template bool abs_gt(const T & a, const T & b, const T & eps) { return !abs_lte(a, b, eps); @@ -98,7 +97,7 @@ bool abs_gt(const T & a, const T & b, const T & eps) * @pre eps >= 0 * @return True iff 'a' is within 'eps' of zero. */ -template +template bool abs_eq_zero(const T & a, const T & eps) { return abs_eq(a, static_cast(0), eps); @@ -110,12 +109,11 @@ bool abs_eq_zero(const T & a, const T & eps) * @pre rel_eps >= 0 * @return True iff 'a' and 'b' are within relative 'rel_eps' of each other. */ -template +template bool rel_eq(const T & a, const T & b, const T & rel_eps) { static_assert( - std::is_floating_point::value, - "Float comparisons only support floating point types."); + std::is_floating_point::value, "Float comparisons only support floating point types."); const auto delta = std::abs(a - b); const auto larger = std::max(std::abs(a), std::abs(b)); @@ -135,7 +133,7 @@ bool rel_eq(const T & a, const T & b, const T & rel_eps) * @pre rel_eps >= 0 * @return True iff 'a' and 'b' are within 'eps' or 'rel_eps' of each other */ -template +template bool approx_eq(const T & a, const T & b, const T & abs_eps, const T & rel_eps) { const auto are_absolute_eq = abs_eq(a, b, abs_eps); diff --git a/common/autoware_auto_common/include/helper_functions/mahalanobis_distance.hpp b/common/autoware_auto_common/include/helper_functions/mahalanobis_distance.hpp index fde5efca90a23..dcfa65880fdd7 100644 --- a/common/autoware_auto_common/include/helper_functions/mahalanobis_distance.hpp +++ b/common/autoware_auto_common/include/helper_functions/mahalanobis_distance.hpp @@ -32,10 +32,9 @@ namespace helper_functions /// \param mean Single column matrix containing mean of samples received so far /// \param covariance_factor Covariance matrix /// \return Square of mahalanobis distance -template +template types::float32_t calculate_squared_mahalanobis_distance( - const Eigen::Matrix & sample, - const Eigen::Matrix & mean, + const Eigen::Matrix & sample, const Eigen::Matrix & mean, const Eigen::Matrix & covariance_factor) { using Vector = Eigen::Matrix; @@ -59,12 +58,10 @@ types::float32_t calculate_squared_mahalanobis_distance( /// \param mean Single column matrix containing mean of samples received so far /// \param covariance_factor Covariance matrix /// \return Mahalanobis distance -template +template types::float32_t calculate_mahalanobis_distance( - const Eigen::Matrix & sample, - const Eigen::Matrix & mean, - const Eigen::Matrix & covariance_factor -) + const Eigen::Matrix & sample, const Eigen::Matrix & mean, + const Eigen::Matrix & covariance_factor) { return sqrtf(calculate_squared_mahalanobis_distance(sample, mean, covariance_factor)); } diff --git a/common/autoware_auto_common/include/helper_functions/message_adapters.hpp b/common/autoware_auto_common/include/helper_functions/message_adapters.hpp index 90156b152fdd1..fc813f7d5107b 100644 --- a/common/autoware_auto_common/include/helper_functions/message_adapters.hpp +++ b/common/autoware_auto_common/include/helper_functions/message_adapters.hpp @@ -20,6 +20,7 @@ #define HELPER_FUNCTIONS__MESSAGE_ADAPTERS_HPP_ #include + #include namespace autoware @@ -35,11 +36,15 @@ using TimeStamp = builtin_interfaces::msg::Time; /// \brief Helper class to check existance of header file in compile time: /// https://stackoverflow.com/a/16000226/2325407 -template -struct HasHeader : std::false_type {}; +template +struct HasHeader : std::false_type +{ +}; -template -struct HasHeader: std::true_type {}; +template +struct HasHeader : std::true_type +{ +}; /////////// Template declarations @@ -48,7 +53,7 @@ struct HasHeader: std::true_type {}; /// \tparam T Message type. /// \param msg Message. /// \return Frame id of the message. -template +template const std::string & get_frame_id(const T & msg) noexcept; /// Get a reference to the frame id from message. nullptr_t is used to prevent @@ -57,7 +62,7 @@ const std::string & get_frame_id(const T & msg) noexcept; /// \tparam T Message type. /// \param msg Message. /// \return Frame id of the message. -template +template std::string & get_frame_id(T & msg) noexcept; /// Get stamp from message. nullptr_t is used to prevent template ambiguity on @@ -65,7 +70,7 @@ std::string & get_frame_id(T & msg) noexcept; /// \tparam T Message type. /// \param msg Message. /// \return Frame id of the message. -template +template const TimeStamp & get_stamp(const T & msg) noexcept; /// Get a reference to the stamp from message. nullptr_t is used to prevent @@ -74,30 +79,29 @@ const TimeStamp & get_stamp(const T & msg) noexcept; /// \tparam T Message type. /// \param msg Message. /// \return Frame id of the message. -template +template TimeStamp & get_stamp(T & msg) noexcept; - /////////////// Default specializations for message types that contain a header. -template::value, nullptr_t>::type = nullptr> +template ::value, nullptr_t>::type = nullptr> const std::string & get_frame_id(const T & msg) noexcept { return msg.header.frame_id; } -template::value, nullptr_t>::type = nullptr> +template ::value, nullptr_t>::type = nullptr> std::string & get_frame_id(T & msg) noexcept { return msg.header.frame_id; } -template::value, nullptr_t>::type = nullptr> +template ::value, nullptr_t>::type = nullptr> TimeStamp & get_stamp(T & msg) noexcept { return msg.header.stamp; } -template::value, nullptr_t>::type = nullptr> +template ::value, nullptr_t>::type = nullptr> TimeStamp get_stamp(const T & msg) noexcept { return msg.header.stamp; diff --git a/common/autoware_auto_common/include/helper_functions/template_utils.hpp b/common/autoware_auto_common/include/helper_functions/template_utils.hpp index b52be9eae0c59..25a1da4134660 100644 --- a/common/autoware_auto_common/include/helper_functions/template_utils.hpp +++ b/common/autoware_auto_common/include/helper_functions/template_utils.hpp @@ -18,6 +18,7 @@ #define HELPER_FUNCTIONS__TEMPLATE_UTILS_HPP_ #include + #include namespace autoware @@ -30,36 +31,43 @@ namespace helper_functions /// `std::false_type` otherwise. /// \tparam ExpressionTemplate Expression to be checked in compile time /// \tparam T Template parameter to instantiate the expression. -template class ExpressionTemplate, typename T, typename = void> -struct expression_valid : std::false_type {}; +template