Skip to content

Commit

Permalink
Add true on latch options
Browse files Browse the repository at this point in the history
  • Loading branch information
LimHyungTae committed Oct 20, 2022
1 parent 2992a98 commit f066bac
Show file tree
Hide file tree
Showing 5 changed files with 23 additions and 23 deletions.
12 changes: 6 additions & 6 deletions nodes/offline_kitti.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -93,12 +93,12 @@ int main(int argc, char**argv) {
nh.param<string>("/seq", seq, "00");
nh.param<string>("/data_path", data_path, "/");

CloudPublisher = nh.advertise<sensor_msgs::PointCloud2>("/benchmark/cloud", 100);
TPPublisher = nh.advertise<sensor_msgs::PointCloud2>("/benchmark/TP", 100);
FPPublisher = nh.advertise<sensor_msgs::PointCloud2>("/benchmark/FP", 100);
FNPublisher = nh.advertise<sensor_msgs::PointCloud2>("/benchmark/FN", 100);
PrecisionPublisher = nh.advertise<visualization_msgs::Marker>("/precision", 1);
RecallPublisher = nh.advertise<visualization_msgs::Marker>("/recall", 1);
CloudPublisher = nh.advertise<sensor_msgs::PointCloud2>("/benchmark/cloud", 100, true);
TPPublisher = nh.advertise<sensor_msgs::PointCloud2>("/benchmark/TP", 100, true);
FPPublisher = nh.advertise<sensor_msgs::PointCloud2>("/benchmark/FP", 100, true);
FNPublisher = nh.advertise<sensor_msgs::PointCloud2>("/benchmark/FN", 100, true);
PrecisionPublisher = nh.advertise<visualization_msgs::Marker>("/precision", 1, true);
RecallPublisher = nh.advertise<visualization_msgs::Marker>("/recall", 1, true);

signal(SIGINT, signal_callback_handler);

Expand Down
6 changes: 3 additions & 3 deletions nodes/offline_own_data.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -50,9 +50,9 @@ int main(int argc, char **argv) {

PatchworkGroundSeg.reset(new PatchWork<PointType>(&nh));

CloudPublisher = nh.advertise<sensor_msgs::PointCloud2>("/benchmark/cloud", 100);
PositivePublisher = nh.advertise<sensor_msgs::PointCloud2>("/patchwork/ground", 100);
NegativePublisher = nh.advertise<sensor_msgs::PointCloud2>("/patchwork/non_ground", 100);
CloudPublisher = nh.advertise<sensor_msgs::PointCloud2>("/benchmark/cloud", 100, true);
PositivePublisher = nh.advertise<sensor_msgs::PointCloud2>("/patchwork/ground", 100, true);
NegativePublisher = nh.advertise<sensor_msgs::PointCloud2>("/patchwork/non_ground", 100, true);

string example_filename = "/catkin_ws/src/patchwork/materials/1629959697.120137.360lidar.pcd";
string filename = std::getenv("HOME") + example_filename;
Expand Down
8 changes: 4 additions & 4 deletions nodes/pub_for_legoloam.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -82,12 +82,12 @@ int main(int argc, char **argv) {
PatchworkGroundSeg.reset(new PatchWork<PointType>(&nh));

/* Publisher for source cloud, ground, non-ground */
CloudPublisher = nh.advertise<sensor_msgs::PointCloud2>("/benchmark/cloud", 100);
PositivePublisher = nh.advertise<sensor_msgs::PointCloud2>("/benchmark/P", 100);
NegativePublisher = nh.advertise<sensor_msgs::PointCloud2>("/benchmark/N", 100);
CloudPublisher = nh.advertise<sensor_msgs::PointCloud2>("/benchmark/cloud", 100, true);
PositivePublisher = nh.advertise<sensor_msgs::PointCloud2>("/benchmark/P", 100, true);
NegativePublisher = nh.advertise<sensor_msgs::PointCloud2>("/benchmark/N", 100, true);

/* Publisher for combined msg of source cloud, ground cloud */
EstimatePublisher = nh.advertise<patchwork::ground_estimate>("/benchmark/ground_estimate", 100);
EstimatePublisher = nh.advertise<patchwork::ground_estimate>("/benchmark/ground_estimate", 100, true);

ros::Subscriber NodeSubscriber = nh.subscribe<sensor_msgs::PointCloud2>("/node", 5000, callbackNode);

Expand Down
18 changes: 9 additions & 9 deletions nodes/ros_kitti.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -153,15 +153,15 @@ int main(int argc, char **argv) {

PatchworkGroundSeg.reset(new PatchWork<PointType>(&nh));

CloudPublisher = nh.advertise<sensor_msgs::PointCloud2>("/benchmark/cloud", 100);
TPPublisher = nh.advertise<sensor_msgs::PointCloud2>("/benchmark/TP", 100);
FPPublisher = nh.advertise<sensor_msgs::PointCloud2>("/benchmark/FP", 100);
FNPublisher = nh.advertise<sensor_msgs::PointCloud2>("/benchmark/FN", 100);
GroundPublisher = nh.advertise<sensor_msgs::PointCloud2>("/patchwork/ground", 100);
NonGroundPublisher = nh.advertise<sensor_msgs::PointCloud2>("/patchwork/non_ground", 100);

PrecisionPublisher = nh.advertise<visualization_msgs::Marker>("/precision", 1);
RecallPublisher = nh.advertise<visualization_msgs::Marker>("/recall", 1);
CloudPublisher = nh.advertise<sensor_msgs::PointCloud2>("/benchmark/cloud", 100, true);
TPPublisher = nh.advertise<sensor_msgs::PointCloud2>("/benchmark/TP", 100, true);
FPPublisher = nh.advertise<sensor_msgs::PointCloud2>("/benchmark/FP", 100, true);
FNPublisher = nh.advertise<sensor_msgs::PointCloud2>("/benchmark/FN", 100, true);
GroundPublisher = nh.advertise<sensor_msgs::PointCloud2>("/patchwork/ground", 100, true);
NonGroundPublisher = nh.advertise<sensor_msgs::PointCloud2>("/patchwork/non_ground", 100, true);

PrecisionPublisher = nh.advertise<visualization_msgs::Marker>("/precision", 1, true);
RecallPublisher = nh.advertise<visualization_msgs::Marker>("/recall", 1, true);

ros::Subscriber NodeSubscriber = nh.subscribe<sensor_msgs::PointCloud2>("/patchwork/cloud", 5000, callbackNode);

Expand Down
2 changes: 1 addition & 1 deletion nodes/ros_kitti_publisher.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -49,7 +49,7 @@ int main(int argc, char**argv) {
nh.param<string>("/data_path", data_path, "/");

ros::Rate r(10);
ros::Publisher CloudPublisher = nh.advertise<sensor_msgs::PointCloud2>("/patchwork/cloud", 100);
ros::Publisher CloudPublisher = nh.advertise<sensor_msgs::PointCloud2>("/patchwork/cloud", 100, true);

signal(SIGINT, signal_callback_handler);

Expand Down

0 comments on commit f066bac

Please sign in to comment.