Skip to content

Commit 7b7dabe

Browse files
authored
OpenNI apps: Improve handling of command line arguments (#5494)
* #5491 * Fixed typo at line 212 in parse.h * Fixed formatting. * Deleted whitespaces. * Dependency update before attempting fix. * Fixed formatting style. * Revert . . formatting? * Weird formatting error test? * Fixed dependency, this should hopefully build. * Removed unused variable in openni_ii_normal_estimation.cpp * Build test after improvements and refactors. * Build Test #2. * deleted whitespace. * Fixed formatting errors. * Fixed formatting openni_boundary_estimation.cpp. * Fixed formatting openni_boundary_estimation.cpp. * Fixed formatting openni_boundary_estimation.cpp. * Formatting check #1. * Formatting check 2. * Deleted whitespace. * Changed general parsing structure, improved usage(). * Fixed formatting errors. * Fixed! * resolve merge conflict * resolve merge conflict * format test * new format test * test formatting * test formatting * test formatting * command line behavior mimics previous version(s), consistent help flags * rest of the files
1 parent 2beb1bb commit 7b7dabe

17 files changed

+457
-271
lines changed

apps/src/openni_3d_concave_hull.cpp

Lines changed: 29 additions & 14 deletions
Original file line numberDiff line numberDiff line change
@@ -34,6 +34,7 @@
3434
*/
3535

3636
#include <pcl/common/time.h>
37+
#include <pcl/console/parse.h>
3738
#include <pcl/filters/voxel_grid.h>
3839
#include <pcl/io/openni_camera/openni_driver.h>
3940
#include <pcl/io/openni_grabber.h>
@@ -165,19 +166,29 @@ class OpenNI3DConcaveHull {
165166
void
166167
usage(char** argv)
167168
{
168-
std::cout << "usage: " << argv[0] << " <device_id> <options>\n\n";
169+
std::cout << "usage: " << argv[0] << " [-device_id X (default: \"#1\")]\n\n";
169170

170171
openni_wrapper::OpenNIDriver& driver = openni_wrapper::OpenNIDriver::getInstance();
171172
if (driver.getNumberDevices() > 0) {
172173
for (unsigned deviceIdx = 0; deviceIdx < driver.getNumberDevices(); ++deviceIdx) {
173174
// clang-format off
174-
std::cout << "Device: " << deviceIdx + 1 << ", vendor: " << driver.getVendorName (deviceIdx) << ", product: " << driver.getProductName (deviceIdx)
175-
<< ", connected: " << driver.getBus (deviceIdx) << " @ " << driver.getAddress (deviceIdx) << ", serial number: \'" << driver.getSerialNumber (deviceIdx) << "\'" << std::endl;
176-
std::cout << "device_id may be #1, #2, ... for the first second etc device in the list or" << std::endl
177-
<< " bus@address for the device connected to a specific usb-bus / address combination (works only in Linux) or" << std::endl
178-
<< " <serial-number> (only in Linux and for devices which provide serial numbers)" << std::endl;
175+
std::cout << "Device: " << deviceIdx + 1
176+
<< ", vendor: " << driver.getVendorName (deviceIdx)
177+
<< ", product: " << driver.getProductName (deviceIdx)
178+
<< ", connected: " << driver.getBus (deviceIdx) << " @ " << driver.getAddress (deviceIdx) << ", serial number: \'" << driver.getSerialNumber (deviceIdx) << "\'"
179+
<< std::endl;
179180
// clang-format on
180181
}
182+
183+
std::cout << "\ndevice_id may be:" << std::endl
184+
<< " #1, #2, ... for the first second etc device in the list or"
185+
<< std::endl
186+
187+
<< " bus@address for the device connected to a specific "
188+
"usb-bus/address combination (works only in Linux) or"
189+
190+
<< " <serial-number> (only in Linux and for devices which provide "
191+
"serial numbers)";
181192
}
182193
else
183194
std::cout << "No devices connected." << std::endl;
@@ -186,24 +197,28 @@ usage(char** argv)
186197
int
187198
main(int argc, char** argv)
188199
{
189-
std::string arg;
190-
if (argc > 1)
191-
arg = std::string(argv[1]);
192-
193-
if (arg == "--help" || arg == "-h") {
200+
/////////////////////////////////////////////////////////////////////
201+
if (pcl::console::find_argument(argc, argv, "-h") != -1 ||
202+
pcl::console::find_argument(argc, argv, "--help") != -1) {
194203
usage(argv);
195204
return 1;
196205
}
197206

198-
pcl::OpenNIGrabber grabber(arg);
207+
std::string device_id = "";
208+
if (pcl::console::parse_argument(argc, argv, "-device_id", device_id) == -1 &&
209+
argc > 1 && argv[1][0] != '-')
210+
device_id = argv[1];
211+
/////////////////////////////////////////////////////////////////////
212+
213+
pcl::OpenNIGrabber grabber(device_id);
199214
if (grabber.providesCallback<pcl::OpenNIGrabber::sig_cb_openni_point_cloud_rgba>()) {
200215
PCL_INFO("PointXYZRGBA mode enabled.\n");
201-
OpenNI3DConcaveHull<pcl::PointXYZRGBA> v(arg);
216+
OpenNI3DConcaveHull<pcl::PointXYZRGBA> v(device_id);
202217
v.run();
203218
}
204219
else {
205220
PCL_INFO("PointXYZ mode enabled.\n");
206-
OpenNI3DConcaveHull<pcl::PointXYZ> v(arg);
221+
OpenNI3DConcaveHull<pcl::PointXYZ> v(device_id);
207222
v.run();
208223
}
209224
return 0;

apps/src/openni_3d_convex_hull.cpp

Lines changed: 29 additions & 14 deletions
Original file line numberDiff line numberDiff line change
@@ -34,6 +34,7 @@
3434
*/
3535

3636
#include <pcl/common/time.h>
37+
#include <pcl/console/parse.h>
3738
#include <pcl/filters/passthrough.h>
3839
#include <pcl/io/openni_camera/openni_driver.h>
3940
#include <pcl/io/openni_grabber.h>
@@ -163,19 +164,29 @@ class OpenNI3DConvexHull {
163164
void
164165
usage(char** argv)
165166
{
166-
std::cout << "usage: " << argv[0] << " <device_id> <options>\n\n";
167+
std::cout << "usage: " << argv[0] << " [-device_id X (default: \"#1\")]\n\n";
167168

168169
openni_wrapper::OpenNIDriver& driver = openni_wrapper::OpenNIDriver::getInstance();
169170
if (driver.getNumberDevices() > 0) {
170171
for (unsigned deviceIdx = 0; deviceIdx < driver.getNumberDevices(); ++deviceIdx) {
171172
// clang-format off
172-
std::cout << "Device: " << deviceIdx + 1 << ", vendor: " << driver.getVendorName (deviceIdx) << ", product: " << driver.getProductName (deviceIdx)
173-
<< ", connected: " << driver.getBus (deviceIdx) << " @ " << driver.getAddress (deviceIdx) << ", serial number: \'" << driver.getSerialNumber (deviceIdx) << "\'" << std::endl;
174-
std::cout << "device_id may be #1, #2, ... for the first second etc device in the list or" << std::endl
175-
<< " bus@address for the device connected to a specific usb-bus / address combination (works only in Linux) or" << std::endl
176-
<< " <serial-number> (only in Linux and for devices which provide serial numbers)" << std::endl;
173+
std::cout << "Device: " << deviceIdx + 1
174+
<< ", vendor: " << driver.getVendorName (deviceIdx)
175+
<< ", product: " << driver.getProductName (deviceIdx)
176+
<< ", connected: " << driver.getBus (deviceIdx) << " @ " << driver.getAddress (deviceIdx) << ", serial number: \'" << driver.getSerialNumber (deviceIdx) << "\'"
177+
<< std::endl;
177178
// clang-format on
178179
}
180+
181+
std::cout << "\ndevice_id may be:" << std::endl
182+
<< " #1, #2, ... for the first second etc device in the list or"
183+
<< std::endl
184+
185+
<< " bus@address for the device connected to a specific "
186+
"usb-bus/address combination (works only in Linux) or"
187+
188+
<< " <serial-number> (only in Linux and for devices which provide "
189+
"serial numbers)";
179190
}
180191
else
181192
std::cout << "No devices connected." << std::endl;
@@ -184,24 +195,28 @@ usage(char** argv)
184195
int
185196
main(int argc, char** argv)
186197
{
187-
std::string arg;
188-
if (argc > 1)
189-
arg = std::string(argv[1]);
190-
191-
if (arg == "--help" || arg == "-h") {
198+
/////////////////////////////////////////////////////////////////////
199+
if (pcl::console::find_argument(argc, argv, "-h") != -1 ||
200+
pcl::console::find_argument(argc, argv, "--help") != -1) {
192201
usage(argv);
193202
return 1;
194203
}
195204

196-
pcl::OpenNIGrabber grabber(arg);
205+
std::string device_id = "";
206+
if (pcl::console::parse_argument(argc, argv, "-device_id", device_id) == -1 &&
207+
argc > 1 && argv[1][0] != '-')
208+
device_id = argv[1];
209+
/////////////////////////////////////////////////////////////////////
210+
211+
pcl::OpenNIGrabber grabber(device_id);
197212
if (grabber.providesCallback<pcl::OpenNIGrabber::sig_cb_openni_point_cloud_rgba>()) {
198213
PCL_INFO("PointXYZRGBA mode enabled.\n");
199-
OpenNI3DConvexHull<pcl::PointXYZRGBA> v(arg);
214+
OpenNI3DConvexHull<pcl::PointXYZRGBA> v(device_id);
200215
v.run();
201216
}
202217
else {
203218
PCL_INFO("PointXYZ mode enabled.\n");
204-
OpenNI3DConvexHull<pcl::PointXYZ> v(arg);
219+
OpenNI3DConvexHull<pcl::PointXYZ> v(device_id);
205220
v.run();
206221
}
207222
return 0;

apps/src/openni_boundary_estimation.cpp

Lines changed: 28 additions & 13 deletions
Original file line numberDiff line numberDiff line change
@@ -36,6 +36,7 @@
3636
*/
3737

3838
#include <pcl/common/time.h>
39+
#include <pcl/console/parse.h>
3940
#include <pcl/features/boundary.h>
4041
#include <pcl/features/integral_image_normal.h>
4142
#include <pcl/filters/approximate_voxel_grid.h>
@@ -180,19 +181,29 @@ class OpenNIIntegralImageNormalEstimation {
180181
void
181182
usage(char** argv)
182183
{
183-
std::cout << "usage: " << argv[0] << " <device_id> <options>\n\n";
184+
std::cout << "usage: " << argv[0] << " [-device_id X (default: \"#1\")]\n\n";
184185

185186
openni_wrapper::OpenNIDriver& driver = openni_wrapper::OpenNIDriver::getInstance();
186187
if (driver.getNumberDevices() > 0) {
187188
for (unsigned deviceIdx = 0; deviceIdx < driver.getNumberDevices(); ++deviceIdx) {
188189
// clang-format off
189-
std::cout << "Device: " << deviceIdx + 1 << ", vendor: " << driver.getVendorName (deviceIdx) << ", product: " << driver.getProductName (deviceIdx)
190-
<< ", connected: " << driver.getBus (deviceIdx) << " @ " << driver.getAddress (deviceIdx) << ", serial number: \'" << driver.getSerialNumber (deviceIdx) << "\'" << std::endl;
191-
std::cout << "device_id may be #1, #2, ... for the first second etc device in the list or" << std::endl
192-
<< " bus@address for the device connected to a specific usb-bus / address combination (works only in Linux) or" << std::endl
193-
<< " <serial-number> (only in Linux and for devices which provide serial numbers)" << std::endl;
190+
std::cout << "Device: " << deviceIdx + 1
191+
<< ", vendor: " << driver.getVendorName (deviceIdx)
192+
<< ", product: " << driver.getProductName (deviceIdx)
193+
<< ", connected: " << driver.getBus (deviceIdx) << " @ " << driver.getAddress (deviceIdx) << ", serial number: \'" << driver.getSerialNumber (deviceIdx) << "\'"
194+
<< std::endl;
194195
// clang-format on
195196
}
197+
198+
std::cout << "\ndevice_id may be:" << std::endl
199+
<< " #1, #2, ... for the first second etc device in the list or"
200+
<< std::endl
201+
202+
<< " bus@address for the device connected to a specific "
203+
"usb-bus/address combination (works only in Linux) or"
204+
205+
<< " <serial-number> (only in Linux and for devices which provide "
206+
"serial numbers)";
196207
}
197208
else
198209
std::cout << "No devices connected." << std::endl;
@@ -201,18 +212,22 @@ usage(char** argv)
201212
int
202213
main(int argc, char** argv)
203214
{
204-
std::string arg;
205-
if (argc > 1)
206-
arg = std::string(argv[1]);
207-
208-
if (arg == "--help" || arg == "-h") {
215+
/////////////////////////////////////////////////////////////////////
216+
if (pcl::console::find_argument(argc, argv, "-h") != -1 ||
217+
pcl::console::find_argument(argc, argv, "--help") != -1) {
209218
usage(argv);
210219
return 1;
211220
}
212221

213-
pcl::OpenNIGrabber grabber(arg);
222+
std::string device_id = "";
223+
if (pcl::console::parse_argument(argc, argv, "-device_id", device_id) == -1 &&
224+
argc > 1 && argv[1][0] != '-')
225+
device_id = argv[1];
226+
/////////////////////////////////////////////////////////////////////
227+
228+
pcl::OpenNIGrabber grabber(device_id);
214229
if (grabber.providesCallback<pcl::OpenNIGrabber::sig_cb_openni_point_cloud_rgb>()) {
215-
OpenNIIntegralImageNormalEstimation v(arg);
230+
OpenNIIntegralImageNormalEstimation v(device_id);
216231
v.run();
217232
}
218233
else

apps/src/openni_color_filter.cpp

Lines changed: 29 additions & 17 deletions
Original file line numberDiff line numberDiff line change
@@ -159,21 +159,33 @@ class OpenNIPassthrough {
159159
void
160160
usage(char** argv)
161161
{
162-
std::cout << "usage: " << argv[0]
163-
<< " <device_id> [-rgb <red> <green> <blue> [-radius <radius>] ]\n\n"
164-
<< std::endl;
162+
std::cout << "usage: " << argv[0] << " [options]\n\n"
163+
<< "where options are:\n"
164+
<< " -device_id X: specify the device id (default: \"#1\").\n"
165+
<< " -rgb R G B: -- (default: 0 0 0)\n"
166+
<< " -radius X: -- (default: 442)\n\n";
165167

166168
openni_wrapper::OpenNIDriver& driver = openni_wrapper::OpenNIDriver::getInstance();
167169
if (driver.getNumberDevices() > 0) {
168170
for (unsigned deviceIdx = 0; deviceIdx < driver.getNumberDevices(); ++deviceIdx) {
169171
// clang-format off
170-
std::cout << "Device: " << deviceIdx + 1 << ", vendor: " << driver.getVendorName (deviceIdx) << ", product: " << driver.getProductName (deviceIdx)
171-
<< ", connected: " << (int)driver.getBus (deviceIdx) << " @ " << (int)driver.getAddress (deviceIdx) << ", serial number: \'" << driver.getSerialNumber (deviceIdx) << "\'" << std::endl;
172-
std::cout << "device_id may be #1, #2, ... for the first second etc device in the list or" << std::endl
173-
<< " bus@address for the device connected to a specific usb-bus / address combination (works only in Linux) or" << std::endl
174-
<< " <serial-number> (only in Linux and for devices which provide serial numbers)" << std::endl;
172+
std::cout << "Device: " << deviceIdx + 1
173+
<< ", vendor: " << driver.getVendorName (deviceIdx)
174+
<< ", product: " << driver.getProductName (deviceIdx)
175+
<< ", connected: " << driver.getBus (deviceIdx) << " @ " << driver.getAddress (deviceIdx) << ", serial number: \'" << driver.getSerialNumber (deviceIdx) << "\'"
176+
<< std::endl;
175177
// clang-format on
176178
}
179+
180+
std::cout << "\ndevice_id may be:" << std::endl
181+
<< " #1, #2, ... for the first second etc device in the list or"
182+
<< std::endl
183+
184+
<< " bus@address for the device connected to a specific "
185+
"usb-bus/address combination (works only in Linux) or"
186+
187+
<< " <serial-number> (only in Linux and for devices which provide "
188+
"serial numbers)";
177189
}
178190
else
179191
std::cout << "No devices connected." << std::endl;
@@ -182,22 +194,21 @@ usage(char** argv)
182194
int
183195
main(int argc, char** argv)
184196
{
185-
if (argc < 2) {
186-
usage(argv);
187-
return 1;
188-
}
189-
190-
std::string arg(argv[1]);
191-
192-
if (arg == "--help" || arg == "-h") {
197+
/////////////////////////////////////////////////////////////////////
198+
if (pcl::console::find_argument(argc, argv, "-h") != -1 ||
199+
pcl::console::find_argument(argc, argv, "--help") != -1) {
193200
usage(argv);
194201
return 1;
195202
}
196203

204+
std::string device_id = "";
197205
unsigned char red = 0, green = 0, blue = 0;
198206
int rr, gg, bb;
199207
unsigned char radius = 442; // all colors!
200208

209+
if (pcl::console::parse_argument(argc, argv, "-device_id", device_id) == -1 &&
210+
argc > 1 && argv[1][0] != '-')
211+
device_id = argv[1];
201212
if (pcl::console::parse_3x_arguments(argc, argv, "-rgb", rr, gg, bb, true) != -1) {
202213
std::cout << "-rgb present" << std::endl;
203214
int rad;
@@ -213,8 +224,9 @@ main(int argc, char** argv)
213224
if (bb >= 0 && bb < 256)
214225
blue = (unsigned char)bb;
215226
}
227+
/////////////////////////////////////////////////////////////////////
216228

217-
pcl::OpenNIGrabber grabber(arg);
229+
pcl::OpenNIGrabber grabber(device_id);
218230

219231
if (grabber.providesCallback<pcl::OpenNIGrabber::sig_cb_openni_point_cloud_rgba>()) {
220232
OpenNIPassthrough<pcl::PointXYZRGBA> v(grabber, red, green, blue, radius);

0 commit comments

Comments
 (0)