ImageProjection的构造函数
ImageProjection():
deskewFlag(0)
{
// 订阅原始imu数据
subImu = nh.subscribe<sensor_msgs::Imu>(imuTopic, 2000, &ImageProjection::imuHandler, this, ros::TransportHints().tcpNoDelay());
// 订阅imu里程计,由imuPreintegration积分计算得到的每时刻imu位姿
subOdom = nh.subscribe<nav_msgs::Odometry>(odomTopic+"_incremental", 2000, &ImageProjection::odometryHandler, this, ros::TransportHints().tcpNoDelay());
// 订阅原始lidar数据
subLaserCloud = nh.subscribe<sensor_msgs::PointCloud2>(pointCloudTopic, 5, &ImageProjection::cloudHandler, this, ros::TransportHints().tcpNoDelay());
// 发布当前激光帧运动畸变校正后的点云,有效点
pubExtractedCloud = nh.advertise<sensor_msgs::PointCloud2> ("lio_sam/deskew/cloud_deskewed", 1);
// 发布当前激光帧运动畸变校正后的点云信息
pubLaserCloudInfo = nh.advertise<lio_sam::cloud_info> ("lio_sam/deskew/cloud_info", 1);
// 初始化
allocateMemory();
// 重置参数
resetParameters();
// pcl日志级别,只打ERROR日志
pcl::console::setVerbosityLevel(pcl::console::L_ERROR);
}
初始化函数
void allocateMemory()
{
// 当前帧原始激光点云
laserCloudIn.reset(new pcl::PointCloud<PointXYZIRT>());
tmpOusterCloudIn.reset(new pcl::PointCloud<OusterPointXYZIRT>());
// 当期帧运动畸变校正之后的激光点云
fullCloud.reset(new pcl::PointCloud<PointType>());
// 从fullCloud中提取有效点
extractedCloud.reset(new pcl::PointCloud<PointType>());
// N_SCAN; 扫描线数,例如16、64
// Horizon_SCAN; 扫描一周计数,例如每隔0.2°扫描一次,一周360°可以扫描1800次
fullCloud->points.resize(N_SCAN*Horizon_SCAN);
cloudInfo.startRingIndex.assign(N_SCAN, 0);
cloudInfo.endRingIndex.assign(N_SCAN, 0);
cloudInfo.pointColInd.assign(N_SCAN*Horizon_SCAN, 0);
cloudInfo.pointRange.assign(N_SCAN*Horizon_SCAN, 0);
resetParameters();
}
重置参数
void resetParameters()
{
laserCloudIn->clear();
extractedCloud->clear();
//用矩阵存放激光点距离
rangeMat = cv::Mat(N_SCAN, Horizon_SCAN, CV_32F, cv::Scalar::all(FLT_MAX));
imuPointerCur = 0;
firstPointFlag = true;
odomDeskewFlag = false;
// 当前激光帧起止时刻间对应的imu数据,计算相对于起始时刻的旋转增量,以及时时间戳;
// 用于插值计算当前激光帧起止时间范围内,每一时刻的旋转姿态
for (int i = 0; i < queueLength; ++i)
{
imuTime[i] = 0;
imuRotX[i] = 0;
imuRotY[i] = 0;
imuRotZ[i] = 0;
}
}
imuHandler把iimu数据转换到lidar位姿下
void imuHandler(const sensor_msgs::Imu::ConstPtr& imuMsg)
{
// imu原始测量数据转换到lidar系,加速度、角速度、RPY
sensor_msgs::Imu thisImu = imuConverter(*imuMsg);
// 上锁,添加数据的时候队列不可用
std::lock_guard<std::mutex> lock1(imuLock);
imuQueue.push_back(thisImu);
}
imuConverter转换函数
sensor_msgs::Imu imuConverter(const sensor_msgs::Imu& imu_in)
{
sensor_msgs::Imu imu_out = imu_in;
// 加速度,只跟xyz坐标系的旋转有关系
Eigen::Vector3d acc(imu_in.linear_acceleration.x, imu_in.linear_acceleration.y, imu_in.linear_acceleration.z);
acc = extRot * acc;
imu_out.linear_acceleration.x = acc.x();
imu_out.linear_acceleration.y = acc.y();
imu_out.linear_acceleration.z = acc.z();
// 角速度,只跟xyz坐标系的旋转有关系
Eigen::Vector3d gyr(imu_in.angular_velocity.x, imu_in.angular_velocity.y, imu_in.angular_velocity.z);
gyr = extRot * gyr;
imu_out.angular_velocity.x = gyr.x();
imu_out.angular_velocity.y = gyr.y();
imu_out.angular_velocity.z = gyr.z();
// RPY
Eigen::Quaterniond q_from(imu_in.orientation.w, imu_in.orientation.x, imu_in.orientation.y, imu_in.orientation.z);
// 为什么是右乘,可以动手画一下看看
Eigen::Quaterniond q_final = q_from * extQRPY;
imu_out.orientation.x = q_final.x();
imu_out.orientation.y = q_final.y();
imu_out.orientation.z = q_final.z();
imu_out.orientation.w = q_final.w();
//旋转的四元数为单位四元数,它的模为1
if (sqrt(q_final.x()*q_final.x() + q_final.y()*q_final.y() + q_final.z()*q_final.z() + q_final.w()*q_final.w()) < 0.1)
{
ROS_ERROR("Invalid quaternion, please use a 9-axis IMU!");
ros::shutdown();
}
return imu_out;
}
订阅imu里程计,由imuPreintegration积分计算得到的每时刻imu位姿
void odometryHandler(const nav_msgs::Odometry::ConstPtr& odometryMsg)
{
std::lock_guard<std::mutex> lock2(odoLock);
odomQueue.push_back(*odometryMsg);
}
/**
* 订阅原始lidar数据
* 1、添加一帧激光点云到队列,取出最早一帧作为当前帧,计算起止时间戳,检查数据有效性
* 2、当前帧起止时刻对应的imu数据、imu里程计数据处理
* imu数据:
* 1) 遍历当前激光帧起止时刻之间的imu数据,初始时刻对应imu的姿态角RPY设为当前帧的初始姿态角
* 2) 用角速度、时间积分,计算每一时刻相对于初始时刻的旋转量,初始时刻旋转设为0
* imu里程计数据:
* 1) 遍历当前激光帧起止时刻之间的imu里程计数据,初始时刻对应imu里程计设为当前帧的初始位姿
* 2) 用起始、终止时刻对应imu里程计,计算相对位姿变换,保存平移增量
* 3、当前帧激光点云运动畸变校正
* 1) 检查激光点距离、扫描线是否合规
* 2) 激光运动畸变校正,保存激光点
* 4、提取有效激光点,存extractedCloud
* 5、发布当前帧校正后点云,有效点
* 6、重置参数,接收每帧lidar数据都要重置这些参数
*/
void cloudHandler(const sensor_msgs::PointCloud2ConstPtr& laserCloudMsg)
{
// 添加一帧激光点云到队列,取出最早一帧作为当前帧,计算起止时间戳,检查数据有效性
if (!cachePointCloud(laserCloudMsg))
return;
// 当前帧起止时刻对应的imu数据、imu里程计数据处理
if (!deskewInfo())
return;
// 当前帧激光点云运动畸变校正
// 1、检查激光点距离、扫描线是否合规
// 2、激光运动畸变校正,保存激光点
projectPointCloud();
// 提取有效激光点,存extractedCloud
cloudExtraction();
// 发布当前帧校正后点云,有效点
publishClouds();
// 重置参数,接收每帧lidar数据都要重置这些参数
resetParameters();
}
/**
* 添加一帧激光点云到队列,取出最早一帧作为当前帧,计算起止时间戳,检查数据有效性
*/
//cache 缓存
bool cachePointCloud(const sensor_msgs::PointCloud2ConstPtr& laserCloudMsg)
{
cloudQueue.push_back(*laserCloudMsg);
if (cloudQueue.size() <= 2)
return false;
// 取出激光点云队列中最早的一帧
currentCloudMsg = std::move(cloudQueue.front());
cloudQueue.pop_front();
if (sensor == SensorType::VELODYNE)
{
// 转换成pcl点云格式
pcl::moveFromROSMsg(currentCloudMsg, *laserCloudIn);
}
else if (sensor == SensorType::OUSTER)
{
// 转换成Velodyne格式
pcl::moveFromROSMsg(currentCloudMsg, *tmpOusterCloudIn);
laserCloudIn->points.resize(tmpOusterCloudIn->size());
laserCloudIn->is_dense = tmpOusterCloudIn->is_dense;
for (size_t i = 0; i < tmpOusterCloudIn->size(); i++)
{
auto &src = tmpOusterCloudIn->points[i];
auto &dst = laserCloudIn->points[i];
dst.x = src.x;
dst.y = src.y;
dst.z = src.z;
dst.intensity = src.intensity;
dst.ring = src.ring;
dst.time = src.t * 1e-9f;
}
}
else
{
ROS_ERROR_STREAM("Unknown sensor type: " << int(sensor));
ros::shutdown();
}
// 当前帧头部
cloudHeader = currentCloudMsg.header;
// 当前帧起始时刻
timeScanCur = cloudHeader.stamp.toSec();
// 当前帧结束时刻,注:点云中激光点的time记录相对于当前帧第一个激光点的时差,第一个点time=0
timeScanEnd = timeScanCur + laserCloudIn->points.back().time;
// 存在无效点,Nan或者Inf
if (laserCloudIn->is_dense == false)
{
ROS_ERROR("Point cloud is not in dense format, please remove NaN points first!");
ros::shutdown();
}
// 检查是否存在ring通道,注意static只检查一次
static int ringFlag = 0;
if (ringFlag == 0)
{
ringFlag = -1;
for (int i = 0; i < (int)currentCloudMsg.fields.size(); ++i)
{
if (currentCloudMsg.fields[i].name == "ring")
{
ringFlag = 1;
break;
}
}
if (ringFlag == -1)
{
ROS_ERROR("Point cloud ring channel not available, please configure your point cloud data!");
ros::shutdown();
}
}
// 检查是否存在time通道
if (deskewFlag == 0)
{
deskewFlag = -1;
for (auto &field : currentCloudMsg.fields)
{
if (field.name == "time" || field.name == "t")
{
deskewFlag = 1;
break;
}
}
if (deskewFlag == -1)
ROS_WARN("Point cloud timestamp not available, deskew function disabled, system will drift significantly!");
}
return true;
}
/**
* 当前帧起止时刻对应的imu数据、imu里程计数据处理
*/
bool deskewInfo()
{
std::lock_guard<std::mutex> lock1(imuLock);
std::lock_guard<std::mutex> lock2(odoLock);
// 要求imu数据包含激光数据,否则不往下处理了
if (imuQueue.empty() || imuQueue.front().header.stamp.toSec() > timeScanCur || imuQueue.back().header.stamp.toSec() < timeScanEnd)
{
ROS_DEBUG("Waiting for IMU data ...");
return false;
}
// 当前帧对应imu数据处理
// 1、遍历当前激光帧起止时刻之间的imu数据,初始时刻对应imu的姿态角RPY设为当前帧的初始姿态角
// 2、用角速度、时间积分,计算每一时刻相对于初始时刻的旋转量,初始时刻旋转设为0
// 注:imu数据都已经转换到lidar系下了
imuDeskewInfo();
// 当前帧对应imu里程计处理
// 1、遍历当前激光帧起止时刻之间的imu里程计数据,初始时刻对应imu里程计设为当前帧的初始位姿
// 2、用起始、终止时刻对应imu里程计,计算相对位姿变换,保存平移增量
// 注:imu数据都已经转换到lidar系下了
odomDeskewInfo();
return true;
}
/**
* 当前帧对应imu数据处理
* 1、遍历当前激光帧起止时刻之间的imu数据,初始时刻对应imu的姿态角RPY设为当前帧的初始姿态角
* 2、用角速度、时间积分,计算每一时刻相对于初始时刻的旋转量,初始时刻旋转设为0
* 注:imu数据都已经转换到lidar系下了
*/
void imuDeskewInfo()
{
cloudInfo.imuAvailable = false;
// 从imu队列中删除当前激光帧0.01s前面时刻的imu数据
while (!imuQueue.empty())
{
if (imuQueue.front().header.stamp.toSec() < timeScanCur - 0.01)
imuQueue.pop_front();
else
break;
}
if (imuQueue.empty())
return;
imuPointerCur = 0;
// 遍历当前激光帧起止时刻(前后扩展0.01s)之间的imu数据
for (int i = 0; i < (int)imuQueue.size(); ++i)
{
sensor_msgs::Imu thisImuMsg = imuQueue[i];
double currentImuTime = thisImuMsg.header.stamp.toSec();
// 提取imu姿态角RPY,作为当前lidar帧初始姿态角
if (currentImuTime <= timeScanCur)
imuRPY2rosRPY(&thisImuMsg, &cloudInfo.imuRollInit, &cloudInfo.imuPitchInit, &cloudInfo.imuYawInit);
// 超过当前激光帧结束时刻0.01s,结束
if (currentImuTime > timeScanEnd + 0.01)
break;
// 第一帧imu旋转角初始化
if (imuPointerCur == 0){
imuRotX[0] = 0;
imuRotY[0] = 0;
imuRotZ[0] = 0;
imuTime[0] = currentImuTime;
++imuPointerCur;
continue;
}
// 提取imu角速度
double angular_x, angular_y, angular_z;
imuAngular2rosAngular(&thisImuMsg, &angular_x, &angular_y, &angular_z);
// imu帧间时差
double timeDiff = currentImuTime - imuTime[imuPointerCur-1];
// 当前时刻旋转角 = 前一时刻旋转角 + 角速度 * 时差
imuRotX[imuPointerCur] = imuRotX[imuPointerCur-1] + angular_x * timeDiff;
imuRotY[imuPointerCur] = imuRotY[imuPointerCur-1] + angular_y * timeDiff;
imuRotZ[imuPointerCur] = imuRotZ[imuPointerCur-1] + angular_z * timeDiff;
imuTime[imuPointerCur] = currentImuTime;
++imuPointerCur;
}
--imuPointerCur;
// 没有合规的imu数据
if (imuPointerCur <= 0)
return;
cloudInfo.imuAvailable = true;
}
/**
* 当前帧对应imu里程计处理
* 1、遍历当前激光帧起止时刻之间的imu里程计数据,初始时刻对应imu里程计设为当前帧的初始位姿
* 2、用起始、终止时刻对应imu里程计,计算相对位姿变换,保存平移增量
* 注:imu数据都已经转换到lidar系下了
*/
void odomDeskewInfo()
{
cloudInfo.odomAvailable = false;
// 从imu里程计队列中删除当前激光帧0.01s前面时刻的imu数据
while (!odomQueue.empty())
{
if (odomQueue.front().header.stamp.toSec() < timeScanCur - 0.01)
odomQueue.pop_front();
else
break;
}
if (odomQueue.empty())
return;
// 要求必须有当前激光帧时刻之前的imu里程计数据
if (odomQueue.front().header.stamp.toSec() > timeScanCur)
return;
// 提取当前激光帧起始时刻的imu里程计
nav_msgs::Odometry startOdomMsg;
for (int i = 0; i < (int)odomQueue.size(); ++i)
{
startOdomMsg = odomQueue[i];
if (ROS_TIME(&startOdomMsg) < timeScanCur)
continue;
else
break;
}
// 提取imu里程计姿态角
tf::Quaternion orientation;
tf::quaternionMsgToTF(startOdomMsg.pose.pose.orientation, orientation);
double roll, pitch, yaw;
tf::Matrix3x3(orientation).getRPY(roll, pitch, yaw);
// 用当前激光帧起始时刻的imu里程计,初始化lidar位姿,后面用于mapOptmization
cloudInfo.initialGuessX = startOdomMsg.pose.pose.position.x;
cloudInfo.initialGuessY = startOdomMsg.pose.pose.position.y;
cloudInfo.initialGuessZ = startOdomMsg.pose.pose.position.z;
cloudInfo.initialGuessRoll = roll;
cloudInfo.initialGuessPitch = pitch;
cloudInfo.initialGuessYaw = yaw;
cloudInfo.odomAvailable = true;
odomDeskewFlag = false;
// 如果当前激光帧结束时刻之后没有imu里程计数据,返回
if (odomQueue.back().header.stamp.toSec() < timeScanEnd)
return;
// 提取当前激光帧结束时刻的imu里程计
nav_msgs::Odometry endOdomMsg;
for (int i = 0; i < (int)odomQueue.size(); ++i)
{
endOdomMsg = odomQueue[i];
if (ROS_TIME(&endOdomMsg) < timeScanEnd)
continue;
else
break;
}
// 如果起止时刻对应imu里程计的方差不等,返回
if (int(round(startOdomMsg.pose.covariance[0])) != int(round(endOdomMsg.pose.covariance[0])))
return;
Eigen::Affine3f transBegin = pcl::getTransformation(startOdomMsg.pose.pose.position.x, startOdomMsg.pose.pose.position.y, startOdomMsg.pose.pose.position.z, roll, pitch, yaw);
tf::quaternionMsgToTF(endOdomMsg.pose.pose.orientation, orientation);
tf::Matrix3x3(orientation).getRPY(roll, pitch, yaw);
Eigen::Affine3f transEnd = pcl::getTransformation(endOdomMsg.pose.pose.position.x, endOdomMsg.pose.pose.position.y, endOdomMsg.pose.pose.position.z, roll, pitch, yaw);
// 起止时刻imu里程计的相对变换
Eigen::Affine3f transBt = transBegin.inverse() * transEnd;
// 相对变换,提取增量平移、旋转(欧拉角)
float rollIncre, pitchIncre, yawIncre;
pcl::getTranslationAndEulerAngles(transBt, odomIncreX, odomIncreY, odomIncreZ, rollIncre, pitchIncre, yawIncre);
odomDeskewFlag = true;
}
/**
* 当前帧激光点云运动畸变校正
* 1、检查激光点距离、扫描线是否合规
* 2、激光运动畸变校正,保存激光点
*/
void projectPointCloud()
{
int cloudSize = laserCloudIn->points.size();
// 遍历当前帧激光点云
for (int i = 0; i < cloudSize; ++i)
{
// pcl格式
PointType thisPoint;
thisPoint.x = laserCloudIn->points[i].x;
thisPoint.y = laserCloudIn->points[i].y;
thisPoint.z = laserCloudIn->points[i].z;
thisPoint.intensity = laserCloudIn->points[i].intensity;
// 距离检查
float range = pointDistance(thisPoint);
if (range < lidarMinRange || range > lidarMaxRange)
continue;
// 扫描线检查
int rowIdn = laserCloudIn->points[i].ring;
if (rowIdn < 0 || rowIdn >= N_SCAN)
continue;
// 扫描线如果有降采样,跳过采样的扫描线这里要跳过
if (rowIdn % downsampleRate != 0)
continue;
float horizonAngle = atan2(thisPoint.x, thisPoint.y) * 180 / M_PI;
// 水平扫描角度步长,例如一周扫描1800次,则两次扫描间隔角度0.2°
static float ang_res_x = 360.0/float(Horizon_SCAN);
int columnIdn = -round((horizonAngle-90.0)/ang_res_x) + Horizon_SCAN/2;
if (columnIdn >= Horizon_SCAN)
columnIdn -= Horizon_SCAN;
if (columnIdn < 0 || columnIdn >= Horizon_SCAN)
continue;
// 已经存过该点,不再处理
if (rangeMat.at<float>(rowIdn, columnIdn) != FLT_MAX)
continue;
// 激光运动畸变校正
// 利用当前帧起止时刻之间的imu数据计算旋转增量,imu里程计数据计算平移增量,进而将每一时刻激光点位置变换到第一个激光点坐标系下,进行运动补偿
thisPoint = deskewPoint(&thisPoint, laserCloudIn->points[i].time);
// 矩阵存激光点的距离
rangeMat.at<float>(rowIdn, columnIdn) = range;
// 转换成一维索引,存校正之后的激光点
int index = columnIdn + rowIdn * Horizon_SCAN;
fullCloud->points[index] = thisPoint;
}
}
/**
* 激光运动畸变校正
* 利用当前帧起止时刻之间的imu数据计算旋转增量,imu里程计数据计算平移增量,进而将每一时刻激光点位置变换到第一个激光点坐标系下,进行运动补偿
*/
PointType deskewPoint(PointType *point, double relTime)
{
if (deskewFlag == -1 || cloudInfo.imuAvailable == false)
return *point;
// relTime是当前激光点相对于激光帧起始时刻的时间,pointTime则是当前激光点的时间戳
double pointTime = timeScanCur + relTime;
// 在当前激光帧起止时间范围内,计算某一时刻的旋转(相对于起始时刻的旋转增量)
float rotXCur, rotYCur, rotZCur;
findRotation(pointTime, &rotXCur, &rotYCur, &rotZCur);
// 在当前激光帧起止时间范围内,计算某一时刻的平移(相对于起始时刻的平移增量)
float posXCur, posYCur, posZCur;
findPosition(relTime, &posXCur, &posYCur, &posZCur);
// 第一个点的位姿增量(0),求逆
if (firstPointFlag == true)
{
transStartInverse = (pcl::getTransformation(posXCur, posYCur, posZCur, rotXCur, rotYCur, rotZCur)).inverse();
firstPointFlag = false;
}
// 当前时刻激光点与第一个激光点的位姿变换
Eigen::Affine3f transFinal = pcl::getTransformation(posXCur, posYCur, posZCur, rotXCur, rotYCur, rotZCur);
Eigen::Affine3f transBt = transStartInverse * transFinal;
// 当前激光点在第一个激光点坐标系下的坐标
PointType newPoint;
newPoint.x = transBt(0,0) * point->x + transBt(0,1) * point->y + transBt(0,2) * point->z + transBt(0,3);
newPoint.y = transBt(1,0) * point->x + transBt(1,1) * point->y + transBt(1,2) * point->z + transBt(1,3);
newPoint.z = transBt(2,0) * point->x + transBt(2,1) * point->y + transBt(2,2) * point->z + transBt(2,3);
newPoint.intensity = point->intensity;
return newPoint;
}
/**
* 提取有效激光点,存extractedCloud
*/
void cloudExtraction()
{
// 有效激光点数量
int count = 0;
// 遍历所有激光点
for (int i = 0; i < N_SCAN; ++i)
{
// 记录每根扫描线起始第5个激光点在一维数组中的索引
cloudInfo.startRingIndex[i] = count - 1 + 5;
for (int j = 0; j < Horizon_SCAN; ++j)
{
// 有效激光点
if (rangeMat.at<float>(i,j) != FLT_MAX)
{
// 记录激光点对应的Horizon_SCAN方向上的索引
cloudInfo.pointColInd[count] = j;
// 激光点距离
cloudInfo.pointRange[count] = rangeMat.at<float>(i,j);
// 加入有效激光点
extractedCloud->push_back(fullCloud->points[j + i*Horizon_SCAN]);
++count;
}
}
// 记录每根扫描线倒数第5个激光点在一维数组中的索引
cloudInfo.endRingIndex[i] = count -1 - 5;
}
}
/**
* 发布当前帧校正后点云,有效点
*/
void publishClouds()
{
cloudInfo.header = cloudHeader;
cloudInfo.cloud_deskewed = publishCloud(&pubExtractedCloud, extractedCloud, cloudHeader.stamp, lidarFrame);
pubLaserCloudInfo.publish(cloudInfo);
}
读别人的代码真爽,感觉写代码和写作文一样,从小自己就是作文弱项