Skip to content

Commit

Permalink
PointCloudLibrary#5475 Allow read device_id from the command line arg…
Browse files Browse the repository at this point in the history
…s to be used in o… (PointCloudLibrary#5477)

* PointCloudLibrary#5475 Allow read device_id from the command line args to be used in openni_3d_concave_hull.cpp.

* PointCloudLibrary#5475 Fixed 8 more files in apps/src.

* Updated help option return value.

* Fixed faulty if statement in openni_voxel_grid.cpp.

* Revert "Fixed faulty if statement in openni_voxel_grid.cpp."

This reverts commit bf112aa.

* Revert "Updated help option return value."

This reverts commit 7dc224d.

* Reverted previous changes.

* Fixed formatting errors.

* Fixed formatting errors.

* Fixed formatting errors.

* Declared argument variable.

* Renamed argument variable for openni_mobile_server.cpp

* Allowed device_id to still be an optional parameter.

* Changed formatting.

* Revert "Changed formatting."

This reverts commit 3de27c1.

* Revert "Allowed device_id to still be an optional parameter."

This reverts commit 652f346.

* Applied previously made changes.

* Fished inconsistent variable naming in openni_mobile_server.cpp.
  • Loading branch information
filbert14 authored Oct 25, 2022
1 parent 41e8332 commit 377d6a9
Show file tree
Hide file tree
Showing 9 changed files with 38 additions and 25 deletions.
6 changes: 3 additions & 3 deletions apps/src/openni_3d_concave_hull.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -195,15 +195,15 @@ main(int argc, char** argv)
return 1;
}

pcl::OpenNIGrabber grabber("");
pcl::OpenNIGrabber grabber(arg);
if (grabber.providesCallback<pcl::OpenNIGrabber::sig_cb_openni_point_cloud_rgba>()) {
PCL_INFO("PointXYZRGBA mode enabled.\n");
OpenNI3DConcaveHull<pcl::PointXYZRGBA> v("");
OpenNI3DConcaveHull<pcl::PointXYZRGBA> v(arg);
v.run();
}
else {
PCL_INFO("PointXYZ mode enabled.\n");
OpenNI3DConcaveHull<pcl::PointXYZ> v("");
OpenNI3DConcaveHull<pcl::PointXYZ> v(arg);
v.run();
}
return 0;
Expand Down
6 changes: 3 additions & 3 deletions apps/src/openni_3d_convex_hull.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -193,15 +193,15 @@ main(int argc, char** argv)
return 1;
}

pcl::OpenNIGrabber grabber("");
pcl::OpenNIGrabber grabber(arg);
if (grabber.providesCallback<pcl::OpenNIGrabber::sig_cb_openni_point_cloud_rgba>()) {
PCL_INFO("PointXYZRGBA mode enabled.\n");
OpenNI3DConvexHull<pcl::PointXYZRGBA> v("");
OpenNI3DConvexHull<pcl::PointXYZRGBA> v(arg);
v.run();
}
else {
PCL_INFO("PointXYZ mode enabled.\n");
OpenNI3DConvexHull<pcl::PointXYZ> v("");
OpenNI3DConvexHull<pcl::PointXYZ> v(arg);
v.run();
}
return 0;
Expand Down
4 changes: 2 additions & 2 deletions apps/src/openni_boundary_estimation.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -210,9 +210,9 @@ main(int argc, char** argv)
return 1;
}

pcl::OpenNIGrabber grabber("");
pcl::OpenNIGrabber grabber(arg);
if (grabber.providesCallback<pcl::OpenNIGrabber::sig_cb_openni_point_cloud_rgb>()) {
OpenNIIntegralImageNormalEstimation v("");
OpenNIIntegralImageNormalEstimation v(arg);
v.run();
}
else
Expand Down
6 changes: 3 additions & 3 deletions apps/src/openni_fast_mesh.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -189,15 +189,15 @@ main(int argc, char** argv)
return 1;
}

pcl::OpenNIGrabber grabber("");
pcl::OpenNIGrabber grabber(arg);
if (grabber.providesCallback<pcl::OpenNIGrabber::sig_cb_openni_point_cloud_rgba>()) {
PCL_INFO("PointXYZRGBA mode enabled.\n");
OpenNIFastMesh<pcl::PointXYZRGBA> v("");
OpenNIFastMesh<pcl::PointXYZRGBA> v(arg);
v.run(argc, argv);
}
else {
PCL_INFO("PointXYZ mode enabled.\n");
OpenNIFastMesh<pcl::PointXYZ> v("");
OpenNIFastMesh<pcl::PointXYZ> v(arg);
v.run(argc, argv);
}
return 0;
Expand Down
10 changes: 7 additions & 3 deletions apps/src/openni_feature_persistence.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -266,6 +266,10 @@ main(int argc, char** argv)
"MultiscaleFeaturePersistence class using the FPFH features\n"
<< "Use \"-h\" to get more info about the available options.\n";

std::string arg = "";
if ((argc > 1) && (argv[1][0] != '-'))
arg = std::string(argv[1]);

if (pcl::console::find_argument(argc, argv, "-h") == -1) {
usage(argv);
return 1;
Expand All @@ -286,17 +290,17 @@ main(int argc, char** argv)
float alpha = default_alpha;
pcl::console::parse_argument(argc, argv, "-persistence_alpha", alpha);

pcl::OpenNIGrabber grabber("");
pcl::OpenNIGrabber grabber(arg);
if (grabber.providesCallback<pcl::OpenNIGrabber::sig_cb_openni_point_cloud_rgba>()) {
PCL_INFO("PointXYZRGBA mode enabled.\n");
OpenNIFeaturePersistence<pcl::PointXYZRGBA> v(
subsampling_leaf_size, normal_search_radius, scales_vector, alpha, "");
subsampling_leaf_size, normal_search_radius, scales_vector, alpha, arg);
v.run();
}
else {
PCL_INFO("PointXYZ mode enabled.\n");
OpenNIFeaturePersistence<pcl::PointXYZ> v(
subsampling_leaf_size, normal_search_radius, scales_vector, alpha, "");
subsampling_leaf_size, normal_search_radius, scales_vector, alpha, arg);
v.run();
}

Expand Down
6 changes: 3 additions & 3 deletions apps/src/openni_ii_normal_estimation.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -230,15 +230,15 @@ main(int argc, char** argv)
std::cout << "<Q,q> quit\n\n";
// clang-format on

pcl::OpenNIGrabber grabber("");
pcl::OpenNIGrabber grabber(arg);
if (grabber.providesCallback<pcl::OpenNIGrabber::sig_cb_openni_point_cloud_rgba>()) {
PCL_INFO("PointXYZRGBA mode enabled.\n");
OpenNIIntegralImageNormalEstimation<pcl::PointXYZRGBA> v("");
OpenNIIntegralImageNormalEstimation<pcl::PointXYZRGBA> v(arg);
v.run();
}
else {
PCL_INFO("PointXYZ mode enabled.\n");
OpenNIIntegralImageNormalEstimation<pcl::PointXYZ> v("");
OpenNIIntegralImageNormalEstimation<pcl::PointXYZ> v(arg);
v.run();
}

Expand Down
9 changes: 6 additions & 3 deletions apps/src/openni_mobile_server.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -221,7 +221,7 @@ class PCLMobileServer {
void
usage(char** argv)
{
std::cout << "usage: " << argv[0] << " <options>\n"
std::cout << "usage: " << argv[0] << " <device_id> <options>\n"
<< "where options are:\n"
<< " -port p :: set the server port (default: 11111)\n"
<< " -leaf x, y, z :: set the voxel grid leaf size (default: 0.01)\n";
Expand All @@ -230,19 +230,22 @@ usage(char** argv)
int
main(int argc, char** argv)
{
std::string device_id = "";
if ((argc > 1) && (argv[1][0] != '-'))
device_id = std::string(argv[1]);

if (pcl::console::find_argument(argc, argv, "-h") != -1) {
usage(argv);
return 0;
}

int port = 11111;
float leaf_x = 0.01f, leaf_y = 0.01f, leaf_z = 0.01f;
std::string device_id;

pcl::console::parse_argument(argc, argv, "-port", port);
pcl::console::parse_3x_arguments(argc, argv, "-leaf", leaf_x, leaf_y, leaf_z, false);

pcl::OpenNIGrabber grabber("");
pcl::OpenNIGrabber grabber(device_id);
if (!grabber.providesCallback<pcl::OpenNIGrabber::sig_cb_openni_point_cloud_rgba>()) {
std::cout << "OpenNI grabber does not provide the rgba cloud format." << std::endl;
return 1;
Expand Down
2 changes: 1 addition & 1 deletion apps/src/openni_organized_edge_detection.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -325,7 +325,7 @@ main(int argc, char** argv)
//std::cout << "<5> EDGELABEL_RGB_CANNY edge" << std::endl;
std::cout << "<Q,q> quit" << std::endl;
// clang-format on
pcl::OpenNIGrabber grabber("");
pcl::OpenNIGrabber grabber(arg);
if (grabber.providesCallback<pcl::OpenNIGrabber::sig_cb_openni_point_cloud_rgb>()) {
OpenNIOrganizedEdgeDetection app;
app.run();
Expand Down
14 changes: 10 additions & 4 deletions apps/src/openni_voxel_grid.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -169,8 +169,14 @@ usage(char** argv)
int
main(int argc, char** argv)
{
if (pcl::console::find_argument(argc, argv, "-h") != -1)
std::string arg = "";
if ((argc > 1) && (argv[1][0] != '-'))
arg = std::string(argv[1]);

if (pcl::console::find_argument(argc, argv, "-h") != -1) {
usage(argv);
return 1;
}

float min_v = 0.0f, max_v = 5.0f;
pcl::console::parse_2x_arguments(argc, argv, "-minmax", min_v, max_v);
Expand All @@ -182,15 +188,15 @@ main(int argc, char** argv)
pcl::console::parse_3x_arguments(argc, argv, "-leaf", leaf_x, leaf_y, leaf_z);
PCL_INFO("Using %f, %f, %f as a leaf size for VoxelGrid.\n", leaf_x, leaf_y, leaf_z);

pcl::OpenNIGrabber grabber("");
pcl::OpenNIGrabber grabber(arg);
if (grabber.providesCallback<pcl::OpenNIGrabber::sig_cb_openni_point_cloud_rgba>()) {
OpenNIVoxelGrid<pcl::PointXYZRGBA> v(
"", field_name, min_v, max_v, leaf_x, leaf_y, leaf_z);
arg, field_name, min_v, max_v, leaf_x, leaf_y, leaf_z);
v.run();
}
else {
OpenNIVoxelGrid<pcl::PointXYZ> v(
"", field_name, min_v, max_v, leaf_x, leaf_y, leaf_z);
arg, field_name, min_v, max_v, leaf_x, leaf_y, leaf_z);
v.run();
}

Expand Down

0 comments on commit 377d6a9

Please sign in to comment.