Skip to content

Commit 3fcbc42

Browse files
style(pre-commit): autofix
1 parent f4201b6 commit 3fcbc42

File tree

3 files changed

+9
-13
lines changed

3 files changed

+9
-13
lines changed

sensing/autoware_cuda_pointcloud_preprocessor/include/autoware/cuda_pointcloud_preprocessor/cuda_pointcloud_preprocessor_node.hpp

+2-2
Original file line numberDiff line numberDiff line change
@@ -40,8 +40,8 @@
4040
#include <memory>
4141
#include <string>
4242

43-
#define CHECK_OFFSET(structure1, structure2, field) \
44-
static_assert( \
43+
#define CHECK_OFFSET(structure1, structure2, field) \
44+
static_assert( \
4545
offsetof(structure1, field) == offsetof(structure2, field), \
4646
"Offset of " #field " in " #structure1 " does not match expected offset.")
4747

sensing/autoware_cuda_pointcloud_preprocessor/include/autoware/cuda_pointcloud_preprocessor/types.hpp

+3-4
Original file line numberDiff line numberDiff line change
@@ -79,13 +79,12 @@ struct RingOutlierFilterParameters
7979
std::size_t num_points_threshold{0};
8080
};
8181

82-
template<typename T>
82+
template <typename T>
8383
class MemoryPoolAllocator
8484
{
8585
public:
8686
using value_type = T;
87-
explicit MemoryPoolAllocator(cudaMemPool_t pool)
88-
: m_pool(pool) {}
87+
explicit MemoryPoolAllocator(cudaMemPool_t pool) : m_pool(pool) {}
8988

9089
T * allocate(std::size_t n)
9190
{
@@ -94,7 +93,7 @@ class MemoryPoolAllocator
9493
return static_cast<T *>(ptr);
9594
}
9695

97-
void deallocate(T * ptr, std::size_t) {cudaFreeAsync(ptr, cudaStreamDefault);}
96+
void deallocate(T * ptr, std::size_t) { cudaFreeAsync(ptr, cudaStreamDefault); }
9897

9998
protected:
10099
cudaMemPool_t m_pool;

sensing/autoware_cuda_pointcloud_preprocessor/src/cuda_pointcloud_preprocessor/cuda_pointcloud_preprocessor_node.cpp

+4-7
Original file line numberDiff line numberDiff line change
@@ -67,8 +67,7 @@ CudaPointcloudPreprocessorNode::CudaPointcloudPreprocessorNode(
6767
crop_box_min_x_vector.size() != crop_box_min_z_vector.size() ||
6868
crop_box_min_x_vector.size() != crop_box_max_x_vector.size() ||
6969
crop_box_min_x_vector.size() != crop_box_max_y_vector.size() ||
70-
crop_box_min_x_vector.size() != crop_box_max_z_vector.size())
71-
{
70+
crop_box_min_x_vector.size() != crop_box_max_z_vector.size()) {
7271
throw std::runtime_error("Crop box parameters must have the same size");
7372
}
7473

@@ -91,7 +90,7 @@ CudaPointcloudPreprocessorNode::CudaPointcloudPreprocessorNode(
9190
// Publisher
9291
pub_ =
9392
std::make_unique<cuda_blackboard::CudaBlackboardPublisher<cuda_blackboard::CudaPointCloud2>>(
94-
*this, "~/output/pointcloud");
93+
*this, "~/output/pointcloud");
9594

9695
// Subscriber
9796
rclcpp::SubscriptionOptions sub_options;
@@ -241,14 +240,12 @@ void CudaPointcloudPreprocessorNode::pointcloudCallback(
241240
first_point_rel_stamp * 1e-9;
242241

243242
while (twist_queue_.size() > 1 &&
244-
rclcpp::Time(twist_queue_.front().header.stamp).seconds() < first_point_stamp)
245-
{
243+
rclcpp::Time(twist_queue_.front().header.stamp).seconds() < first_point_stamp) {
246244
twist_queue_.pop_front();
247245
}
248246

249247
while (angular_velocity_queue_.size() > 1 &&
250-
rclcpp::Time(angular_velocity_queue_.front().header.stamp).seconds() < first_point_stamp)
251-
{
248+
rclcpp::Time(angular_velocity_queue_.front().header.stamp).seconds() < first_point_stamp) {
252249
angular_velocity_queue_.pop_front();
253250
}
254251

0 commit comments

Comments
 (0)