From 62396a01f85ec73695f333678206b7b6da2dc1f3 Mon Sep 17 00:00:00 2001 From: Kenji Miyake Date: Fri, 15 Apr 2022 12:35:52 +0900 Subject: [PATCH] address cpplint errors Signed-off-by: Kenji Miyake --- .../kinematic_bicycle.snippet.hpp | 6 ++++-- .../autogeneration_code_snippets/linear_tire.snippet.hpp | 6 ++++-- control/trajectory_follower/src/mpc.cpp | 2 +- .../src/lateral_controller_node.cpp | 2 +- .../simple_planning_simulator_core.hpp | 1 + .../simple_planning_simulator_core.cpp | 4 ++-- .../test/test_simple_planning_simulator.cpp | 2 +- 7 files changed, 14 insertions(+), 9 deletions(-) diff --git a/common/motion_common/scripts/autogeneration_code_snippets/kinematic_bicycle.snippet.hpp b/common/motion_common/scripts/autogeneration_code_snippets/kinematic_bicycle.snippet.hpp index e29729ba7e5b4..872cc9595088a 100644 --- a/common/motion_common/scripts/autogeneration_code_snippets/kinematic_bicycle.snippet.hpp +++ b/common/motion_common/scripts/autogeneration_code_snippets/kinematic_bicycle.snippet.hpp @@ -47,5 +47,7 @@ f << dot(x) == u * cos(yaw + beta); f << dot(y) == u * sin(yaw + beta); f << dot(yaw) == (u * sin(beta)) / L_r; f << dot(u) == ax; -#endif // COMMON__MOTION_COMMON__SCRIPTS__AUTOGENERATION_CODE_SNIPPETS__KINEMATIC_BICYCLE_SNIPPET_HPP_ - // // NOLINT + +// clang-format off +#endif // COMMON__MOTION_COMMON__SCRIPTS__AUTOGENERATION_CODE_SNIPPETS__KINEMATIC_BICYCLE_SNIPPET_HPP_ // NOLINT +// clang-format on diff --git a/common/motion_common/scripts/autogeneration_code_snippets/linear_tire.snippet.hpp b/common/motion_common/scripts/autogeneration_code_snippets/linear_tire.snippet.hpp index c09b283ca2ab2..edbdabcdbf58a 100644 --- a/common/motion_common/scripts/autogeneration_code_snippets/linear_tire.snippet.hpp +++ b/common/motion_common/scripts/autogeneration_code_snippets/linear_tire.snippet.hpp @@ -56,5 +56,7 @@ f << dot(v) == ((-u * omega) + ((F_f + F_r) / m)); f << dot(omega) == (((L_f * F_f) - (L_r * F_r)) / I); f << dot(delta) == delta_dot; f << dot(ax) == jx; -#endif // COMMON__MOTION_COMMON__SCRIPTS__AUTOGENERATION_CODE_SNIPPETS__LINEAR_TIRE_SNIPPET_HPP_ - // NOLINT + +// clang-format off +#endif // COMMON__MOTION_COMMON__SCRIPTS__AUTOGENERATION_CODE_SNIPPETS__LINEAR_TIRE_SNIPPET_HPP_ // NOLINT +// clang-format on diff --git a/control/trajectory_follower/src/mpc.cpp b/control/trajectory_follower/src/mpc.cpp index 01cc580eea029..f71bd4e7b65ca 100644 --- a/control/trajectory_follower/src/mpc.cpp +++ b/control/trajectory_follower/src/mpc.cpp @@ -33,7 +33,7 @@ namespace control { namespace trajectory_follower { -using namespace std::chrono_literals; +using namespace std::literals::chrono_literals; using ::motion::motion_common::to_angle; bool8_t MPC::calculateMPC( diff --git a/control/trajectory_follower_nodes/src/lateral_controller_node.cpp b/control/trajectory_follower_nodes/src/lateral_controller_node.cpp index 2964e2f933a9c..4b8e609429da9 100644 --- a/control/trajectory_follower_nodes/src/lateral_controller_node.cpp +++ b/control/trajectory_follower_nodes/src/lateral_controller_node.cpp @@ -34,7 +34,7 @@ namespace trajectory_follower_nodes { namespace { -using namespace std::chrono_literals; +using namespace std::literals::chrono_literals; template void update_param( diff --git a/simulator/simple_planning_simulator/include/simple_planning_simulator/simple_planning_simulator_core.hpp b/simulator/simple_planning_simulator/include/simple_planning_simulator/simple_planning_simulator_core.hpp index 5a55280dd3e11..369b9b63c7465 100644 --- a/simulator/simple_planning_simulator/include/simple_planning_simulator/simple_planning_simulator_core.hpp +++ b/simulator/simple_planning_simulator/include/simple_planning_simulator/simple_planning_simulator_core.hpp @@ -49,6 +49,7 @@ #include #include #include +#include namespace simulation { diff --git a/simulator/simple_planning_simulator/src/simple_planning_simulator/simple_planning_simulator_core.cpp b/simulator/simple_planning_simulator/src/simple_planning_simulator/simple_planning_simulator_core.cpp index 77fcd52934806..2eb04d42acc81 100644 --- a/simulator/simple_planning_simulator/src/simple_planning_simulator/simple_planning_simulator_core.cpp +++ b/simulator/simple_planning_simulator/src/simple_planning_simulator/simple_planning_simulator_core.cpp @@ -31,7 +31,7 @@ #include #include -using namespace std::chrono_literals; +using namespace std::literals::chrono_literals; namespace { @@ -314,7 +314,7 @@ void SimplePlanningSimulator::set_input(const float steer, const float vel, cons using autoware_auto_vehicle_msgs::msg::GearCommand; Eigen::VectorXd input(vehicle_model_ptr_->getDimU()); - // TODO (Watanabe): The definition of the sign of acceleration in REVERSE mode is different + // TODO(Watanabe): The definition of the sign of acceleration in REVERSE mode is different // between .auto and proposal.iv, and will be discussed later. float acc = accel; if (!current_gear_cmd_ptr_) { diff --git a/simulator/simple_planning_simulator/test/test_simple_planning_simulator.cpp b/simulator/simple_planning_simulator/test/test_simple_planning_simulator.cpp index dbeae13297ff7..ef96730583b6c 100644 --- a/simulator/simple_planning_simulator/test/test_simple_planning_simulator.cpp +++ b/simulator/simple_planning_simulator/test/test_simple_planning_simulator.cpp @@ -260,7 +260,7 @@ TEST_P(TestSimplePlanningSimulator, TestIdealSteerVel) rclcpp::shutdown(); } -const std::string VEHICLE_MODEL_LIST[] = { +const char VEHICLE_MODEL_LIST[] = { "IDEAL_STEER_VEL", "IDEAL_STEER_ACC", "IDEAL_STEER_ACC_GEARED", "DELAY_STEER_VEL", "DELAY_STEER_ACC", "DELAY_STEER_ACC_GEARED", };