diff --git a/modules/localization/msf/local_integ/lidar_msg_transfer.cc b/modules/localization/msf/local_integ/lidar_msg_transfer.cc index 22fbf89329c95a6474d4107fe1a989247c5940b1..e07ba5f896dfe6c15bc7908f9b37d0ade9e0f03c 100644 --- a/modules/localization/msf/local_integ/lidar_msg_transfer.cc +++ b/modules/localization/msf/local_integ/lidar_msg_transfer.cc @@ -32,8 +32,8 @@ void LidarMsgTransfer::Transfer(const drivers::PointCloud &msg, CHECK_NOTNULL(lidar_frame); if (msg.height() > 1 && msg.width() > 1) { - for (int i = 0; i < msg.height(); ++i) { - for (int j = 0; j < msg.width(); ++j) { + for (unsigned int i = 0; i < msg.height(); ++i) { + for (unsigned int j = 0; j < msg.width(); ++j) { Eigen::Vector3d pt3d; pt3d[0] = static_cast(msg.point(i * msg.width() + j).x()); pt3d[1] = static_cast(msg.point(i * msg.width() + j).y());