diff --git a/.markdownlint.yaml b/.markdownlint.yaml index babaaa1f1586d..7b7359fe0cdc4 100644 --- a/.markdownlint.yaml +++ b/.markdownlint.yaml @@ -7,5 +7,6 @@ MD029: style: ordered MD033: false MD041: false +MD045: false MD046: false MD049: false diff --git a/.pre-commit-config.yaml b/.pre-commit-config.yaml index a5ca7b6cf37fa..823ff516c1dc7 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.4.0 + rev: v4.6.0 hooks: - id: check-json - id: check-merge-conflict @@ -18,18 +18,18 @@ repos: args: [--markdown-linebreak-ext=md] - repo: https://github.com/igorshubovych/markdownlint-cli - rev: v0.33.0 + rev: v0.41.0 hooks: - id: markdownlint args: [-c, .markdownlint.yaml, --fix] - repo: https://github.com/pre-commit/mirrors-prettier - rev: v3.0.0-alpha.6 + rev: v4.0.0-alpha.8 hooks: - id: prettier - repo: https://github.com/adrienverge/yamllint - rev: v1.30.0 + rev: v1.35.1 hooks: - id: yamllint @@ -44,29 +44,29 @@ repos: - id: sort-package-xml - repo: https://github.com/shellcheck-py/shellcheck-py - rev: v0.9.0.2 + rev: v0.10.0.1 hooks: - id: shellcheck - repo: https://github.com/scop/pre-commit-shfmt - rev: v3.6.0-2 + rev: v3.8.0-1 hooks: - id: shfmt args: [-w, -s, -i=4] - repo: https://github.com/pycqa/isort - rev: 5.12.0 + rev: 5.13.2 hooks: - id: isort - repo: https://github.com/psf/black - rev: 23.3.0 + rev: 24.4.2 hooks: - id: black args: [--line-length=100] - repo: https://github.com/pre-commit/mirrors-clang-format - rev: v16.0.0 + rev: v18.1.6 hooks: - id: clang-format types_or: [c++, c, cuda] @@ -79,7 +79,7 @@ repos: exclude: .cu - repo: https://github.com/python-jsonschema/check-jsonschema - rev: 0.23.2 + rev: 0.28.5 hooks: - id: check-metaschema files: ^.+/schema/.*schema\.json$ diff --git a/common/component_interface_utils/include/component_interface_utils/rclcpp.hpp b/common/component_interface_utils/include/component_interface_utils/rclcpp.hpp index 32b6b6ca2565c..8099bea36784e 100644 --- a/common/component_interface_utils/include/component_interface_utils/rclcpp.hpp +++ b/common/component_interface_utils/include/component_interface_utils/rclcpp.hpp @@ -94,8 +94,7 @@ class NodeAdaptor C & cli, S & srv, CallbackGroup group, std::optional timeout = std::nullopt) const { init_cli(cli); - init_srv( - srv, [cli, timeout](auto req, auto res) { *res = *cli->call(req, timeout); }, group); + init_srv(srv, [cli, timeout](auto req, auto res) { *res = *cli->call(req, timeout); }, group); } /// Create a subscription wrapper. diff --git a/common/motion_utils/test/src/trajectory/test_trajectory.cpp b/common/motion_utils/test/src/trajectory/test_trajectory.cpp index 9ebc712b3bf1a..3789ea21a2256 100644 --- a/common/motion_utils/test/src/trajectory/test_trajectory.cpp +++ b/common/motion_utils/test/src/trajectory/test_trajectory.cpp @@ -5365,8 +5365,7 @@ TEST(Trajectory, removeFirstInvalidOrientationPoints) auto traj = generateTestTrajectory(10, 1.0, 1.0); // no invalid points - testRemoveInvalidOrientationPoints( - traj, [](Trajectory &) {}, traj.points.size()); + testRemoveInvalidOrientationPoints(traj, [](Trajectory &) {}, traj.points.size()); // invalid point at the end testRemoveInvalidOrientationPoints( diff --git a/control/autoware_pid_longitudinal_controller/README.md b/control/autoware_pid_longitudinal_controller/README.md index 9929d955e5ba7..b147b3b795391 100644 --- a/control/autoware_pid_longitudinal_controller/README.md +++ b/control/autoware_pid_longitudinal_controller/README.md @@ -212,8 +212,8 @@ AutonomouStuff Lexus RX 450h for under 40 km/h driving. | max_d_effort | double | max value of acceleration with d gain | 0.0 | | min_d_effort | double | min value of acceleration with d gain | 0.0 | | lpf_vel_error_gain | double | gain of low-pass filter for velocity error | 0.9 | -| 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. | -| 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] | +| 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 | +| 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 | | time_threshold_before_pid_integration | double | How much time without the vehicle moving must past to enable PID error integration. [s] | 5.0 | | 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 | diff --git a/control/autoware_smart_mpc_trajectory_follower/autoware_smart_mpc_trajectory_follower/scripts/drive_controller.py b/control/autoware_smart_mpc_trajectory_follower/autoware_smart_mpc_trajectory_follower/scripts/drive_controller.py index 228b0c37c5e7b..3877f7177720b 100644 --- a/control/autoware_smart_mpc_trajectory_follower/autoware_smart_mpc_trajectory_follower/scripts/drive_controller.py +++ b/control/autoware_smart_mpc_trajectory_follower/autoware_smart_mpc_trajectory_follower/scripts/drive_controller.py @@ -560,12 +560,12 @@ def update_input_queue( np.array(time_stamp), np.array(steer_history) ) - self.acc_input_queue[ - drive_functions.acc_ctrl_queue_size - acc_num : - ] = acc_interpolate(time_stamp_acc) - self.steer_input_queue[ - drive_functions.steer_ctrl_queue_size - steer_num : - ] = steer_interpolate(time_stamp_steer) + self.acc_input_queue[drive_functions.acc_ctrl_queue_size - acc_num :] = ( + acc_interpolate(time_stamp_acc) + ) + self.steer_input_queue[drive_functions.steer_ctrl_queue_size - steer_num :] = ( + steer_interpolate(time_stamp_steer) + ) if ( acc_num == drive_functions.acc_ctrl_queue_size diff --git a/evaluator/kinematic_evaluator/include/kinematic_evaluator/parameters.hpp b/evaluator/kinematic_evaluator/include/kinematic_evaluator/parameters.hpp index a2de980336e5d..dada46f44292f 100644 --- a/evaluator/kinematic_evaluator/include/kinematic_evaluator/parameters.hpp +++ b/evaluator/kinematic_evaluator/include/kinematic_evaluator/parameters.hpp @@ -27,7 +27,7 @@ namespace kinematic_diagnostics struct Parameters { std::array(Metric::SIZE)> metrics{}; // default values to false -}; // struct Parameters +}; // struct Parameters } // namespace kinematic_diagnostics diff --git a/evaluator/kinematic_evaluator/test/test_kinematic_evaluator_node.cpp b/evaluator/kinematic_evaluator/test/test_kinematic_evaluator_node.cpp index 314bace43eb59..51e6113aea999 100644 --- a/evaluator/kinematic_evaluator/test/test_kinematic_evaluator_node.cpp +++ b/evaluator/kinematic_evaluator/test/test_kinematic_evaluator_node.cpp @@ -67,9 +67,7 @@ class EvalTest : public ::testing::Test tf_broadcaster_ = std::make_unique(dummy_node); } - ~EvalTest() override - { /*rclcpp::shutdown();*/ - } + ~EvalTest() override { /*rclcpp::shutdown();*/ } void setTargetMetric(kinematic_diagnostics::Metric metric) { diff --git a/evaluator/localization_evaluator/include/localization_evaluator/parameters.hpp b/evaluator/localization_evaluator/include/localization_evaluator/parameters.hpp index 46cdf2e77bf11..d8328fe62b3ed 100644 --- a/evaluator/localization_evaluator/include/localization_evaluator/parameters.hpp +++ b/evaluator/localization_evaluator/include/localization_evaluator/parameters.hpp @@ -27,7 +27,7 @@ namespace localization_diagnostics struct Parameters { std::array(Metric::SIZE)> metrics{}; // default values to false -}; // struct Parameters +}; // struct Parameters } // namespace localization_diagnostics diff --git a/launch/tier4_perception_launch/launch/obstacle_segmentation/ground_segmentation/ground_segmentation.launch.py b/launch/tier4_perception_launch/launch/obstacle_segmentation/ground_segmentation/ground_segmentation.launch.py index a307b192d7caa..25fb1e6ac6c4d 100644 --- a/launch/tier4_perception_launch/launch/obstacle_segmentation/ground_segmentation/ground_segmentation.launch.py +++ b/launch/tier4_perception_launch/launch/obstacle_segmentation/ground_segmentation/ground_segmentation.launch.py @@ -501,9 +501,11 @@ def launch_setup(context, *args, **kwargs): components.extend( pipeline.create_single_frame_obstacle_segmentation_components( input_topic=LaunchConfiguration("input/pointcloud"), - output_topic=pipeline.single_frame_obstacle_seg_output - if pipeline.use_single_frame_filter or pipeline.use_time_series_filter - else pipeline.output_topic, + output_topic=( + pipeline.single_frame_obstacle_seg_output + if pipeline.use_single_frame_filter or pipeline.use_time_series_filter + else pipeline.output_topic + ), ) ) @@ -512,18 +514,20 @@ def launch_setup(context, *args, **kwargs): components.extend( pipeline.create_single_frame_outlier_filter_components( input_topic=pipeline.single_frame_obstacle_seg_output, - output_topic=relay_topic - if pipeline.use_time_series_filter - else pipeline.output_topic, + output_topic=( + relay_topic if pipeline.use_time_series_filter else pipeline.output_topic + ), context=context, ) ) if pipeline.use_time_series_filter: components.extend( pipeline.create_time_series_outlier_filter_components( - input_topic=relay_topic - if pipeline.use_single_frame_filter - else pipeline.single_frame_obstacle_seg_output, + input_topic=( + relay_topic + if pipeline.use_single_frame_filter + else pipeline.single_frame_obstacle_seg_output + ), output_topic=pipeline.output_topic, ) ) diff --git a/perception/image_projection_based_fusion/src/roi_pointcloud_fusion/node.cpp b/perception/image_projection_based_fusion/src/roi_pointcloud_fusion/node.cpp index cb462e103a216..ea5c2005bdd46 100644 --- a/perception/image_projection_based_fusion/src/roi_pointcloud_fusion/node.cpp +++ b/perception/image_projection_based_fusion/src/roi_pointcloud_fusion/node.cpp @@ -42,14 +42,14 @@ RoiPointCloudFusionNode::RoiPointCloudFusionNode(const rclcpp::NodeOptions & opt cluster_debug_pub_ = this->create_publisher("debug/clusters", 1); } -void RoiPointCloudFusionNode::preprocess(__attribute__((unused)) - sensor_msgs::msg::PointCloud2 & pointcloud_msg) +void RoiPointCloudFusionNode::preprocess( + __attribute__((unused)) sensor_msgs::msg::PointCloud2 & pointcloud_msg) { return; } -void RoiPointCloudFusionNode::postprocess(__attribute__((unused)) - sensor_msgs::msg::PointCloud2 & pointcloud_msg) +void RoiPointCloudFusionNode::postprocess( + __attribute__((unused)) sensor_msgs::msg::PointCloud2 & pointcloud_msg) { const auto objects_sub_count = pub_objects_ptr_->get_subscription_count() + pub_objects_ptr_->get_intra_process_subscription_count(); diff --git a/perception/lidar_centerpoint/README.md b/perception/lidar_centerpoint/README.md index 2cbec5a561732..fa42655b6ca1f 100644 --- a/perception/lidar_centerpoint/README.md +++ b/perception/lidar_centerpoint/README.md @@ -349,4 +349,4 @@ Special thanks to [Deepen AI](https://www.deepen.ai/) for providing their 3D Ann _The nuScenes dataset is released publicly for non-commercial use under the Creative Commons Attribution-NonCommercial-ShareAlike 4.0 International Public License. Additional Terms of Use can be found at . -To inquire about a commercial license please contact nuscenes@motional.com._ +To inquire about a commercial license please contact ._ diff --git a/perception/probabilistic_occupancy_grid_map/launch/pointcloud_based_occupancy_grid_map.launch.py b/perception/probabilistic_occupancy_grid_map/launch/pointcloud_based_occupancy_grid_map.launch.py index c58e747f84af2..0e84e4860fdf3 100644 --- a/perception/probabilistic_occupancy_grid_map/launch/pointcloud_based_occupancy_grid_map.launch.py +++ b/perception/probabilistic_occupancy_grid_map/launch/pointcloud_based_occupancy_grid_map.launch.py @@ -101,15 +101,19 @@ def launch_setup(context, *args, **kwargs): remappings=[ ( "~/input/obstacle_pointcloud", - LaunchConfiguration("input/obstacle_pointcloud") - if not downsample_input_pointcloud - else "obstacle/downsample/pointcloud", + ( + LaunchConfiguration("input/obstacle_pointcloud") + if not downsample_input_pointcloud + else "obstacle/downsample/pointcloud" + ), ), ( "~/input/raw_pointcloud", - LaunchConfiguration("input/raw_pointcloud") - if not downsample_input_pointcloud - else "raw/downsample/pointcloud", + ( + LaunchConfiguration("input/raw_pointcloud") + if not downsample_input_pointcloud + else "raw/downsample/pointcloud" + ), ), ("~/output/occupancy_grid_map", LaunchConfiguration("output")), ], diff --git a/perception/raindrop_cluster_filter/raindrop_cluster_filter.md b/perception/raindrop_cluster_filter/raindrop_cluster_filter.md index 175bbd00a93ea..e92e645f7a3e8 100644 --- a/perception/raindrop_cluster_filter/raindrop_cluster_filter.md +++ b/perception/raindrop_cluster_filter/raindrop_cluster_filter.md @@ -26,22 +26,22 @@ Mainly this focuses on filtering out unknown objects with very low intensity poi ### Core Parameters -| Name | Type | Default Value | Description | -| --------------------------------- | ----- | ------------------------------------------------------- | --------------------------------------------- | -| `filter_target_label.UNKNOWN` | bool | false | If true, unknown objects are filtered. | -| `filter_target_label.CAR` | bool | false | If true, car objects are filtered. | -| `filter_target_label.TRUCK` | bool | false | If true, truck objects are filtered. | -| `filter_target_label.BUS` | bool | false | If true, bus objects are filtered. | -| `filter_target_label.TRAILER` | bool | false | If true, trailer objects are filtered. | -| `filter_target_label.MOTORCYCLE` | bool | false | If true, motorcycle objects are filtered. | -| `filter_target_label.BICYCLE` | bool | false | If true, bicycle objects are filtered. | -| `filter_target_label.PEDESTRIAN` | bool | false | If true, pedestrian objects are filtered. | -| `max_x` | float | 60.00 | Maximum of x of the filter effective range | -| `min_x` | float | -20.00 | Minimum of x of the filter effective range | -| `max_y` | float | 20.00 | Maximum of y of the filter effective range | -| `min_y` | float | -20.00 | Minium of y of the filter effective range | -| `intensity_threshold` | float | 1.0 | The threshold of average intensity for filter | -| `existence_probability_threshold` | float | The existence probability threshold to apply the filter | +| Name | Type | Default Value | Description | +| --------------------------------- | ----- | ------------- | ------------------------------------------------------- | +| `filter_target_label.UNKNOWN` | bool | false | If true, unknown objects are filtered. | +| `filter_target_label.CAR` | bool | false | If true, car objects are filtered. | +| `filter_target_label.TRUCK` | bool | false | If true, truck objects are filtered. | +| `filter_target_label.BUS` | bool | false | If true, bus objects are filtered. | +| `filter_target_label.TRAILER` | bool | false | If true, trailer objects are filtered. | +| `filter_target_label.MOTORCYCLE` | bool | false | If true, motorcycle objects are filtered. | +| `filter_target_label.BICYCLE` | bool | false | If true, bicycle objects are filtered. | +| `filter_target_label.PEDESTRIAN` | bool | false | If true, pedestrian objects are filtered. | +| `max_x` | float | 60.00 | Maximum of x of the filter effective range | +| `min_x` | float | -20.00 | Minimum of x of the filter effective range | +| `max_y` | float | 20.00 | Maximum of y of the filter effective range | +| `min_y` | float | -20.00 | Minium of y of the filter effective range | +| `intensity_threshold` | float | 1.0 | The threshold of average intensity for filter | +| `existence_probability_threshold` | float | 0.2 | The existence probability threshold to apply the filter | ## Assumptions / Known limits diff --git a/perception/tensorrt_yolox/src/tensorrt_yolox.cpp b/perception/tensorrt_yolox/src/tensorrt_yolox.cpp index ea7857c3768aa..11f68f580acc2 100644 --- a/perception/tensorrt_yolox/src/tensorrt_yolox.cpp +++ b/perception/tensorrt_yolox/src/tensorrt_yolox.cpp @@ -956,7 +956,7 @@ void TrtYoloX::generateYoloxProposals( objects.push_back(obj); } } // class loop - } // point anchor loop + } // point anchor loop } void TrtYoloX::qsortDescentInplace(ObjectArray & face_objects, int left, int right) const diff --git a/planning/sampling_based_planner/autoware_path_sampler/src/node.cpp b/planning/sampling_based_planner/autoware_path_sampler/src/node.cpp index a7ca2035e1474..2b8a1bd115856 100644 --- a/planning/sampling_based_planner/autoware_path_sampler/src/node.cpp +++ b/planning/sampling_based_planner/autoware_path_sampler/src/node.cpp @@ -423,8 +423,8 @@ std::vector PathSampler::generateCandidatesFromP size_t reuse_idx = 0; for (reuse_idx = 0; reuse_idx + 1 < prev_path_->lengths.size() && prev_path_->lengths[reuse_idx] < reuse_length; - ++reuse_idx) - ; + ++reuse_idx) { + } if (reuse_idx == 0UL) continue; const auto reused_path = *prev_path_->subset(0UL, reuse_idx); reuse_state.curvature = reused_path.curvatures.back(); diff --git a/sensing/pointcloud_preprocessor/src/passthrough_filter/passthrough_uint16.cpp b/sensing/pointcloud_preprocessor/src/passthrough_filter/passthrough_uint16.cpp index 3a40408bcd8de..d68ba32282351 100644 --- a/sensing/pointcloud_preprocessor/src/passthrough_filter/passthrough_uint16.cpp +++ b/sensing/pointcloud_preprocessor/src/passthrough_filter/passthrough_uint16.cpp @@ -242,7 +242,7 @@ void pcl::PassThroughUInt16::applyFilter(PCLPointCloud2 & o nr_p++; } output.width = nr_p; - } // !keep_organized_ + } // !keep_organized_ } else { // No distance filtering, process all data. // No need to check for is_organized here as we did it above for (int cp = 0; cp < nr_points; ++cp, xyz_offset += input_->point_step) { diff --git a/sensing/tier4_pcl_extensions/include/tier4_pcl_extensions/voxel_grid_nearest_centroid_impl.hpp b/sensing/tier4_pcl_extensions/include/tier4_pcl_extensions/voxel_grid_nearest_centroid_impl.hpp index a42b43b448080..db36befb69237 100644 --- a/sensing/tier4_pcl_extensions/include/tier4_pcl_extensions/voxel_grid_nearest_centroid_impl.hpp +++ b/sensing/tier4_pcl_extensions/include/tier4_pcl_extensions/voxel_grid_nearest_centroid_impl.hpp @@ -221,7 +221,7 @@ void pcl::VoxelGridNearestCentroid::applyFilter(PointCloud & output) &rgb, reinterpret_cast(&input_->points[cp]) + rgba_index, sizeof(int)); centroid[centroid_size - 3] = static_cast((rgb >> 16) & 0x0000ff); centroid[centroid_size - 2] = static_cast((rgb >> 8) & 0x0000ff); - centroid[centroid_size - 1] = static_cast((rgb)&0x0000ff); + centroid[centroid_size - 1] = static_cast((rgb) & 0x0000ff); } pcl::for_each_type( NdCopyPointEigenFunctor(input_->points[cp], centroid)); @@ -272,7 +272,7 @@ void pcl::VoxelGridNearestCentroid::applyFilter(PointCloud & output) &rgb, reinterpret_cast(&input_->points[cp]) + rgba_index, sizeof(int)); centroid[centroid_size - 3] = static_cast((rgb >> 16) & 0x0000ff); centroid[centroid_size - 2] = static_cast((rgb >> 8) & 0x0000ff); - centroid[centroid_size - 1] = static_cast((rgb)&0x0000ff); + centroid[centroid_size - 1] = static_cast((rgb) & 0x0000ff); } pcl::for_each_type( NdCopyPointEigenFunctor(input_->points[cp], centroid)); diff --git a/system/system_monitor/include/system_monitor/cpu_monitor/raspi_cpu_monitor.hpp b/system/system_monitor/include/system_monitor/cpu_monitor/raspi_cpu_monitor.hpp index b0456cf34963e..b1dbc358bc858 100644 --- a/system/system_monitor/include/system_monitor/cpu_monitor/raspi_cpu_monitor.hpp +++ b/system/system_monitor/include/system_monitor/cpu_monitor/raspi_cpu_monitor.hpp @@ -35,16 +35,16 @@ #define raspiThermalThrottlingMask (raspiCurrentlyThrottled | raspiSoftTemperatureLimitActive) -#define throttledToString(X) \ - (((X)&raspiUnderVoltageDetected) ? "Under-voltage detected" \ - : ((X)&raspiArmFrequencyCapped) ? "Arm frequency capped" \ - : ((X)&raspiCurrentlyThrottled) ? "Currently throttled" \ - : ((X)&raspiSoftTemperatureLimitActive) ? "Soft temperature limit active" \ - : ((X)&raspiUnderVoltageHasOccurred) ? "Under-voltage has occurred" \ - : ((X)&raspiArmFrequencyCappedHasOccurred) ? "Arm frequency capped has occurred" \ - : ((X)&raspiThrottlingHasOccurred) ? "Throttling has occurred" \ - : ((X)&raspiSoftTemperatureLimitHasOccurred) ? "Soft temperature limit has occurred" \ - : "UNKNOWN") +#define throttledToString(X) \ + (((X) & raspiUnderVoltageDetected) ? "Under-voltage detected" \ + : ((X) & raspiArmFrequencyCapped) ? "Arm frequency capped" \ + : ((X) & raspiCurrentlyThrottled) ? "Currently throttled" \ + : ((X) & raspiSoftTemperatureLimitActive) ? "Soft temperature limit active" \ + : ((X) & raspiUnderVoltageHasOccurred) ? "Under-voltage has occurred" \ + : ((X) & raspiArmFrequencyCappedHasOccurred) ? "Arm frequency capped has occurred" \ + : ((X) & raspiThrottlingHasOccurred) ? "Throttling has occurred" \ + : ((X) & raspiSoftTemperatureLimitHasOccurred) ? "Soft temperature limit has occurred" \ + : "UNKNOWN") class CPUMonitor : public CPUMonitorBase { diff --git a/system/system_monitor/include/system_monitor/gpu_monitor/nvml_gpu_monitor.hpp b/system/system_monitor/include/system_monitor/gpu_monitor/nvml_gpu_monitor.hpp index 3a1df49027d4a..c21b5dc3b1878 100644 --- a/system/system_monitor/include/system_monitor/gpu_monitor/nvml_gpu_monitor.hpp +++ b/system/system_monitor/include/system_monitor/gpu_monitor/nvml_gpu_monitor.hpp @@ -29,17 +29,17 @@ #include #include -#define reasonToString(X) \ - (((X)&nvmlClocksThrottleReasonGpuIdle) ? "GpuIdle" \ - : ((X)&nvmlClocksThrottleReasonApplicationsClocksSetting) ? "ApplicationsClocksSetting" \ - : ((X)&nvmlClocksThrottleReasonSwPowerCap) ? "SwPowerCap" \ - : ((X)&nvmlClocksThrottleReasonHwSlowdown) ? "HwSlowdown" \ - : ((X)&nvmlClocksThrottleReasonSyncBoost) ? "SyncBoost" \ - : ((X)&nvmlClocksThrottleReasonSwThermalSlowdown) ? "SwThermalSlowdown" \ - : ((X)&nvmlClocksThrottleReasonHwThermalSlowdown) ? "HwThermalSlowdown" \ - : ((X)&nvmlClocksThrottleReasonHwPowerBrakeSlowdown) ? "HwPowerBrakeSlowdown" \ - : ((X)&nvmlClocksThrottleReasonDisplayClockSetting) ? "DisplayClockSetting" \ - : "UNKNOWN") +#define reasonToString(X) \ + (((X) & nvmlClocksThrottleReasonGpuIdle) ? "GpuIdle" \ + : ((X) & nvmlClocksThrottleReasonApplicationsClocksSetting) ? "ApplicationsClocksSetting" \ + : ((X) & nvmlClocksThrottleReasonSwPowerCap) ? "SwPowerCap" \ + : ((X) & nvmlClocksThrottleReasonHwSlowdown) ? "HwSlowdown" \ + : ((X) & nvmlClocksThrottleReasonSyncBoost) ? "SyncBoost" \ + : ((X) & nvmlClocksThrottleReasonSwThermalSlowdown) ? "SwThermalSlowdown" \ + : ((X) & nvmlClocksThrottleReasonHwThermalSlowdown) ? "HwThermalSlowdown" \ + : ((X) & nvmlClocksThrottleReasonHwPowerBrakeSlowdown) ? "HwPowerBrakeSlowdown" \ + : ((X) & nvmlClocksThrottleReasonDisplayClockSetting) ? "DisplayClockSetting" \ + : "UNKNOWN") /** * @brief GPU information