Skip to content

Commit 941f5e1

Browse files
style(pre-commit): autofix
1 parent 1660b31 commit 941f5e1

File tree

4 files changed

+36
-32
lines changed

4 files changed

+36
-32
lines changed

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

+13-9
Original file line numberDiff line numberDiff line change
@@ -477,9 +477,11 @@ def launch_setup(context, *args, **kwargs):
477477
components.extend(
478478
pipeline.create_single_frame_obstacle_segmentation_components(
479479
input_topic=LaunchConfiguration("input/pointcloud"),
480-
output_topic=pipeline.single_frame_obstacle_seg_output
481-
if pipeline.use_single_frame_filter or pipeline.use_time_series_filter
482-
else pipeline.output_topic,
480+
output_topic=(
481+
pipeline.single_frame_obstacle_seg_output
482+
if pipeline.use_single_frame_filter or pipeline.use_time_series_filter
483+
else pipeline.output_topic
484+
),
483485
)
484486
)
485487

@@ -488,18 +490,20 @@ def launch_setup(context, *args, **kwargs):
488490
components.extend(
489491
pipeline.create_single_frame_outlier_filter_components(
490492
input_topic=pipeline.single_frame_obstacle_seg_output,
491-
output_topic=relay_topic
492-
if pipeline.use_time_series_filter
493-
else pipeline.output_topic,
493+
output_topic=(
494+
relay_topic if pipeline.use_time_series_filter else pipeline.output_topic
495+
),
494496
context=context,
495497
)
496498
)
497499
if pipeline.use_time_series_filter:
498500
components.extend(
499501
pipeline.create_time_series_outlier_filter_components(
500-
input_topic=relay_topic
501-
if pipeline.use_single_frame_filter
502-
else pipeline.single_frame_obstacle_seg_output,
502+
input_topic=(
503+
relay_topic
504+
if pipeline.use_single_frame_filter
505+
else pipeline.single_frame_obstacle_seg_output
506+
),
503507
output_topic=pipeline.output_topic,
504508
)
505509
)

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
{

system/system_monitor/include/system_monitor/gpu_monitor/nvml_gpu_monitor.hpp

+11-11
Original file line numberDiff line numberDiff line change
@@ -29,17 +29,17 @@
2929
#include <string>
3030
#include <vector>
3131

32-
#define reasonToString(X) \
33-
(((X)&nvmlClocksThrottleReasonGpuIdle) ? "GpuIdle" \
34-
: ((X)&nvmlClocksThrottleReasonApplicationsClocksSetting) ? "ApplicationsClocksSetting" \
35-
: ((X)&nvmlClocksThrottleReasonSwPowerCap) ? "SwPowerCap" \
36-
: ((X)&nvmlClocksThrottleReasonHwSlowdown) ? "HwSlowdown" \
37-
: ((X)&nvmlClocksThrottleReasonSyncBoost) ? "SyncBoost" \
38-
: ((X)&nvmlClocksThrottleReasonSwThermalSlowdown) ? "SwThermalSlowdown" \
39-
: ((X)&nvmlClocksThrottleReasonHwThermalSlowdown) ? "HwThermalSlowdown" \
40-
: ((X)&nvmlClocksThrottleReasonHwPowerBrakeSlowdown) ? "HwPowerBrakeSlowdown" \
41-
: ((X)&nvmlClocksThrottleReasonDisplayClockSetting) ? "DisplayClockSetting" \
42-
: "UNKNOWN")
32+
#define reasonToString(X) \
33+
(((X) & nvmlClocksThrottleReasonGpuIdle) ? "GpuIdle" \
34+
: ((X) & nvmlClocksThrottleReasonApplicationsClocksSetting) ? "ApplicationsClocksSetting" \
35+
: ((X) & nvmlClocksThrottleReasonSwPowerCap) ? "SwPowerCap" \
36+
: ((X) & nvmlClocksThrottleReasonHwSlowdown) ? "HwSlowdown" \
37+
: ((X) & nvmlClocksThrottleReasonSyncBoost) ? "SyncBoost" \
38+
: ((X) & nvmlClocksThrottleReasonSwThermalSlowdown) ? "SwThermalSlowdown" \
39+
: ((X) & nvmlClocksThrottleReasonHwThermalSlowdown) ? "HwThermalSlowdown" \
40+
: ((X) & nvmlClocksThrottleReasonHwPowerBrakeSlowdown) ? "HwPowerBrakeSlowdown" \
41+
: ((X) & nvmlClocksThrottleReasonDisplayClockSetting) ? "DisplayClockSetting" \
42+
: "UNKNOWN")
4343

4444
/**
4545
* @brief GPU information

0 commit comments

Comments
 (0)