diff --git a/.pre-commit-config.yaml b/.pre-commit-config.yaml index 63dc504f61a2b..707471d3cdd81 100644 --- a/.pre-commit-config.yaml +++ b/.pre-commit-config.yaml @@ -3,7 +3,7 @@ ci: repos: - repo: https://github.com/pre-commit/pre-commit-hooks - rev: v4.6.0 + rev: v5.0.0 hooks: - id: check-json - id: check-merge-conflict @@ -18,7 +18,7 @@ repos: args: [--markdown-linebreak-ext=md] - repo: https://github.com/igorshubovych/markdownlint-cli - rev: v0.41.0 + rev: v0.42.0 hooks: - id: markdownlint args: [-c, .markdownlint.yaml, --fix] @@ -49,7 +49,7 @@ repos: - id: shellcheck - repo: https://github.com/scop/pre-commit-shfmt - rev: v3.9.0-1 + rev: v3.10.0-1 hooks: - id: shfmt args: [-w, -s, -i=4] @@ -60,26 +60,26 @@ repos: - id: isort - repo: https://github.com/psf/black - rev: 24.8.0 + rev: 24.10.0 hooks: - id: black args: [--line-length=100] - repo: https://github.com/pre-commit/mirrors-clang-format - rev: v18.1.8 + rev: v19.1.3 hooks: - id: clang-format types_or: [c++, c, cuda] - repo: https://github.com/cpplint/cpplint - rev: 1.6.1 + rev: 2.0.0 hooks: - id: cpplint args: [--quiet] exclude: .cu - repo: https://github.com/python-jsonschema/check-jsonschema - rev: 0.29.2 + rev: 0.29.4 hooks: - id: check-metaschema files: ^.+/schema/.*schema\.json$ diff --git a/perception/autoware_multi_object_tracker/lib/tracker/motion_model/ctrv_motion_model.cpp b/perception/autoware_multi_object_tracker/lib/tracker/motion_model/ctrv_motion_model.cpp index 6f63ecbdce06d..700800e94ecd5 100644 --- a/perception/autoware_multi_object_tracker/lib/tracker/motion_model/ctrv_motion_model.cpp +++ b/perception/autoware_multi_object_tracker/lib/tracker/motion_model/ctrv_motion_model.cpp @@ -276,7 +276,7 @@ bool CTRVMotionModel::predictStateStep(const double dt, KalmanFilter & ekf) cons Eigen::MatrixXd X_next_t(DIM, 1); // predicted state X_next_t(IDX::X) = X_t(IDX::X) + X_t(IDX::VEL) * cos_yaw * dt; // dx = v * cos(yaw) X_next_t(IDX::Y) = X_t(IDX::Y) + X_t(IDX::VEL) * sin_yaw * dt; // dy = v * sin(yaw) - X_next_t(IDX::YAW) = X_t(IDX::YAW) + (X_t(IDX::WZ)) * dt; // dyaw = omega + X_next_t(IDX::YAW) = X_t(IDX::YAW) + (X_t(IDX::WZ))*dt; // dyaw = omega X_next_t(IDX::VEL) = X_t(IDX::VEL); X_next_t(IDX::WZ) = X_t(IDX::WZ); diff --git a/planning/autoware_surround_obstacle_checker/src/node.cpp b/planning/autoware_surround_obstacle_checker/src/node.cpp index da0dd0ec09a26..78b6e4aa09cd5 100644 --- a/planning/autoware_surround_obstacle_checker/src/node.cpp +++ b/planning/autoware_surround_obstacle_checker/src/node.cpp @@ -411,8 +411,8 @@ std::optional SurroundObstacleCheckerNode: auto SurroundObstacleCheckerNode::isStopRequired( const bool is_obstacle_found, const bool is_vehicle_stopped, const State & state, - const std::optional & last_obstacle_found_time, - const double time_threshold) const -> std::pair> + const std::optional & last_obstacle_found_time, const double time_threshold) const + -> std::pair> { if (!is_vehicle_stopped) { return std::make_pair(false, std::nullopt); diff --git a/planning/autoware_surround_obstacle_checker/src/node.hpp b/planning/autoware_surround_obstacle_checker/src/node.hpp index 480a937a4a909..58f55233ed32d 100644 --- a/planning/autoware_surround_obstacle_checker/src/node.hpp +++ b/planning/autoware_surround_obstacle_checker/src/node.hpp @@ -89,8 +89,8 @@ class SurroundObstacleCheckerNode : public rclcpp::Node auto isStopRequired( const bool is_obstacle_found, const bool is_vehicle_stopped, const State & state, - const std::optional & last_obstacle_found_time, - const double time_threshold) const -> std::pair>; + const std::optional & last_obstacle_found_time, const double time_threshold) const + -> std::pair>; // ros mutable tf2_ros::Buffer tf_buffer_{get_clock()}; diff --git a/planning/autoware_surround_obstacle_checker/test/test_surround_obstacle_checker.cpp b/planning/autoware_surround_obstacle_checker/test/test_surround_obstacle_checker.cpp index c5fbb7958208d..1122a37bb2672 100644 --- a/planning/autoware_surround_obstacle_checker/test/test_surround_obstacle_checker.cpp +++ b/planning/autoware_surround_obstacle_checker/test/test_surround_obstacle_checker.cpp @@ -48,8 +48,8 @@ class SurroundObstacleCheckerNodeTest : public ::testing::Test auto isStopRequired( const bool is_obstacle_found, const bool is_vehicle_stopped, const State & state, - const std::optional & last_obstacle_found_time, - const double time_threshold) const -> std::pair> + const std::optional & last_obstacle_found_time, const double time_threshold) const + -> std::pair> { return node_->isStopRequired( is_obstacle_found, is_vehicle_stopped, state, last_obstacle_found_time, time_threshold); diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_traffic_light_module/src/utils.cpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_traffic_light_module/src/utils.cpp index c9eb93abb2e2f..4f0829c901915 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_traffic_light_module/src/utils.cpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_traffic_light_module/src/utils.cpp @@ -32,8 +32,8 @@ auto getOffsetPoint(const Eigen::Vector2d & src, const Eigen::Vector2d & dst, co } auto findNearestCollisionPoint( - const LineString2d & line1, const LineString2d & line2, - const Point2d & origin) -> std::optional + const LineString2d & line1, const LineString2d & line2, const Point2d & origin) + -> std::optional { std::vector collision_points; bg::intersection(line1, line2, collision_points); diff --git a/planning/behavior_velocity_planner/autoware_behavior_velocity_traffic_light_module/src/utils.hpp b/planning/behavior_velocity_planner/autoware_behavior_velocity_traffic_light_module/src/utils.hpp index c6655064d3ffa..ad4ed84cea116 100644 --- a/planning/behavior_velocity_planner/autoware_behavior_velocity_traffic_light_module/src/utils.hpp +++ b/planning/behavior_velocity_planner/autoware_behavior_velocity_traffic_light_module/src/utils.hpp @@ -48,8 +48,8 @@ auto getOffsetPoint(const Eigen::Vector2d & src, const Eigen::Vector2d & dst, co * @return intersection point. if there is no intersection point, return std::nullopt. */ auto findNearestCollisionPoint( - const LineString2d & line1, const LineString2d & line2, - const Point2d & origin) -> std::optional; + const LineString2d & line1, const LineString2d & line2, const Point2d & origin) + -> std::optional; /** * @brief find intersection point between path and stop line and return the point. diff --git a/vehicle/autoware_accel_brake_map_calibrator/README.md b/vehicle/autoware_accel_brake_map_calibrator/README.md index 024c8059a169e..a85e7de98a3ef 100644 --- a/vehicle/autoware_accel_brake_map_calibrator/README.md +++ b/vehicle/autoware_accel_brake_map_calibrator/README.md @@ -212,10 +212,11 @@ Update by Recursive Least Squares(RLS) method using data close enough to each gr #### Parameters Data selection is determined by the following thresholds. -| Name | Default Value | + +| Name | Default Value | | ----------------------- | ------------- | -| velocity_diff_threshold | 0.556 | -| pedal_diff_threshold | 0.03 | +| velocity_diff_threshold | 0.556 | +| pedal_diff_threshold | 0.03 | #### Update formula