diff --git a/src/travel_run.cpp b/src/travel_run.cpp index 3b627bf..b4ce2e6 100644 --- a/src/travel_run.cpp +++ b/src/travel_run.cpp @@ -90,6 +90,7 @@ int main(int argc, char **argv) { // Set Parameters std::string cloud_topic_; + nh.param ("/node_topic" , cloud_topic_, "/ouster/points"); std::cout << "\033[1;32m" << "Cloud topic: " << cloud_topic_ << "\033[0m" << std::endl; nh.param ("/save_results/save_labels" , save_labels_, false); nh.param ("/save_results/abs_save_dir" , abs_save_dir_, ""); @@ -167,7 +168,7 @@ int main(int argc, char **argv) { pub_ground_cloud = nh.advertise("travel/ground_pc", 1); pub_labeled_cloud = nh.advertise("travel/segmented_pc", 1); - ros::Subscriber sub_ptCloud = nh.subscribe("/ouster/points", 4000, callbackCloud, ros::TransportHints().tcpNoDelay()); + ros::Subscriber sub_ptCloud = nh.subscribe(cloud_topic_, 4000, callbackCloud, ros::TransportHints().tcpNoDelay()); ros::spin(); return 0;