RobustFieldAutonomyLab / LeGO-LOAM

LeGO-LOAM: Lightweight and Ground-Optimized Lidar Odometry and Mapping on Variable Terrain
BSD 3-Clause "New" or "Revised" License
2.36k stars 1.11k forks source link

frames meaning #104

Closed narutojxl closed 5 years ago

narutojxl commented 5 years ago

Hello @TixiaoShan

when launching lego_loam and play jackal_dataset_20170608 bags, i got the frame tree as follows. 5d2702aff8d6171f67000172 In the picture, the meaning of virtual_velodyne frame is (Z-front, X-left, Y-up), which different from velodyne_frame(X-front, Y-left, Z-up).

Q1. Does base_link in tf tree meaning velodyne_frame? camera is virtual_velodyne?

Q2. What's the meaning of lego_loam backend calculated frame aft_mapped? I see transformAftMapped's orientation is transformed to get aft_mapped and then published on topic and TF. But when saving finalCloud.pcd map, use cloudKeyPoses6D(cloudKeyPoses6D == transformAftMapped) to transform points to camera_init frame, not use aft_mapped or camera frame.

Looking forward to your help, thanks sincerely!

void publishTF(){ geometrymsgs::Quaternion geoQuat = tf::createQuaternionMsgFromRollPitchYaw (transformAftMapped[2], -transformAftMapped[0], -transformAftMapped[1]); odomAftMapped.header.stamp = ros::Time().fromSec(timeLaserOdometry); odomAftMapped.pose.pose.orientation.x = -geoQuat.y; odomAftMapped.pose.pose.orientation.y = -geoQuat.z; odomAftMapped.pose.pose.orientation.z = geoQuat.x; odomAftMapped.pose.pose.orientation.w = geoQuat.w; odomAftMapped.pose.pose.position.x = transformAftMapped[3]; odomAftMapped.pose.pose.position.y = transformAftMapped[4]; odomAftMapped.pose.pose.position.z = transformAftMapped[5]; odomAftMapped.twist.twist.angular.x = transformBefMapped[0]; odomAftMapped.twist.twist.angular.y = transformBefMapped[1]; odomAftMapped.twist.twist.angular.z = transformBefMapped[2]; odomAftMapped.twist.twist.linear.x = transformBefMapped[3]; odomAftMapped.twist.twist.linear.y = transformBefMapped[4]; odomAftMapped.twist.twist.linear.z = transformBefMapped[5]; pubOdomAftMapped.publish(odomAftMapped); aftMappedTrans.stamp = ros::Time().fromSec(timeLaserOdometry); aftMappedTrans.setRotation(tf::Quaternion(-geoQuat.y, -geoQuat.z, geoQuat.x, geoQuat.w)); aftMappedTrans.setOrigin(tf::Vector3(transformAftMapped[3], transformAftMapped[4], transformAftMapped[5])); tfBroadcaster.sendTransform(aftMappedTrans); }

thisPose3D.x = latestEstimate.translation().y(); thisPose3D.y = latestEstimate.translation().z(); thisPose3D.z = latestEstimate.translation().x(); thisPose3D.intensity = cloudKeyPoses3D->points.size(); // this can be used as index cloudKeyPoses3D->push_back(thisPose3D); thisPose6D.x = thisPose3D.x; thisPose6D.y = thisPose3D.y; thisPose6D.z = thisPose3D.z; thisPose6D.intensity = thisPose3D.intensity; // this can be used as index thisPose6D.roll = latestEstimate.rotation().pitch(); thisPose6D.pitch = latestEstimate.rotation().yaw(); thisPose6D.yaw = latestEstimate.rotation().roll(); // in camera frame thisPose6D.time = timeLaserOdometry; cloudKeyPoses6D->push_back(thisPose6D); /**

  • save updated transform */ if (cloudKeyPoses3D->points.size() > 1) { transformAftMapped[0] = latestEstimate.rotation().pitch(); transformAftMapped[1] = latestEstimate.rotation().yaw(); transformAftMapped[2] = latestEstimate.rotation().roll(); transformAftMapped[3] = latestEstimate.translation().y(); transformAftMapped[4] = latestEstimate.translation().z(); transformAftMapped[5] = latestEstimate.translation().x();
        for (int i = 0; i < 6; ++i) {
            transformLast[i] = transformAftMapped[i];
            transformTobeMapped[i] = transformAftMapped[i];
        }
    }
tejalbarnwal commented 2 years ago

@narutojxl did you get the answers to the questions you had posted?