@@ -62,6 +62,7 @@ CudaPointcloudPreprocessorNode::CudaPointcloudPreprocessorNode(
62
62
const auto crop_box_max_y_vector = declare_parameter<std::vector<double >>(" crop_box.max_y" );
63
63
const auto crop_box_max_z_vector = declare_parameter<std::vector<double >>(" crop_box.max_z" );
64
64
65
+ /* *INDENT-OFF* */
65
66
if (
66
67
crop_box_min_x_vector.size () != crop_box_min_y_vector.size () ||
67
68
crop_box_min_x_vector.size () != crop_box_min_z_vector.size () ||
@@ -70,6 +71,7 @@ CudaPointcloudPreprocessorNode::CudaPointcloudPreprocessorNode(
70
71
crop_box_min_x_vector.size () != crop_box_max_z_vector.size ()) {
71
72
throw std::runtime_error (" Crop box parameters must have the same size" );
72
73
}
74
+ /* *INDENT-ON* */
73
75
74
76
std::vector<CropBoxParameters> crop_box_parameters;
75
77
@@ -201,6 +203,7 @@ void CudaPointcloudPreprocessorNode::imuCallback(
201
203
transformed_angular_velocity.header = imu_msg->header ;
202
204
angular_velocity_queue_.push_back (transformed_angular_velocity);
203
205
206
+ /* *INDENT-OFF* */
204
207
while (!angular_velocity_queue_.empty ()) {
205
208
// for rosbag replay
206
209
bool backwards_time_jump_detected = rclcpp::Time (angular_velocity_queue_.front ().header .stamp ) >
@@ -217,6 +220,7 @@ void CudaPointcloudPreprocessorNode::imuCallback(
217
220
break ;
218
221
}
219
222
}
223
+ /* *INDENT-ON* */
220
224
}
221
225
222
226
void CudaPointcloudPreprocessorNode::pointcloudCallback (
@@ -243,7 +247,7 @@ void CudaPointcloudPreprocessorNode::pointcloudCallback(
243
247
input_pointcloud_msg_ptr->header .stamp .nanosec * 1e-9 +
244
248
first_point_rel_stamp * 1e-9 ;
245
249
246
- /* *INDENT-ON * */
250
+ /* *INDENT-OFF * */
247
251
while (twist_queue_.size () > 1 &&
248
252
rclcpp::Time (twist_queue_.front ().header .stamp ).seconds () < first_point_stamp) {
249
253
twist_queue_.pop_front ();
0 commit comments