Skip to content

ci(pre-commit): autoupdate #350

New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Open
wants to merge 4 commits into
base: main
Choose a base branch
from
Open
Show file tree
Hide file tree
Changes from 2 commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
14 changes: 7 additions & 7 deletions .pre-commit-config.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -26,7 +26,7 @@ repos:
args: [--markdown-linebreak-ext=md]

- repo: https://github.com/igorshubovych/markdownlint-cli
rev: v0.43.0
rev: v0.44.0
hooks:
- id: markdownlint
args: [-c, .markdownlint.yaml, --fix]
Expand All @@ -37,7 +37,7 @@ repos:
- id: prettier

- repo: https://github.com/adrienverge/yamllint
rev: v1.35.1
rev: v1.37.0
hooks:
- id: yamllint

Expand All @@ -57,24 +57,24 @@ repos:
- id: shellcheck

- repo: https://github.com/scop/pre-commit-shfmt
rev: v3.10.0-2
rev: v3.11.0-1
hooks:
- id: shfmt
args: [-w, -s, -i=4]

- repo: https://github.com/pycqa/isort
rev: 5.13.2
rev: 6.0.1
hooks:
- id: isort

- repo: https://github.com/psf/black
rev: 24.10.0
rev: 25.1.0
hooks:
- id: black
args: [--line-length=100]

- repo: https://github.com/pre-commit/mirrors-clang-format
rev: v19.1.6
rev: v20.1.0
hooks:
- id: clang-format
types_or: [c++, c, cuda]
Expand All @@ -87,7 +87,7 @@ repos:
exclude: .cu

- repo: https://github.com/python-jsonschema/check-jsonschema
rev: 0.30.0
rev: 0.32.1
hooks:
- id: check-metaschema
files: ^.+/schema/.*schema\.json$
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -124,8 +124,9 @@ bool VehicleArrivalChecker::isVehicleStoppedAtStopPoint(const double stop_durati
return false;
}

return std::abs(autoware::motion_utils::calcSignedArcLength(
trajectory_ptr_->points, p, idx.value())) < th_arrived_distance_m;
return std::abs(
autoware::motion_utils::calcSignedArcLength(trajectory_ptr_->points, p, idx.value())) <
th_arrived_distance_m;
}

void VehicleArrivalChecker::onTrajectory(const Trajectory::ConstSharedPtr msg)
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -146,14 +146,16 @@ class InterpolatorCommonInterface
InterpolationResult>
{
if (bases.size() != values.size()) {
return tl::unexpected(InterpolationFailure{
"base size " + std::to_string(bases.size()) + " and value size " +
std::to_string(values.size()) + " are different"});
return tl::unexpected(
InterpolationFailure{
"base size " + std::to_string(bases.size()) + " and value size " +
std::to_string(values.size()) + " are different"});
}
if (const auto minimum_required = minimum_required_points(); bases.size() < minimum_required) {
return tl::unexpected(InterpolationFailure{
"base size " + std::to_string(bases.size()) + " is less than minimum required " +
std::to_string(minimum_required)});
return tl::unexpected(
InterpolationFailure{
"base size " + std::to_string(bases.size()) + " is less than minimum required " +
std::to_string(minimum_required)});
}
if (!build_impl(std::forward<BaseVectorT>(bases), std::forward<ValueVectorT>(values))) {
return tl::unexpected(
Expand Down
5 changes: 3 additions & 2 deletions common/autoware_trajectory/src/path_point.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -77,8 +77,9 @@ interpolator::InterpolationResult Trajectory<PointType>::build(
if (const auto result = this->longitudinal_velocity_mps().build(
bases_, std::move(longitudinal_velocity_mps_values));
!result) {
return tl::unexpected(interpolator::InterpolationFailure{
"failed to interpolate PathPoint::longitudinal_velocity_mps"});
return tl::unexpected(
interpolator::InterpolationFailure{
"failed to interpolate PathPoint::longitudinal_velocity_mps"});
}
if (const auto result =
this->lateral_velocity_mps().build(bases_, std::move(lateral_velocity_mps_values));
Expand Down
38 changes: 23 additions & 15 deletions common/autoware_trajectory/src/trajectory_point.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -71,9 +71,11 @@ interpolator::InterpolationResult Trajectory<PointType>::build(
if (
!longitudinal_velocity_mps_ || !lateral_velocity_mps_ || !heading_rate_rps_ ||
!acceleration_mps2_ || !front_wheel_angle_rad_ || !rear_wheel_angle_rad_) {
return tl::unexpected(interpolator::InterpolationFailure{
"longitudinal_velocity_mps/lateral_velocity_mps/heading_rate_rps/acceleration_mps2/"
"front_wheel_angle_rad/rear_wheel_angle_rad interpolator are nullptr! check Builder usage"});
return tl::unexpected(
interpolator::InterpolationFailure{
"longitudinal_velocity_mps/lateral_velocity_mps/heading_rate_rps/acceleration_mps2/"
"front_wheel_angle_rad/rear_wheel_angle_rad interpolator are nullptr! check Builder "
"usage"});
}

std::vector<geometry_msgs::msg::Pose> poses;
Expand Down Expand Up @@ -102,38 +104,44 @@ interpolator::InterpolationResult Trajectory<PointType>::build(
if (const auto result = this->longitudinal_velocity_mps().build(
bases_, std::move(longitudinal_velocity_mps_values));
!result) {
return tl::unexpected(interpolator::InterpolationFailure{
"failed to interpolate TrajectoryPoint::longitudinal_velocity_mps"});
return tl::unexpected(
interpolator::InterpolationFailure{
"failed to interpolate TrajectoryPoint::longitudinal_velocity_mps"});
}
if (const auto result =
this->lateral_velocity_mps().build(bases_, std::move(lateral_velocity_mps_values));
!result) {
return tl::unexpected(interpolator::InterpolationFailure{
"failed to interpolate TrajectoryPoint::lateral_velocity_mps"});
return tl::unexpected(
interpolator::InterpolationFailure{
"failed to interpolate TrajectoryPoint::lateral_velocity_mps"});
}
if (const auto result =
this->heading_rate_rps().build(bases_, std::move(heading_rate_rps_values));
!result) {
return tl::unexpected(interpolator::InterpolationFailure{
"failed to interpolate TrajectoryPoint::heading_rate_rps"});
return tl::unexpected(
interpolator::InterpolationFailure{
"failed to interpolate TrajectoryPoint::heading_rate_rps"});
}
if (const auto result =
this->acceleration_mps2().build(bases_, std::move(acceleration_mps2_values));
!result) {
return tl::unexpected(interpolator::InterpolationFailure{
"failed to interpolate TrajectoryPoint::acceleration_mps2"});
return tl::unexpected(
interpolator::InterpolationFailure{
"failed to interpolate TrajectoryPoint::acceleration_mps2"});
}
if (const auto result =
this->front_wheel_angle_rad().build(bases_, std::move(front_wheel_angle_rad_values));
!result) {
return tl::unexpected(interpolator::InterpolationFailure{
"failed to interpolate TrajectoryPoint::front_wheel_angle_rad"});
return tl::unexpected(
interpolator::InterpolationFailure{
"failed to interpolate TrajectoryPoint::front_wheel_angle_rad"});
}
if (const auto result =
this->rear_wheel_angle_rad().build(bases_, std::move(rear_wheel_angle_rad_values));
!result) {
return tl::unexpected(interpolator::InterpolationFailure{
"failed to interpolate TrajectoryPoint::rear_wheel_angle_rad"});
return tl::unexpected(
interpolator::InterpolationFailure{
"failed to interpolate TrajectoryPoint::rear_wheel_angle_rad"});
}

return interpolator::InterpolationSuccess{};
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -27,8 +27,9 @@ using autoware::motion_utils::findNearestIndex;

SimplePurePursuitNode::SimplePurePursuitNode(const rclcpp::NodeOptions & node_options)
: Node("simple_pure_pursuit", node_options),
pub_control_command_(create_publisher<autoware_control_msgs::msg::Control>(
"~/output/control_command", rclcpp::QoS(1).transient_local())),
pub_control_command_(
create_publisher<autoware_control_msgs::msg::Control>(
"~/output/control_command", rclcpp::QoS(1).transient_local())),
vehicle_info_(autoware::vehicle_info_utils::VehicleInfoUtils(*this).getVehicleInfo()),
lookahead_gain_(declare_parameter<float>("lookahead_gain")),
lookahead_min_distance_(declare_parameter<float>("lookahead_min_distance")),
Expand Down
14 changes: 8 additions & 6 deletions perception/autoware_ground_filter/src/node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -220,17 +220,19 @@ void GroundFilterComponent::subscribe()
message_filters::Synchronizer<message_filters::sync_policies::ApproximateTime<
sensor_msgs::msg::PointCloud2, pcl_msgs::msg::PointIndices>>>(max_queue_size_);
sync_input_indices_a_->connectInput(sub_input_filter_, sub_indices_filter_);
sync_input_indices_a_->registerCallback(std::bind(
&GroundFilterComponent::faster_input_indices_callback, this, std::placeholders::_1,
std::placeholders::_2));
sync_input_indices_a_->registerCallback(
std::bind(
&GroundFilterComponent::faster_input_indices_callback, this, std::placeholders::_1,
std::placeholders::_2));
} else {
sync_input_indices_e_ =
std::make_shared<message_filters::Synchronizer<message_filters::sync_policies::ExactTime<
sensor_msgs::msg::PointCloud2, pcl_msgs::msg::PointIndices>>>(max_queue_size_);
sync_input_indices_e_->connectInput(sub_input_filter_, sub_indices_filter_);
sync_input_indices_e_->registerCallback(std::bind(
&GroundFilterComponent::faster_input_indices_callback, this, std::placeholders::_1,
std::placeholders::_2));
sync_input_indices_e_->registerCallback(
std::bind(
&GroundFilterComponent::faster_input_indices_callback, this, std::placeholders::_1,
std::placeholders::_2));
}
} else {
std::function<void(const sensor_msgs::msg::PointCloud2::ConstSharedPtr msg)> cb = std::bind(
Expand Down
10 changes: 6 additions & 4 deletions planning/autoware_path_generator/src/utils.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -460,13 +460,15 @@ std::vector<geometry_msgs::msg::Point> crop_line_string(
s += segment_length;
continue;
}
cropped_line_string.push_back(lanelet::utils::conversion::toGeomMsgPt(
lanelet::geometry::interpolatedPointAtDistance(segment, s_start - s)));
cropped_line_string.push_back(
lanelet::utils::conversion::toGeomMsgPt(
lanelet::geometry::interpolatedPointAtDistance(segment, s_start - s)));
}
s += segment_length;
if (s >= s_end) {
cropped_line_string.push_back(lanelet::utils::conversion::toGeomMsgPt(
lanelet::geometry::interpolatedPointAtDistance(segment, s_end - s)));
cropped_line_string.push_back(
lanelet::utils::conversion::toGeomMsgPt(
lanelet::geometry::interpolatedPointAtDistance(segment, s_end - s)));
break;
}
cropped_line_string.push_back(lanelet::utils::conversion::toGeomMsgPt(*it));
Expand Down
5 changes: 3 additions & 2 deletions planning/autoware_route_handler/src/route_handler.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -1702,8 +1702,9 @@ void RouteHandler::removeOverlappedCenterlineWithWaypoints(
int target_lanelet_sequence_index = static_cast<int>(piecewise_waypoints_lanelet_sequence_index);
while (isIndexWithinVector(lanelet_sequence, target_lanelet_sequence_index)) {
auto & target_piecewise_ref_points = piecewise_ref_points_vec.at(target_lanelet_sequence_index);
const double target_lanelet_arc_length = boost::geometry::length(lanelet::utils::to2D(
lanelet_sequence.at(target_lanelet_sequence_index).centerline().basicLineString()));
const double target_lanelet_arc_length = boost::geometry::length(
lanelet::utils::to2D(
lanelet_sequence.at(target_lanelet_sequence_index).centerline().basicLineString()));

// search overlapped ref points in the target lanelet
std::vector<size_t> overlapped_ref_points_indices{};
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -82,9 +82,10 @@ void StopLineModuleManager::launchNewModules(
getStopLinesWithLaneIdOnPath(path, planner_data_->route_handler_->getLaneletMapPtr())) {
const auto module_id = stop_line_with_lane_id.first.id();
if (!isModuleRegistered(module_id)) {
registerModule(std::make_shared<StopLineModule>(
module_id, stop_line_with_lane_id.first, planner_param_,
logger_.get_child("stop_line_module"), clock_, time_keeper_, planning_factor_interface_));
registerModule(
std::make_shared<StopLineModule>(
module_id, stop_line_with_lane_id.first, planner_param_,
logger_.get_child("stop_line_module"), clock_, time_keeper_, planning_factor_interface_));
}
}
}
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -126,8 +126,9 @@ double calc_time_to_reach_collision_point(
const double min_velocity_to_reach_collision_point)
{
const double dist_from_ego_to_obstacle =
std::abs(autoware::motion_utils::calcSignedArcLength(
traj_points, odometry.pose.pose.position, collision_point)) -
std::abs(
autoware::motion_utils::calcSignedArcLength(
traj_points, odometry.pose.pose.position, collision_point)) -
dist_to_bumper;
return dist_from_ego_to_obstacle /
std::max(min_velocity_to_reach_collision_point, std::abs(odometry.twist.twist.linear.x));
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -244,17 +244,17 @@ std::vector<Polygon2d> create_one_step_polygons(
idx_poly,
autoware_utils::to_footprint(pose, front_length, rear_length, vehicle_width).outer());
boost::geometry::append(
idx_poly,
autoware_utils::from_msg(autoware_utils::calc_offset_pose(
pose, front_length, vehicle_width * 0.5 + lat_margin, 0.0)
.position)
.to_2d());
idx_poly, autoware_utils::from_msg(
autoware_utils::calc_offset_pose(
pose, front_length, vehicle_width * 0.5 + lat_margin, 0.0)
.position)
.to_2d());
boost::geometry::append(
idx_poly,
autoware_utils::from_msg(autoware_utils::calc_offset_pose(
pose, front_length, -vehicle_width * 0.5 - lat_margin, 0.0)
.position)
.to_2d());
idx_poly, autoware_utils::from_msg(
autoware_utils::calc_offset_pose(
pose, front_length, -vehicle_width * 0.5 - lat_margin, 0.0)
.position)
.to_2d());
} else {
boost::geometry::append(
idx_poly, autoware_utils::to_footprint(
Expand Down
Loading