Skip to content

Commit

Permalink
Merge pull request #11 from miguelcastillon/fix/input-cloud-param
Browse files Browse the repository at this point in the history
Using param /node_topic as cloud input
  • Loading branch information
LimHyungTae authored Jun 18, 2024
2 parents 71f2104 + 7420631 commit b4a41ad
Showing 1 changed file with 2 additions and 1 deletion.
3 changes: 2 additions & 1 deletion src/travel_run.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -90,6 +90,7 @@ int main(int argc, char **argv) {

// Set Parameters
std::string cloud_topic_;
nh.param<string> ("/node_topic" , cloud_topic_, "/ouster/points");
std::cout << "\033[1;32m" << "Cloud topic: " << cloud_topic_ << "\033[0m" << std::endl;
nh.param<bool> ("/save_results/save_labels" , save_labels_, false);
nh.param<string> ("/save_results/abs_save_dir" , abs_save_dir_, "");
Expand Down Expand Up @@ -167,7 +168,7 @@ int main(int argc, char **argv) {
pub_ground_cloud = nh.advertise<sensor_msgs::PointCloud2>("travel/ground_pc", 1);
pub_labeled_cloud = nh.advertise<sensor_msgs::PointCloud2>("travel/segmented_pc", 1);

ros::Subscriber sub_ptCloud = nh.subscribe<sensor_msgs::PointCloud2>("/ouster/points", 4000, callbackCloud, ros::TransportHints().tcpNoDelay());
ros::Subscriber sub_ptCloud = nh.subscribe<sensor_msgs::PointCloud2>(cloud_topic_, 4000, callbackCloud, ros::TransportHints().tcpNoDelay());
ros::spin();

return 0;
Expand Down

0 comments on commit b4a41ad

Please sign in to comment.