Skip to content

Commit

Permalink
style(pre-commit): autofix
Browse files Browse the repository at this point in the history
  • Loading branch information
pre-commit-ci[bot] committed Nov 12, 2024
1 parent 4b9ab29 commit 75b205b
Show file tree
Hide file tree
Showing 7 changed files with 15 additions and 14 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -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);

Expand Down
4 changes: 2 additions & 2 deletions planning/autoware_surround_obstacle_checker/src/node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -411,8 +411,8 @@ std::optional<geometry_msgs::msg::TransformStamped> SurroundObstacleCheckerNode:

auto SurroundObstacleCheckerNode::isStopRequired(
const bool is_obstacle_found, const bool is_vehicle_stopped, const State & state,
const std::optional<rclcpp::Time> & last_obstacle_found_time,
const double time_threshold) const -> std::pair<bool, std::optional<rclcpp::Time>>
const std::optional<rclcpp::Time> & last_obstacle_found_time, const double time_threshold) const
-> std::pair<bool, std::optional<rclcpp::Time>>
{
if (!is_vehicle_stopped) {
return std::make_pair(false, std::nullopt);
Expand Down
4 changes: 2 additions & 2 deletions planning/autoware_surround_obstacle_checker/src/node.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -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<rclcpp::Time> & last_obstacle_found_time,
const double time_threshold) const -> std::pair<bool, std::optional<rclcpp::Time>>;
const std::optional<rclcpp::Time> & last_obstacle_found_time, const double time_threshold) const
-> std::pair<bool, std::optional<rclcpp::Time>>;

// ros
mutable tf2_ros::Buffer tf_buffer_{get_clock()};
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -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<rclcpp::Time> & last_obstacle_found_time,
const double time_threshold) const -> std::pair<bool, std::optional<rclcpp::Time>>
const std::optional<rclcpp::Time> & last_obstacle_found_time, const double time_threshold) const
-> std::pair<bool, std::optional<rclcpp::Time>>
{
return node_->isStopRequired(
is_obstacle_found, is_vehicle_stopped, state, last_obstacle_found_time, time_threshold);
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -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<Point2d>
const LineString2d & line1, const LineString2d & line2, const Point2d & origin)
-> std::optional<Point2d>
{
std::vector<Point2d> collision_points;
bg::intersection(line1, line2, collision_points);
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -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<Point2d>;
const LineString2d & line1, const LineString2d & line2, const Point2d & origin)
-> std::optional<Point2d>;

/**
* @brief find intersection point between path and stop line and return the point.
Expand Down
7 changes: 4 additions & 3 deletions vehicle/autoware_accel_brake_map_calibrator/README.md
Original file line number Diff line number Diff line change
Expand Up @@ -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

Expand Down

0 comments on commit 75b205b

Please sign in to comment.