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 May 27, 2024
1 parent 72e29ff commit d6b8138
Show file tree
Hide file tree
Showing 15 changed files with 64 additions and 61 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -94,8 +94,7 @@ class NodeAdaptor
C & cli, S & srv, CallbackGroup group, std::optional<double> 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.
Expand Down
3 changes: 1 addition & 2 deletions common/motion_utils/test/src/trajectory/test_trajectory.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -5365,8 +5365,7 @@ TEST(Trajectory, removeFirstInvalidOrientationPoints)
auto traj = generateTestTrajectory<Trajectory>(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(
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -27,7 +27,7 @@ namespace kinematic_diagnostics
struct Parameters
{
std::array<bool, static_cast<size_t>(Metric::SIZE)> metrics{}; // default values to false
}; // struct Parameters
}; // struct Parameters

} // namespace kinematic_diagnostics

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -67,9 +67,7 @@ class EvalTest : public ::testing::Test
tf_broadcaster_ = std::make_unique<tf2_ros::TransformBroadcaster>(dummy_node);
}

~EvalTest() override
{ /*rclcpp::shutdown();*/
}
~EvalTest() override { /*rclcpp::shutdown();*/ }

void setTargetMetric(kinematic_diagnostics::Metric metric)
{
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -27,7 +27,7 @@ namespace localization_diagnostics
struct Parameters
{
std::array<bool, static_cast<size_t>(Metric::SIZE)> metrics{}; // default values to false
}; // struct Parameters
}; // struct Parameters

} // namespace localization_diagnostics

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -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
),
)
)

Expand All @@ -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,
)
)
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -42,14 +42,14 @@ RoiPointCloudFusionNode::RoiPointCloudFusionNode(const rclcpp::NodeOptions & opt
cluster_debug_pub_ = this->create_publisher<sensor_msgs::msg::PointCloud2>("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();
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -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")),
],
Expand Down
2 changes: 1 addition & 1 deletion perception/tensorrt_yolox/src/tensorrt_yolox.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand Down
3 changes: 1 addition & 2 deletions planning/sampling_based_planner/path_sampler/src/node.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -423,8 +423,7 @@ std::vector<sampler_common::Path> PathSampler::generateCandidatesFromPreviousPat
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();
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -242,7 +242,7 @@ void pcl::PassThroughUInt16<pcl::PCLPointCloud2>::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) {
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -221,7 +221,7 @@ void pcl::VoxelGridNearestCentroid<PointT>::applyFilter(PointCloud & output)
&rgb, reinterpret_cast<const char *>(&input_->points[cp]) + rgba_index, sizeof(int));
centroid[centroid_size - 3] = static_cast<float>((rgb >> 16) & 0x0000ff);
centroid[centroid_size - 2] = static_cast<float>((rgb >> 8) & 0x0000ff);
centroid[centroid_size - 1] = static_cast<float>((rgb)&0x0000ff);
centroid[centroid_size - 1] = static_cast<float>((rgb) & 0x0000ff);
}
pcl::for_each_type<FieldList>(
NdCopyPointEigenFunctor<PointT>(input_->points[cp], centroid));
Expand Down Expand Up @@ -272,7 +272,7 @@ void pcl::VoxelGridNearestCentroid<PointT>::applyFilter(PointCloud & output)
&rgb, reinterpret_cast<const char *>(&input_->points[cp]) + rgba_index, sizeof(int));
centroid[centroid_size - 3] = static_cast<float>((rgb >> 16) & 0x0000ff);
centroid[centroid_size - 2] = static_cast<float>((rgb >> 8) & 0x0000ff);
centroid[centroid_size - 1] = static_cast<float>((rgb)&0x0000ff);
centroid[centroid_size - 1] = static_cast<float>((rgb) & 0x0000ff);
}
pcl::for_each_type<FieldList>(
NdCopyPointEigenFunctor<PointT>(input_->points[cp], centroid));
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -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
{
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -29,17 +29,17 @@
#include <string>
#include <vector>

#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
Expand Down

0 comments on commit d6b8138

Please sign in to comment.