diff --git a/launch/mapping_horizon.launch b/launch/mapping_horizon.launch index c240388..9c364a4 100644 --- a/launch/mapping_horizon.launch +++ b/launch/mapping_horizon.launch @@ -1,18 +1,28 @@ - + + + + + - - - + + + + + + + + + - + diff --git a/launch/mapping_mid.launch b/launch/mapping_mid.launch index 079099d..49b123b 100644 --- a/launch/mapping_mid.launch +++ b/launch/mapping_mid.launch @@ -1,14 +1,24 @@ - + + + + + - - - + + + + + + + + + diff --git a/launch/mapping_outdoor.launch b/launch/mapping_outdoor.launch index 3842181..f1442bb 100644 --- a/launch/mapping_outdoor.launch +++ b/launch/mapping_outdoor.launch @@ -1,14 +1,25 @@ + + + + + - - - + + + + + + + + + diff --git a/src/laserMapping.cpp b/src/laserMapping.cpp index 308caa5..f4d136a 100644 --- a/src/laserMapping.cpp +++ b/src/laserMapping.cpp @@ -381,26 +381,26 @@ void laserCloudFullResHandler(const sensor_msgs::PointCloud2ConstPtr& laserCloud int main(int argc, char** argv) { ros::init(argc, argv, "laserMapping"); - ros::NodeHandle nh; + ros::NodeHandle nh("~"); ros::Subscriber subLaserCloudCornerLast = nh.subscribe - ("/laser_cloud_sharp", 100, laserCloudCornerLastHandler); + ("cloud_sharp", 100, laserCloudCornerLastHandler); ros::Subscriber subLaserCloudSurfLast = nh.subscribe - ("/laser_cloud_flat", 100, laserCloudSurfLastHandler); + ("cloud_flat", 100, laserCloudSurfLastHandler); ros::Subscriber subLaserCloudFullRes = nh.subscribe - ("/livox_cloud", 100, laserCloudFullResHandler); + ("cloud", 100, laserCloudFullResHandler); ros::Publisher pubLaserCloudSurround = nh.advertise - ("/laser_cloud_surround", 100); + ("cloud_surround", 100); ros::Publisher pubLaserCloudSurround_corner = nh.advertise - ("/laser_cloud_surround_corner", 100); + ("cloud_surround_corner", 100); ros::Publisher pubLaserCloudFullRes = nh.advertise ("/velodyne_cloud_registered", 100); - ros::Publisher pubOdomAftMapped = nh.advertise ("/aft_mapped_to_init", 1); + ros::Publisher pubOdomAftMapped = nh.advertise ("odometry", 1); nav_msgs::Odometry odomAftMapped; odomAftMapped.header.frame_id = "/camera_init"; odomAftMapped.child_frame_id = "/aft_mapped"; diff --git a/src/scanRegistration.cpp b/src/scanRegistration.cpp index a0c9f5d..3ea276a 100644 --- a/src/scanRegistration.cpp +++ b/src/scanRegistration.cpp @@ -526,7 +526,7 @@ void laserCloudHandler(const sensor_msgs::PointCloud2ConstPtr& laserCloudMsg) int main(int argc, char** argv) { ros::init(argc, argv, "scanRegistration"); - ros::NodeHandle nh; + ros::NodeHandle nh("~"); // ros::Subscriber subLaserCloud_for_hk = nh.subscribe // ("/livox/lidar", 2, laserCloudHandler_temp); @@ -534,16 +534,16 @@ int main(int argc, char** argv) // ("/livox/lidar_temp", 2); ros::Subscriber subLaserCloud = nh.subscribe - ("/livox/lidar", 100, laserCloudHandler); + ("input", 100, laserCloudHandler); pubLaserCloud = nh.advertise - ("/livox_cloud", 20); + ("cloud", 20); pubCornerPointsSharp = nh.advertise - ("/laser_cloud_sharp", 20); + ("cloud_sharp", 20); pubSurfPointsFlat = nh.advertise - ("/laser_cloud_flat", 20); + ("cloud_flat", 20); ros::spin();