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 Apr 23, 2024
1 parent 33341bb commit 501a124
Show file tree
Hide file tree
Showing 4 changed files with 13 additions and 9 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -60,7 +60,7 @@ struct PointXYZIRC
float y{0.0F};
float z{0.0F};
float intensity{0.0F};
union { // for memory alignment
union { // for memory alignment
uint16_t _data;
struct
{
Expand Down Expand Up @@ -121,9 +121,9 @@ using PointXYZIRADRTGenerator = std::tuple<

POINT_CLOUD_REGISTER_POINT_STRUCT(
autoware_point_types::PointXYZIRC,
(float, x, x)(float, y, y)(float, z, z)(float, intensity, intensity)(
std::uint8_t, padding, padding)(std::uint8_t, return_type, return_type)(
std::uint16_t, channel, channel))
(float, x,
x)(float, y, y)(float, z, z)(float, intensity, intensity)(std::uint8_t, padding, padding)(
std::uint8_t, return_type, return_type)(std::uint16_t, channel, channel))

POINT_CLOUD_REGISTER_POINT_STRUCT(
autoware_point_types::PointXYZIRADRT,
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -27,8 +27,8 @@

namespace pointcloud_preprocessor
{
using autoware_point_types::PointXYZIRC;
using autoware_point_types::PointXYZIRADRT;
using autoware_point_types::PointXYZIRC;
using point_cloud_msg_wrapper::PointCloud2Modifier;

class RingOutlierFilterComponent : public pointcloud_preprocessor::Filter
Expand Down Expand Up @@ -65,8 +65,10 @@ class RingOutlierFilterComponent : public pointcloud_preprocessor::Filter
{
if (walk_size > num_points_threshold_) return true;

auto first_point = reinterpret_cast<const PointXYZIRADRT *>(&input->data[data_idx_both_ends.first]);
auto last_point = reinterpret_cast<const PointXYZIRADRT *>(&input->data[data_idx_both_ends.second]);
auto first_point =
reinterpret_cast<const PointXYZIRADRT *>(&input->data[data_idx_both_ends.first]);
auto last_point =
reinterpret_cast<const PointXYZIRADRT *>(&input->data[data_idx_both_ends.second]);

const auto x = first_point->x - last_point->x;
const auto y = first_point->y - last_point->y;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -423,7 +423,8 @@ PointCloudConcatenateDataSynchronizerComponent::combineClouds(

// after concatenation, channels have no consistent meaning
size_t channel_offset = offsetof(PointXYZIRC, channel);
for (size_t data_idx = 0; data_idx < concat_cloud_ptr->data.size(); data_idx += concat_cloud_ptr->point_step) {
for (size_t data_idx = 0; data_idx < concat_cloud_ptr->data.size();
data_idx += concat_cloud_ptr->point_step) {
concat_cloud_ptr->data[data_idx + channel_offset] = 0;
}
concat_cloud_ptr->header.stamp = oldest_stamp;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -239,7 +239,8 @@ void RingOutlierFilterComponent::faster_filter(
}
} else if (publish_outlier_pointcloud_) {
for (int i = walk_first_idx; i < walk_last_idx; i++) {
auto outlier_ptr = reinterpret_cast<PointXYZIRC *>(&outlier_points.data[outlier_points_size]);
auto outlier_ptr =
reinterpret_cast<PointXYZIRC *>(&outlier_points.data[outlier_points_size]);
auto input_ptr = reinterpret_cast<const PointXYZIRADRT *>(&input->data[indices[i]]);
if (transform_info.need_transform) {
Eigen::Vector4f p(input_ptr->x, input_ptr->y, input_ptr->z, 1);
Expand Down

0 comments on commit 501a124

Please sign in to comment.