Skip to content

Commit b5d74ca

Browse files
committedJun 14, 2024
chore: move varialbe to const
Signed-off-by: vividf <yihsiang.fang@tier4.jp>
1 parent 39f4f62 commit b5d74ca

File tree

2 files changed

+10
-10
lines changed

2 files changed

+10
-10
lines changed
 

‎sensing/pointcloud_preprocessor/include/pointcloud_preprocessor/distortion_corrector/distortion_corrector.hpp

+6-6
Original file line numberDiff line numberDiff line change
@@ -99,8 +99,8 @@ class DistortionCorrector : public DistortionCorrectorBase
9999
sensor_msgs::PointCloud2Iterator<float> & it_x, sensor_msgs::PointCloud2Iterator<float> & it_y,
100100
sensor_msgs::PointCloud2Iterator<float> & it_z,
101101
std::deque<geometry_msgs::msg::TwistStamped>::iterator & it_twist,
102-
std::deque<geometry_msgs::msg::Vector3Stamped>::iterator & it_imu, float & time_offset,
103-
bool & is_twist_valid, bool & is_imu_valid)
102+
std::deque<geometry_msgs::msg::Vector3Stamped>::iterator & it_imu, float const & time_offset,
103+
const bool & is_twist_valid, const bool & is_imu_valid)
104104
{
105105
static_cast<Derived *>(this)->undistortPointImplementation(
106106
it_x, it_y, it_z, it_twist, it_imu, time_offset, is_twist_valid, is_imu_valid);
@@ -130,8 +130,8 @@ class DistortionCorrector2D : public DistortionCorrector<DistortionCorrector2D>
130130
sensor_msgs::PointCloud2Iterator<float> & it_x, sensor_msgs::PointCloud2Iterator<float> & it_y,
131131
sensor_msgs::PointCloud2Iterator<float> & it_z,
132132
std::deque<geometry_msgs::msg::TwistStamped>::iterator & it_twist,
133-
std::deque<geometry_msgs::msg::Vector3Stamped>::iterator & it_imu, float & time_offset,
134-
bool & is_twist_valid, bool & is_imu_valid);
133+
std::deque<geometry_msgs::msg::Vector3Stamped>::iterator & it_imu, const float & time_offset,
134+
const bool & is_twist_valid, const bool & is_imu_valid);
135135

136136
void setPointCloudTransform(
137137
const std::string & base_frame, const std::string & lidar_frame) override;
@@ -157,8 +157,8 @@ class DistortionCorrector3D : public DistortionCorrector<DistortionCorrector3D>
157157
sensor_msgs::PointCloud2Iterator<float> & it_x, sensor_msgs::PointCloud2Iterator<float> & it_y,
158158
sensor_msgs::PointCloud2Iterator<float> & it_z,
159159
std::deque<geometry_msgs::msg::TwistStamped>::iterator & it_twist,
160-
std::deque<geometry_msgs::msg::Vector3Stamped>::iterator & it_imu, float & time_offset,
161-
bool & is_twist_valid, bool & is_imu_valid);
160+
std::deque<geometry_msgs::msg::Vector3Stamped>::iterator & it_imu, const float & time_offset,
161+
const bool & is_twist_valid, const bool & is_imu_valid);
162162
void setPointCloudTransform(
163163
const std::string & base_frame, const std::string & lidar_frame) override;
164164
};

‎sensing/pointcloud_preprocessor/src/distortion_corrector/distortion_corrector.cpp

+4-4
Original file line numberDiff line numberDiff line change
@@ -328,8 +328,8 @@ void DistortionCorrector2D::undistortPointImplementation(
328328
sensor_msgs::PointCloud2Iterator<float> & it_x, sensor_msgs::PointCloud2Iterator<float> & it_y,
329329
sensor_msgs::PointCloud2Iterator<float> & it_z,
330330
std::deque<geometry_msgs::msg::TwistStamped>::iterator & it_twist,
331-
std::deque<geometry_msgs::msg::Vector3Stamped>::iterator & it_imu, float & time_offset,
332-
bool & is_twist_valid, bool & is_imu_valid)
331+
std::deque<geometry_msgs::msg::Vector3Stamped>::iterator & it_imu, const float & time_offset,
332+
const bool & is_twist_valid, const bool & is_imu_valid)
333333
{
334334
// Initialize linear velocity and angular velocity
335335
float v{0.0f}, w{0.0f};
@@ -373,8 +373,8 @@ void DistortionCorrector3D::undistortPointImplementation(
373373
sensor_msgs::PointCloud2Iterator<float> & it_x, sensor_msgs::PointCloud2Iterator<float> & it_y,
374374
sensor_msgs::PointCloud2Iterator<float> & it_z,
375375
std::deque<geometry_msgs::msg::TwistStamped>::iterator & it_twist,
376-
std::deque<geometry_msgs::msg::Vector3Stamped>::iterator & it_imu, float & time_offset,
377-
bool & is_twist_valid, bool & is_imu_valid)
376+
std::deque<geometry_msgs::msg::Vector3Stamped>::iterator & it_imu, const float & time_offset,
377+
const bool & is_twist_valid, const bool & is_imu_valid)
378378
{
379379
// Initialize linear velocity and angular velocity
380380
float v_x_{0.0f}, v_y_{0.0f}, v_z_{0.0f}, w_x_{0.0f}, w_y_{0.0f}, w_z_{0.0f};

0 commit comments

Comments
 (0)