@@ -99,8 +99,8 @@ class DistortionCorrector : public DistortionCorrectorBase
99
99
sensor_msgs::PointCloud2Iterator<float > & it_x, sensor_msgs::PointCloud2Iterator<float > & it_y,
100
100
sensor_msgs::PointCloud2Iterator<float > & it_z,
101
101
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)
104
104
{
105
105
static_cast <Derived *>(this )->undistortPointImplementation (
106
106
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>
130
130
sensor_msgs::PointCloud2Iterator<float > & it_x, sensor_msgs::PointCloud2Iterator<float > & it_y,
131
131
sensor_msgs::PointCloud2Iterator<float > & it_z,
132
132
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);
135
135
136
136
void setPointCloudTransform (
137
137
const std::string & base_frame, const std::string & lidar_frame) override ;
@@ -157,8 +157,8 @@ class DistortionCorrector3D : public DistortionCorrector<DistortionCorrector3D>
157
157
sensor_msgs::PointCloud2Iterator<float > & it_x, sensor_msgs::PointCloud2Iterator<float > & it_y,
158
158
sensor_msgs::PointCloud2Iterator<float > & it_z,
159
159
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);
162
162
void setPointCloudTransform (
163
163
const std::string & base_frame, const std::string & lidar_frame) override ;
164
164
};
0 commit comments