Skip to content

Commit 00e12c4

Browse files
awf-autoware-bot[bot]M. Fatih Cırıt
and
M. Fatih Cırıt
authored
ci(pre-commit): autoupdate (autowarefoundation#7499)
Signed-off-by: github-actions[bot] <41898282+github-actions[bot]@users.noreply.github.com> Co-authored-by: M. Fatih Cırıt <mfc@leodrive.ai>
1 parent acac821 commit 00e12c4

File tree

20 files changed

+95
-90
lines changed

20 files changed

+95
-90
lines changed

.markdownlint.yaml

+1
Original file line numberDiff line numberDiff line change
@@ -7,5 +7,6 @@ MD029:
77
style: ordered
88
MD033: false
99
MD041: false
10+
MD045: false
1011
MD046: false
1112
MD049: false

.pre-commit-config.yaml

+10-10
Original file line numberDiff line numberDiff line change
@@ -3,7 +3,7 @@ ci:
33

44
repos:
55
- repo: https://github.com/pre-commit/pre-commit-hooks
6-
rev: v4.4.0
6+
rev: v4.6.0
77
hooks:
88
- id: check-json
99
- id: check-merge-conflict
@@ -18,18 +18,18 @@ repos:
1818
args: [--markdown-linebreak-ext=md]
1919

2020
- repo: https://github.com/igorshubovych/markdownlint-cli
21-
rev: v0.33.0
21+
rev: v0.41.0
2222
hooks:
2323
- id: markdownlint
2424
args: [-c, .markdownlint.yaml, --fix]
2525

2626
- repo: https://github.com/pre-commit/mirrors-prettier
27-
rev: v3.0.0-alpha.6
27+
rev: v4.0.0-alpha.8
2828
hooks:
2929
- id: prettier
3030

3131
- repo: https://github.com/adrienverge/yamllint
32-
rev: v1.30.0
32+
rev: v1.35.1
3333
hooks:
3434
- id: yamllint
3535

@@ -44,29 +44,29 @@ repos:
4444
- id: sort-package-xml
4545

4646
- repo: https://github.com/shellcheck-py/shellcheck-py
47-
rev: v0.9.0.2
47+
rev: v0.10.0.1
4848
hooks:
4949
- id: shellcheck
5050

5151
- repo: https://github.com/scop/pre-commit-shfmt
52-
rev: v3.6.0-2
52+
rev: v3.8.0-1
5353
hooks:
5454
- id: shfmt
5555
args: [-w, -s, -i=4]
5656

5757
- repo: https://github.com/pycqa/isort
58-
rev: 5.12.0
58+
rev: 5.13.2
5959
hooks:
6060
- id: isort
6161

6262
- repo: https://github.com/psf/black
63-
rev: 23.3.0
63+
rev: 24.4.2
6464
hooks:
6565
- id: black
6666
args: [--line-length=100]
6767

6868
- repo: https://github.com/pre-commit/mirrors-clang-format
69-
rev: v16.0.0
69+
rev: v18.1.6
7070
hooks:
7171
- id: clang-format
7272
types_or: [c++, c, cuda]
@@ -79,7 +79,7 @@ repos:
7979
exclude: .cu
8080

8181
- repo: https://github.com/python-jsonschema/check-jsonschema
82-
rev: 0.23.2
82+
rev: 0.28.5
8383
hooks:
8484
- id: check-metaschema
8585
files: ^.+/schema/.*schema\.json$

common/component_interface_utils/include/component_interface_utils/rclcpp.hpp

+1-2
Original file line numberDiff line numberDiff line change
@@ -94,8 +94,7 @@ class NodeAdaptor
9494
C & cli, S & srv, CallbackGroup group, std::optional<double> timeout = std::nullopt) const
9595
{
9696
init_cli(cli);
97-
init_srv(
98-
srv, [cli, timeout](auto req, auto res) { *res = *cli->call(req, timeout); }, group);
97+
init_srv(srv, [cli, timeout](auto req, auto res) { *res = *cli->call(req, timeout); }, group);
9998
}
10099

101100
/// Create a subscription wrapper.

common/motion_utils/test/src/trajectory/test_trajectory.cpp

+1-2
Original file line numberDiff line numberDiff line change
@@ -5365,8 +5365,7 @@ TEST(Trajectory, removeFirstInvalidOrientationPoints)
53655365
auto traj = generateTestTrajectory<Trajectory>(10, 1.0, 1.0);
53665366

53675367
// no invalid points
5368-
testRemoveInvalidOrientationPoints(
5369-
traj, [](Trajectory &) {}, traj.points.size());
5368+
testRemoveInvalidOrientationPoints(traj, [](Trajectory &) {}, traj.points.size());
53705369

53715370
// invalid point at the end
53725371
testRemoveInvalidOrientationPoints(

control/autoware_pid_longitudinal_controller/README.md

+2-2
Original file line numberDiff line numberDiff line change
@@ -212,8 +212,8 @@ AutonomouStuff Lexus RX 450h for under 40 km/h driving.
212212
| max_d_effort | double | max value of acceleration with d gain | 0.0 |
213213
| min_d_effort | double | min value of acceleration with d gain | 0.0 |
214214
| lpf_vel_error_gain | double | gain of low-pass filter for velocity error | 0.9 |
215-
| enable_integration_at_low_speed | bool | Whether to enable integration of acceleration errors when the vehicle speed is lower than `current_vel_threshold_pid_integration` or not. |
216-
| current_vel_threshold_pid_integration | double | Velocity error is integrated for I-term only when the absolute value of current velocity is larger than this parameter. [m/s] |
215+
| enable_integration_at_low_speed | bool | Whether to enable integration of acceleration errors when the vehicle speed is lower than `current_vel_threshold_pid_integration` or not. | false |
216+
| current_vel_threshold_pid_integration | double | Velocity error is integrated for I-term only when the absolute value of current velocity is larger than this parameter. [m/s] | 0.5 |
217217
| time_threshold_before_pid_integration | double | How much time without the vehicle moving must past to enable PID error integration. [s] | 5.0 |
218218
| brake_keeping_acc | double | If `enable_brake_keeping_before_stop` is true, a certain acceleration is kept during DRIVE state before the ego stops [m/s^2] See [Brake keeping](#brake-keeping). | 0.2 |
219219

control/autoware_smart_mpc_trajectory_follower/autoware_smart_mpc_trajectory_follower/scripts/drive_controller.py

+6-6
Original file line numberDiff line numberDiff line change
@@ -560,12 +560,12 @@ def update_input_queue(
560560
np.array(time_stamp), np.array(steer_history)
561561
)
562562

563-
self.acc_input_queue[
564-
drive_functions.acc_ctrl_queue_size - acc_num :
565-
] = acc_interpolate(time_stamp_acc)
566-
self.steer_input_queue[
567-
drive_functions.steer_ctrl_queue_size - steer_num :
568-
] = steer_interpolate(time_stamp_steer)
563+
self.acc_input_queue[drive_functions.acc_ctrl_queue_size - acc_num :] = (
564+
acc_interpolate(time_stamp_acc)
565+
)
566+
self.steer_input_queue[drive_functions.steer_ctrl_queue_size - steer_num :] = (
567+
steer_interpolate(time_stamp_steer)
568+
)
569569

570570
if (
571571
acc_num == drive_functions.acc_ctrl_queue_size

evaluator/kinematic_evaluator/include/kinematic_evaluator/parameters.hpp

+1-1
Original file line numberDiff line numberDiff line change
@@ -27,7 +27,7 @@ namespace kinematic_diagnostics
2727
struct Parameters
2828
{
2929
std::array<bool, static_cast<size_t>(Metric::SIZE)> metrics{}; // default values to false
30-
}; // struct Parameters
30+
}; // struct Parameters
3131

3232
} // namespace kinematic_diagnostics
3333

evaluator/kinematic_evaluator/test/test_kinematic_evaluator_node.cpp

+1-3
Original file line numberDiff line numberDiff line change
@@ -67,9 +67,7 @@ class EvalTest : public ::testing::Test
6767
tf_broadcaster_ = std::make_unique<tf2_ros::TransformBroadcaster>(dummy_node);
6868
}
6969

70-
~EvalTest() override
71-
{ /*rclcpp::shutdown();*/
72-
}
70+
~EvalTest() override { /*rclcpp::shutdown();*/ }
7371

7472
void setTargetMetric(kinematic_diagnostics::Metric metric)
7573
{

evaluator/localization_evaluator/include/localization_evaluator/parameters.hpp

+1-1
Original file line numberDiff line numberDiff line change
@@ -27,7 +27,7 @@ namespace localization_diagnostics
2727
struct Parameters
2828
{
2929
std::array<bool, static_cast<size_t>(Metric::SIZE)> metrics{}; // default values to false
30-
}; // struct Parameters
30+
}; // struct Parameters
3131

3232
} // namespace localization_diagnostics
3333

launch/tier4_perception_launch/launch/obstacle_segmentation/ground_segmentation/ground_segmentation.launch.py

+13-9
Original file line numberDiff line numberDiff line change
@@ -501,9 +501,11 @@ def launch_setup(context, *args, **kwargs):
501501
components.extend(
502502
pipeline.create_single_frame_obstacle_segmentation_components(
503503
input_topic=LaunchConfiguration("input/pointcloud"),
504-
output_topic=pipeline.single_frame_obstacle_seg_output
505-
if pipeline.use_single_frame_filter or pipeline.use_time_series_filter
506-
else pipeline.output_topic,
504+
output_topic=(
505+
pipeline.single_frame_obstacle_seg_output
506+
if pipeline.use_single_frame_filter or pipeline.use_time_series_filter
507+
else pipeline.output_topic
508+
),
507509
)
508510
)
509511

@@ -512,18 +514,20 @@ def launch_setup(context, *args, **kwargs):
512514
components.extend(
513515
pipeline.create_single_frame_outlier_filter_components(
514516
input_topic=pipeline.single_frame_obstacle_seg_output,
515-
output_topic=relay_topic
516-
if pipeline.use_time_series_filter
517-
else pipeline.output_topic,
517+
output_topic=(
518+
relay_topic if pipeline.use_time_series_filter else pipeline.output_topic
519+
),
518520
context=context,
519521
)
520522
)
521523
if pipeline.use_time_series_filter:
522524
components.extend(
523525
pipeline.create_time_series_outlier_filter_components(
524-
input_topic=relay_topic
525-
if pipeline.use_single_frame_filter
526-
else pipeline.single_frame_obstacle_seg_output,
526+
input_topic=(
527+
relay_topic
528+
if pipeline.use_single_frame_filter
529+
else pipeline.single_frame_obstacle_seg_output
530+
),
527531
output_topic=pipeline.output_topic,
528532
)
529533
)

perception/image_projection_based_fusion/src/roi_pointcloud_fusion/node.cpp

+4-4
Original file line numberDiff line numberDiff line change
@@ -42,14 +42,14 @@ RoiPointCloudFusionNode::RoiPointCloudFusionNode(const rclcpp::NodeOptions & opt
4242
cluster_debug_pub_ = this->create_publisher<sensor_msgs::msg::PointCloud2>("debug/clusters", 1);
4343
}
4444

45-
void RoiPointCloudFusionNode::preprocess(__attribute__((unused))
46-
sensor_msgs::msg::PointCloud2 & pointcloud_msg)
45+
void RoiPointCloudFusionNode::preprocess(
46+
__attribute__((unused)) sensor_msgs::msg::PointCloud2 & pointcloud_msg)
4747
{
4848
return;
4949
}
5050

51-
void RoiPointCloudFusionNode::postprocess(__attribute__((unused))
52-
sensor_msgs::msg::PointCloud2 & pointcloud_msg)
51+
void RoiPointCloudFusionNode::postprocess(
52+
__attribute__((unused)) sensor_msgs::msg::PointCloud2 & pointcloud_msg)
5353
{
5454
const auto objects_sub_count = pub_objects_ptr_->get_subscription_count() +
5555
pub_objects_ptr_->get_intra_process_subscription_count();

perception/lidar_centerpoint/README.md

+1-1
Original file line numberDiff line numberDiff line change
@@ -349,4 +349,4 @@ Special thanks to [Deepen AI](https://www.deepen.ai/) for providing their 3D Ann
349349
_The nuScenes dataset is released publicly for non-commercial use under the Creative
350350
Commons Attribution-NonCommercial-ShareAlike 4.0 International Public License.
351351
Additional Terms of Use can be found at <https://www.nuscenes.org/terms-of-use>.
352-
To inquire about a commercial license please contact nuscenes@motional.com._
352+
To inquire about a commercial license please contact <nuscenes@motional.com>._

perception/probabilistic_occupancy_grid_map/launch/pointcloud_based_occupancy_grid_map.launch.py

+10-6
Original file line numberDiff line numberDiff line change
@@ -101,15 +101,19 @@ def launch_setup(context, *args, **kwargs):
101101
remappings=[
102102
(
103103
"~/input/obstacle_pointcloud",
104-
LaunchConfiguration("input/obstacle_pointcloud")
105-
if not downsample_input_pointcloud
106-
else "obstacle/downsample/pointcloud",
104+
(
105+
LaunchConfiguration("input/obstacle_pointcloud")
106+
if not downsample_input_pointcloud
107+
else "obstacle/downsample/pointcloud"
108+
),
107109
),
108110
(
109111
"~/input/raw_pointcloud",
110-
LaunchConfiguration("input/raw_pointcloud")
111-
if not downsample_input_pointcloud
112-
else "raw/downsample/pointcloud",
112+
(
113+
LaunchConfiguration("input/raw_pointcloud")
114+
if not downsample_input_pointcloud
115+
else "raw/downsample/pointcloud"
116+
),
113117
),
114118
("~/output/occupancy_grid_map", LaunchConfiguration("output")),
115119
],

perception/raindrop_cluster_filter/raindrop_cluster_filter.md

+16-16
Original file line numberDiff line numberDiff line change
@@ -26,22 +26,22 @@ Mainly this focuses on filtering out unknown objects with very low intensity poi
2626

2727
### Core Parameters
2828

29-
| Name | Type | Default Value | Description |
30-
| --------------------------------- | ----- | ------------------------------------------------------- | --------------------------------------------- |
31-
| `filter_target_label.UNKNOWN` | bool | false | If true, unknown objects are filtered. |
32-
| `filter_target_label.CAR` | bool | false | If true, car objects are filtered. |
33-
| `filter_target_label.TRUCK` | bool | false | If true, truck objects are filtered. |
34-
| `filter_target_label.BUS` | bool | false | If true, bus objects are filtered. |
35-
| `filter_target_label.TRAILER` | bool | false | If true, trailer objects are filtered. |
36-
| `filter_target_label.MOTORCYCLE` | bool | false | If true, motorcycle objects are filtered. |
37-
| `filter_target_label.BICYCLE` | bool | false | If true, bicycle objects are filtered. |
38-
| `filter_target_label.PEDESTRIAN` | bool | false | If true, pedestrian objects are filtered. |
39-
| `max_x` | float | 60.00 | Maximum of x of the filter effective range |
40-
| `min_x` | float | -20.00 | Minimum of x of the filter effective range |
41-
| `max_y` | float | 20.00 | Maximum of y of the filter effective range |
42-
| `min_y` | float | -20.00 | Minium of y of the filter effective range |
43-
| `intensity_threshold` | float | 1.0 | The threshold of average intensity for filter |
44-
| `existence_probability_threshold` | float | The existence probability threshold to apply the filter |
29+
| Name | Type | Default Value | Description |
30+
| --------------------------------- | ----- | ------------- | ------------------------------------------------------- |
31+
| `filter_target_label.UNKNOWN` | bool | false | If true, unknown objects are filtered. |
32+
| `filter_target_label.CAR` | bool | false | If true, car objects are filtered. |
33+
| `filter_target_label.TRUCK` | bool | false | If true, truck objects are filtered. |
34+
| `filter_target_label.BUS` | bool | false | If true, bus objects are filtered. |
35+
| `filter_target_label.TRAILER` | bool | false | If true, trailer objects are filtered. |
36+
| `filter_target_label.MOTORCYCLE` | bool | false | If true, motorcycle objects are filtered. |
37+
| `filter_target_label.BICYCLE` | bool | false | If true, bicycle objects are filtered. |
38+
| `filter_target_label.PEDESTRIAN` | bool | false | If true, pedestrian objects are filtered. |
39+
| `max_x` | float | 60.00 | Maximum of x of the filter effective range |
40+
| `min_x` | float | -20.00 | Minimum of x of the filter effective range |
41+
| `max_y` | float | 20.00 | Maximum of y of the filter effective range |
42+
| `min_y` | float | -20.00 | Minium of y of the filter effective range |
43+
| `intensity_threshold` | float | 1.0 | The threshold of average intensity for filter |
44+
| `existence_probability_threshold` | float | 0.2 | The existence probability threshold to apply the filter |
4545

4646
## Assumptions / Known limits
4747

perception/tensorrt_yolox/src/tensorrt_yolox.cpp

+1-1
Original file line numberDiff line numberDiff line change
@@ -956,7 +956,7 @@ void TrtYoloX::generateYoloxProposals(
956956
objects.push_back(obj);
957957
}
958958
} // class loop
959-
} // point anchor loop
959+
} // point anchor loop
960960
}
961961

962962
void TrtYoloX::qsortDescentInplace(ObjectArray & face_objects, int left, int right) const

planning/sampling_based_planner/autoware_path_sampler/src/node.cpp

+2-2
Original file line numberDiff line numberDiff line change
@@ -423,8 +423,8 @@ std::vector<autoware::sampler_common::Path> PathSampler::generateCandidatesFromP
423423
size_t reuse_idx = 0;
424424
for (reuse_idx = 0; reuse_idx + 1 < prev_path_->lengths.size() &&
425425
prev_path_->lengths[reuse_idx] < reuse_length;
426-
++reuse_idx)
427-
;
426+
++reuse_idx) {
427+
}
428428
if (reuse_idx == 0UL) continue;
429429
const auto reused_path = *prev_path_->subset(0UL, reuse_idx);
430430
reuse_state.curvature = reused_path.curvatures.back();

sensing/pointcloud_preprocessor/src/passthrough_filter/passthrough_uint16.cpp

+1-1
Original file line numberDiff line numberDiff line change
@@ -242,7 +242,7 @@ void pcl::PassThroughUInt16<pcl::PCLPointCloud2>::applyFilter(PCLPointCloud2 & o
242242
nr_p++;
243243
}
244244
output.width = nr_p;
245-
} // !keep_organized_
245+
} // !keep_organized_
246246
} else { // No distance filtering, process all data.
247247
// No need to check for is_organized here as we did it above
248248
for (int cp = 0; cp < nr_points; ++cp, xyz_offset += input_->point_step) {

sensing/tier4_pcl_extensions/include/tier4_pcl_extensions/voxel_grid_nearest_centroid_impl.hpp

+2-2
Original file line numberDiff line numberDiff line change
@@ -221,7 +221,7 @@ void pcl::VoxelGridNearestCentroid<PointT>::applyFilter(PointCloud & output)
221221
&rgb, reinterpret_cast<const char *>(&input_->points[cp]) + rgba_index, sizeof(int));
222222
centroid[centroid_size - 3] = static_cast<float>((rgb >> 16) & 0x0000ff);
223223
centroid[centroid_size - 2] = static_cast<float>((rgb >> 8) & 0x0000ff);
224-
centroid[centroid_size - 1] = static_cast<float>((rgb)&0x0000ff);
224+
centroid[centroid_size - 1] = static_cast<float>((rgb) & 0x0000ff);
225225
}
226226
pcl::for_each_type<FieldList>(
227227
NdCopyPointEigenFunctor<PointT>(input_->points[cp], centroid));
@@ -272,7 +272,7 @@ void pcl::VoxelGridNearestCentroid<PointT>::applyFilter(PointCloud & output)
272272
&rgb, reinterpret_cast<const char *>(&input_->points[cp]) + rgba_index, sizeof(int));
273273
centroid[centroid_size - 3] = static_cast<float>((rgb >> 16) & 0x0000ff);
274274
centroid[centroid_size - 2] = static_cast<float>((rgb >> 8) & 0x0000ff);
275-
centroid[centroid_size - 1] = static_cast<float>((rgb)&0x0000ff);
275+
centroid[centroid_size - 1] = static_cast<float>((rgb) & 0x0000ff);
276276
}
277277
pcl::for_each_type<FieldList>(
278278
NdCopyPointEigenFunctor<PointT>(input_->points[cp], centroid));

system/system_monitor/include/system_monitor/cpu_monitor/raspi_cpu_monitor.hpp

+10-10
Original file line numberDiff line numberDiff line change
@@ -35,16 +35,16 @@
3535

3636
#define raspiThermalThrottlingMask (raspiCurrentlyThrottled | raspiSoftTemperatureLimitActive)
3737

38-
#define throttledToString(X) \
39-
(((X)&raspiUnderVoltageDetected) ? "Under-voltage detected" \
40-
: ((X)&raspiArmFrequencyCapped) ? "Arm frequency capped" \
41-
: ((X)&raspiCurrentlyThrottled) ? "Currently throttled" \
42-
: ((X)&raspiSoftTemperatureLimitActive) ? "Soft temperature limit active" \
43-
: ((X)&raspiUnderVoltageHasOccurred) ? "Under-voltage has occurred" \
44-
: ((X)&raspiArmFrequencyCappedHasOccurred) ? "Arm frequency capped has occurred" \
45-
: ((X)&raspiThrottlingHasOccurred) ? "Throttling has occurred" \
46-
: ((X)&raspiSoftTemperatureLimitHasOccurred) ? "Soft temperature limit has occurred" \
47-
: "UNKNOWN")
38+
#define throttledToString(X) \
39+
(((X) & raspiUnderVoltageDetected) ? "Under-voltage detected" \
40+
: ((X) & raspiArmFrequencyCapped) ? "Arm frequency capped" \
41+
: ((X) & raspiCurrentlyThrottled) ? "Currently throttled" \
42+
: ((X) & raspiSoftTemperatureLimitActive) ? "Soft temperature limit active" \
43+
: ((X) & raspiUnderVoltageHasOccurred) ? "Under-voltage has occurred" \
44+
: ((X) & raspiArmFrequencyCappedHasOccurred) ? "Arm frequency capped has occurred" \
45+
: ((X) & raspiThrottlingHasOccurred) ? "Throttling has occurred" \
46+
: ((X) & raspiSoftTemperatureLimitHasOccurred) ? "Soft temperature limit has occurred" \
47+
: "UNKNOWN")
4848

4949
class CPUMonitor : public CPUMonitorBase
5050
{

0 commit comments

Comments
 (0)