LIO-SAM icon indicating copy to clipboard operation
LIO-SAM copied to clipboard

"odom_mapping" in child_frame_id for mapOptimization global odometry topic

Open PurplePegasuss opened this issue 6 months ago • 0 comments

Why the child_frame_id of publishOdometry() function is the "odom_mapping"? Shouldn't it be the lidarFrame variable?

I find it logical cause later we publish a TF from odom to lidar with the same information.

        // Publish odometry for ROS (global)
        nav_msgs::Odometry laserOdometryROS;
        laserOdometryROS.header.stamp = timeLaserInfoStamp;
        laserOdometryROS.header.frame_id = odometryFrame;
        laserOdometryROS.child_frame_id = "odom_mapping";
        laserOdometryROS.pose.pose.position.x = transformTobeMapped[3];
        laserOdometryROS.pose.pose.position.y = transformTobeMapped[4];
        laserOdometryROS.pose.pose.position.z = transformTobeMapped[5];
        laserOdometryROS.pose.pose.orientation = tf::createQuaternionMsgFromRollPitchYaw(transformTobeMapped[0], transformTobeMapped[1], transformTobeMapped[2]);
        pubLaserOdometryGlobal.publish(laserOdometryROS);
        
        // Publish TF
        static tf::TransformBroadcaster br;
        tf::Transform t_odom_to_lidar = tf::Transform(tf::createQuaternionFromRPY(transformTobeMapped[0], transformTobeMapped[1], transformTobeMapped[2]),
                                                      tf::Vector3(transformTobeMapped[3], transformTobeMapped[4], transformTobeMapped[5]));
        
        ```

PurplePegasuss avatar Dec 21 '23 13:12 PurplePegasuss