@@ -86,11 +86,17 @@ int main(int argc, char *argv[]) {
86
86
std::vector<std::string> arguments (argv, argv + argc);
87
87
ob::Context::setLoggerSeverity (OB_LOG_SEVERITY_OFF);
88
88
89
- // Create OrbbecSDK pipeline (with default device).
90
- ob::Pipeline obPipeline;
89
+ std::shared_ptr<ob::Pipeline> obPipeline;
90
+ try {
91
+ // Create OrbbecSDK pipeline (with default device).
92
+ obPipeline = std::make_shared<ob::Pipeline>();
93
+ } catch (ob::Error &e) {
94
+ std::cerr << " Make sure your Orbbec device is connected!" << std::endl;
95
+ return EXIT_FAILURE;
96
+ }
91
97
92
98
// Create Spectacular AI orbbec plugin configuration (depends on device type).
93
- spectacularAI::orbbecPlugin::Configuration config (obPipeline);
99
+ spectacularAI::orbbecPlugin::Configuration config (* obPipeline);
94
100
95
101
int exposureValue = -1 ;
96
102
int whiteBalanceKelvins = -1 ;
@@ -140,9 +146,9 @@ int main(int argc, char *argv[]) {
140
146
}
141
147
142
148
// Create vio pipeline using the config & setup orbbec pipeline
143
- spectacularAI::orbbecPlugin::Pipeline vioPipeline (obPipeline, config);
149
+ spectacularAI::orbbecPlugin::Pipeline vioPipeline (* obPipeline, config);
144
150
145
- auto device = obPipeline. getDevice ();
151
+ auto device = obPipeline-> getDevice ();
146
152
if (exposureValue >= 0 ) {
147
153
if (!setCameraProperty (device, OB_PROP_COLOR_AUTO_EXPOSURE_BOOL, false , " OB_PROP_COLOR_AUTO_EXPOSURE_BOOL" )) return EXIT_FAILURE;
148
154
if (!setCameraProperty (device, OB_PROP_COLOR_EXPOSURE_INT, exposureValue, " OB_PROP_COLOR_EXPOSURE_INT" )) return EXIT_FAILURE;
0 commit comments