void CameraGigeAravis::acqStop(){ arv_stream_get_statistics(stream, &nbCompletedBuffers, &nbFailures, &nbUnderruns); //cout << "Completed buffers = " << (unsigned long long) nbCompletedBuffers << endl; //cout << "Failures = " << (unsigned long long) nbFailures << endl; //cout << "Underruns = " << (unsigned long long) nbUnderruns << endl; BOOST_LOG_SEV(logger, notification) << "Completed buffers = " << (unsigned long long) nbCompletedBuffers; BOOST_LOG_SEV(logger, notification) << "Failures = " << (unsigned long long) nbFailures; BOOST_LOG_SEV(logger, notification) << "Underruns = " << (unsigned long long) nbUnderruns; BOOST_LOG_SEV(logger, notification) << "Stopping acquisition..."; arv_camera_stop_acquisition(camera); BOOST_LOG_SEV(logger, notification) << "Acquisition stopped."; BOOST_LOG_SEV(logger, notification) << "Unreferencing stream."; g_object_unref(stream); stream = NULL; BOOST_LOG_SEV(logger, notification) << "Unreferencing camera."; g_object_unref(camera); camera = NULL; }
int main(int argc, char *argv[]) { ArvDevice *device; ArvStream *stream; ArvCamera *camera; ArvGcFeatureNode *feature; guint64 n_completed_buffers; guint64 n_failures; guint64 n_underruns; GOptionContext *context; GError *error = NULL; void (*old_sigint_handler)(int); int i, payload; arv_g_thread_init (NULL); arv_g_type_init (); context = g_option_context_new (NULL); g_option_context_set_summary (context, "Test of heartbeat robustness while continuously changing a feature."); g_option_context_add_main_entries (context, arv_option_entries, NULL); if (!g_option_context_parse (context, &argc, &argv, &error)) { g_option_context_free (context); g_print ("Option parsing failed: %s\n", error->message); g_error_free (error); return EXIT_FAILURE; } g_option_context_free (context); arv_debug_enable (arv_option_debug_domains); camera = arv_camera_new (arv_option_camera_name); if (!ARV_IS_CAMERA (camera)) { printf ("Device not found\n"); return EXIT_FAILURE; } device = arv_camera_get_device (camera); stream = arv_camera_create_stream (camera, NULL, NULL); if (!ARV_IS_STREAM (stream)) { printf ("Invalid device\n"); } else { payload = arv_camera_get_payload (camera); if (ARV_IS_GV_STREAM (stream)) { g_object_set (stream, //"socket-buffer", ARV_GV_STREAM_SOCKET_BUFFER_AUTO, "socket-buffer", ARV_GV_STREAM_SOCKET_BUFFER_FIXED, "socket-buffer-size", payload*6, "packet-timeout", 1000 * 1000, "frame-retention", 100 * 1000, "packet-resend", ARV_GV_STREAM_PACKET_RESEND_ALWAYS, NULL); } for (i = 0; i < 100; i++) arv_stream_push_buffer(stream, arv_buffer_new(payload, NULL)); arv_camera_set_acquisition_mode(camera, ARV_ACQUISITION_MODE_CONTINUOUS); feature = ARV_GC_FEATURE_NODE (arv_device_get_feature (device, arv_option_feature_name)); arv_camera_start_acquisition (camera); old_sigint_handler = signal (SIGINT, set_cancel); while (!cancel) { ArvBuffer *buffer = arv_stream_timeout_pop_buffer(stream, 2000000); if (buffer) { usleep(10); arv_stream_push_buffer (stream, buffer); } if (!(++i%5)) { char *value; if ((i/100) % 2 == 0) value = g_strdup_printf ("%d", arv_option_min); else value = g_strdup_printf ("%d", arv_option_max); fprintf (stderr, "Setting %s from %s to %s\n", arv_option_feature_name, arv_gc_feature_node_get_value_as_string (feature, NULL), value); arv_gc_feature_node_set_value_from_string (feature, value, NULL); g_free (value); } } signal (SIGINT, old_sigint_handler); arv_stream_get_statistics (stream, &n_completed_buffers, &n_failures, &n_underruns); printf ("\nCompleted buffers = %Lu\n", (unsigned long long) n_completed_buffers); printf ("Failures = %Lu\n", (unsigned long long) n_failures); printf ("Underruns = %Lu\n", (unsigned long long) n_underruns); arv_camera_stop_acquisition (camera); } g_object_unref (camera); return 0; }
int main (int argc, char **argv) { ArvCamera * camera; ArvStream *stream; ArvBuffer *buffer; GOptionContext *context; GError *error = NULL; char memory_buffer[100000]; int i; arv_g_thread_init (NULL); arv_g_type_init (); context = g_option_context_new (NULL); g_option_context_add_main_entries (context, arv_option_entries, NULL); if (!g_option_context_parse (context, &argc, &argv, &error)) { g_option_context_free (context); g_print ("Option parsing failed: %s\n", error->message); g_error_free (error); return EXIT_FAILURE; } g_option_context_free (context); if (arv_option_max_frames < 0) arv_option_max_errors_before_abort = -1; save_buffer_fn = GetSaveBufferFn(arv_option_save_type); arv_debug_enable (arv_option_debug_domains); if (arv_option_camera_name == NULL) g_print ("Looking for the first available camera\n"); else g_print ("Looking for camera '%s'\n", arv_option_camera_name); camera = arv_camera_new (arv_option_camera_name); int errors = 0; if (camera == NULL) { g_print("No device found"); return 1; } guint payload_size = arv_camera_get_payload(camera); g_print ("payload size = %d (0x%x)\n", payload_size, payload_size); stream = arv_camera_create_stream (camera, NULL, NULL); if (arv_option_auto_buffer) { g_object_set (stream,"socket-buffer", ARV_GV_STREAM_SOCKET_BUFFER_AUTO,"socket-buffer-size", 0,NULL); } for (i = 0; i < 30; i++) { arv_stream_push_buffer (stream, arv_buffer_new (payload_size, NULL)); } arv_camera_stop_acquisition(camera); // set the bit depth ArvDevice * device = arv_camera_get_device(camera); ArvGcNode * feature = arv_device_get_feature(device, "PixelFormat"); char * pix_format = "Mono8"; if (arv_option_pixel_format == 14) pix_format = "Mono14"; arv_gc_feature_node_set_value_from_string(ARV_GC_FEATURE_NODE(feature), pix_format, NULL); if (arv_option_pixel_format == 14) { feature = arv_device_get_feature(device, "CMOSBitDepth"); arv_gc_feature_node_set_value_from_string(ARV_GC_FEATURE_NODE(feature), "bit14bit", NULL); } signal (SIGINT, set_cancel); signal (SIGQUIT, set_cancel); int captured_frames = 0; guint64 timeout=1000000; #define _CAN_STOP (arv_option_max_frames > 0 && captured_frames >= arv_option_max_frames) arv_camera_start_acquisition(camera); do { g_usleep (100000); do { buffer = arv_stream_timeout_pop_buffer (stream, timeout); if (buffer == NULL) break; ArvBufferStatus status = arv_buffer_get_status(buffer); fprintf(stderr, "Status is %d\n", status); if (status == ARV_BUFFER_STATUS_SUCCESS) { if (timeout > 100000) timeout -= 1000; errors = 0; if (save_buffer_fn != NULL) { struct timespec timestamp; clock_gettime(CLOCK_REALTIME, ×tamp); char filename[BUFSIZ]; if (strcmp(arv_option_save_prefix,"") != 0) { sprintf(filename, "%s/%s%d.%s", arv_option_save_dir,arv_option_save_prefix, captured_frames, arv_option_save_type); } else { sprintf(filename, "%s/%d.%03ld.%s", arv_option_save_dir, (int)timestamp.tv_sec, (long)(timestamp.tv_nsec/1.0e6), arv_option_save_type); } if ((*save_buffer_fn)(buffer, filename) == false) { g_print("Couldn't save frame %d to %s\n", captured_frames, filename); set_cancel(SIGQUIT); } g_print("Saved frame %d to %s\n", captured_frames, filename); char latest[] = "latest.png"; sprintf(latest, "latest.%s", arv_option_save_type); unlink(latest); symlink(filename, latest); } captured_frames++; g_usleep(arv_option_sample_period); } else { if (timeout < 10000000) timeout+=1000; fprintf(stderr, "%d errors out of %d allowed\n", errors, arv_option_max_errors_before_abort); arv_camera_stop_acquisition(camera); if (++errors > arv_option_max_errors_before_abort && arv_option_max_errors_before_abort >= 0) { set_cancel(SIGQUIT); } else { arv_camera_start_acquisition(camera); } } arv_stream_push_buffer (stream, buffer); } while (!cancel && buffer != NULL && !_CAN_STOP); } while (!cancel && !_CAN_STOP); arv_camera_stop_acquisition(camera); guint64 n_processed_buffers; guint64 n_failures; guint64 n_underruns; arv_stream_get_statistics (stream, &n_processed_buffers, &n_failures, &n_underruns); g_print ("Processed buffers = %Lu\n", (unsigned long long) n_processed_buffers); g_print ("Failures = %Lu\n", (unsigned long long) n_failures); g_print ("Underruns = %Lu\n", (unsigned long long) n_underruns); g_object_unref (stream); g_object_unref (camera); return (errors > 0); }
int main(int argc, char** argv) { char *pszGuid = NULL; char szGuid[512]; int nInterfaces = 0; int nDevices = 0; int i = 0; const char *pkeyAcquisitionFrameRate[2] = {"AcquisitionFrameRate", "AcquisitionFrameRateAbs"}; ArvGcNode *pGcNode; GError *error=NULL; global.bCancel = FALSE; global.config = global.config.__getDefault__(); global.idSoftwareTriggerTimer = 0; ros::init(argc, argv, "camera"); global.phNode = new ros::NodeHandle(); // Service callback for firing nuc's. // Needed since we cannot open another connection to cameras while streaming. ros::NodeHandle nh; ros::ServiceServer NUCservice = nh.advertiseService("FireNUC", NUCService_callback); //g_type_init (); // Print out some useful info. ROS_INFO ("Attached cameras:"); arv_update_device_list(); nInterfaces = arv_get_n_interfaces(); ROS_INFO ("# Interfaces: %d", nInterfaces); nDevices = arv_get_n_devices(); ROS_INFO ("# Devices: %d", nDevices); for (i=0; i<nDevices; i++) ROS_INFO ("Device%d: %s", i, arv_get_device_id(i)); if (nDevices>0) { // Get the camera guid from either the command-line or as a parameter. if (argc==2) { strcpy(szGuid, argv[1]); pszGuid = szGuid; } else { if (global.phNode->hasParam(ros::this_node::getName()+"/guid")) { std::string stGuid; global.phNode->getParam(ros::this_node::getName()+"/guid", stGuid); strcpy (szGuid, stGuid.c_str()); pszGuid = szGuid; } else pszGuid = NULL; } // Open the camera, and set it up. ROS_INFO("Opening: %s", pszGuid ? pszGuid : "(any)"); while (TRUE) { global.pCamera = arv_camera_new(pszGuid); if (global.pCamera) break; else { ROS_WARN ("Could not open camera %s. Retrying...", pszGuid); ros::Duration(1.0).sleep(); ros::spinOnce(); } } global.pDevice = arv_camera_get_device(global.pCamera); ROS_INFO("Opened: %s-%s", arv_device_get_string_feature_value (global.pDevice, "DeviceVendorName"), arv_device_get_string_feature_value (global.pDevice, "DeviceID")); // See if some basic camera features exist. pGcNode = arv_device_get_feature (global.pDevice, "AcquisitionMode"); global.isImplementedAcquisitionMode = ARV_GC_FEATURE_NODE (pGcNode) ? arv_gc_feature_node_is_implemented (ARV_GC_FEATURE_NODE (pGcNode), &error) : FALSE; pGcNode = arv_device_get_feature (global.pDevice, "GainRaw"); global.isImplementedGain = ARV_GC_FEATURE_NODE (pGcNode) ? arv_gc_feature_node_is_implemented (ARV_GC_FEATURE_NODE (pGcNode), &error) : FALSE; pGcNode = arv_device_get_feature (global.pDevice, "Gain"); global.isImplementedGain |= ARV_GC_FEATURE_NODE (pGcNode) ? arv_gc_feature_node_is_implemented (ARV_GC_FEATURE_NODE (pGcNode), &error) : FALSE; pGcNode = arv_device_get_feature (global.pDevice, "ExposureTimeAbs"); global.isImplementedExposureTimeAbs = ARV_GC_FEATURE_NODE (pGcNode) ? arv_gc_feature_node_is_implemented (ARV_GC_FEATURE_NODE (pGcNode), &error) : FALSE; pGcNode = arv_device_get_feature (global.pDevice, "ExposureAuto"); global.isImplementedExposureAuto = ARV_GC_FEATURE_NODE (pGcNode) ? arv_gc_feature_node_is_implemented (ARV_GC_FEATURE_NODE (pGcNode), &error) : FALSE; pGcNode = arv_device_get_feature (global.pDevice, "GainAuto"); global.isImplementedGainAuto = ARV_GC_FEATURE_NODE (pGcNode) ? arv_gc_feature_node_is_implemented (ARV_GC_FEATURE_NODE (pGcNode), &error) : FALSE; pGcNode = arv_device_get_feature (global.pDevice, "TriggerSelector"); global.isImplementedTriggerSelector = ARV_GC_FEATURE_NODE (pGcNode) ? arv_gc_feature_node_is_implemented (ARV_GC_FEATURE_NODE (pGcNode), &error) : FALSE; pGcNode = arv_device_get_feature (global.pDevice, "TriggerSource"); global.isImplementedTriggerSource = ARV_GC_FEATURE_NODE (pGcNode) ? arv_gc_feature_node_is_implemented (ARV_GC_FEATURE_NODE (pGcNode), &error) : FALSE; pGcNode = arv_device_get_feature (global.pDevice, "TriggerMode"); global.isImplementedTriggerMode = ARV_GC_FEATURE_NODE (pGcNode) ? arv_gc_feature_node_is_implemented (ARV_GC_FEATURE_NODE (pGcNode), &error) : FALSE; pGcNode = arv_device_get_feature (global.pDevice, "FocusPos"); global.isImplementedFocusPos = ARV_GC_FEATURE_NODE (pGcNode) ? arv_gc_feature_node_is_implemented (ARV_GC_FEATURE_NODE (pGcNode), &error) : FALSE; pGcNode = arv_device_get_feature (global.pDevice, "GevSCPSPacketSize"); global.isImplementedMtu = ARV_GC_FEATURE_NODE (pGcNode) ? arv_gc_feature_node_is_implemented (ARV_GC_FEATURE_NODE (pGcNode), &error) : FALSE; pGcNode = arv_device_get_feature (global.pDevice, "AcquisitionFrameRateEnable"); global.isImplementedAcquisitionFrameRateEnable = ARV_GC_FEATURE_NODE (pGcNode) ? arv_gc_feature_node_is_implemented (ARV_GC_FEATURE_NODE (pGcNode), &error) : FALSE; // Find the key name for framerate. global.keyAcquisitionFrameRate = NULL; for (i=0; i<2; i++) { pGcNode = arv_device_get_feature (global.pDevice, pkeyAcquisitionFrameRate[i]); global.isImplementedAcquisitionFrameRate = pGcNode ? arv_gc_feature_node_is_implemented (ARV_GC_FEATURE_NODE (pGcNode), &error) : FALSE; if (global.isImplementedAcquisitionFrameRate) { global.keyAcquisitionFrameRate = pkeyAcquisitionFrameRate[i]; break; } } // Get parameter bounds. arv_camera_get_exposure_time_bounds (global.pCamera, &global.configMin.ExposureTimeAbs, &global.configMax.ExposureTimeAbs); arv_camera_get_gain_bounds (global.pCamera, &global.configMin.Gain, &global.configMax.Gain); arv_camera_get_sensor_size (global.pCamera, &global.widthSensor, &global.heightSensor); arv_camera_get_width_bounds (global.pCamera, &global.widthRoiMin, &global.widthRoiMax); arv_camera_get_height_bounds (global.pCamera, &global.heightRoiMin, &global.heightRoiMax); if (global.isImplementedFocusPos) { gint64 focusMin64, focusMax64; arv_device_get_integer_feature_bounds (global.pDevice, "FocusPos", &focusMin64, &focusMax64); global.configMin.FocusPos = focusMin64; global.configMax.FocusPos = focusMax64; } else { global.configMin.FocusPos = 0; global.configMax.FocusPos = 0; } global.configMin.AcquisitionFrameRate = 0.0; global.configMax.AcquisitionFrameRate = 1000.0; // Initial camera settings. if (global.isImplementedExposureTimeAbs) arv_device_set_float_feature_value(global.pDevice, "ExposureTimeAbs", global.config.ExposureTimeAbs); if (global.isImplementedGain) arv_camera_set_gain(global.pCamera, global.config.Gain); //arv_device_set_integer_feature_value(global.pDevice, "GainRaw", global.config.GainRaw); if (global.isImplementedAcquisitionFrameRateEnable) arv_device_set_integer_feature_value(global.pDevice, "AcquisitionFrameRateEnable", 1); if (global.isImplementedAcquisitionFrameRate) arv_device_set_float_feature_value(global.pDevice, global.keyAcquisitionFrameRate, global.config.AcquisitionFrameRate); // Set up the triggering. if (global.isImplementedTriggerMode) { if (global.isImplementedTriggerSelector && global.isImplementedTriggerMode) { arv_device_set_string_feature_value(global.pDevice, "TriggerSelector", "AcquisitionStart"); arv_device_set_string_feature_value(global.pDevice, "TriggerMode", "Off"); arv_device_set_string_feature_value(global.pDevice, "TriggerSelector", "FrameStart"); arv_device_set_string_feature_value(global.pDevice, "TriggerMode", "Off"); } } WriteCameraFeaturesFromRosparam (); #ifdef TUNING ros::Publisher pubInt64 = global.phNode->advertise<std_msgs::Int64>(ros::this_node::getName()+"/dt", 100); global.ppubInt64 = &pubInt64; #endif // Grab the calibration file url from the param server if exists std::string calibrationURL = ""; // Default looks in .ros/camera_info if (!(ros::param::get(std::string("calibrationURL").append(arv_device_get_string_feature_value (global.pDevice, "DeviceID")), calibrationURL))) { ROS_ERROR("ERROR: Could not read calibrationURL from parameter server"); } // Start the camerainfo manager. global.pCameraInfoManager = new camera_info_manager::CameraInfoManager(ros::NodeHandle(ros::this_node::getName()), arv_device_get_string_feature_value (global.pDevice, "DeviceID"), calibrationURL); // Start the dynamic_reconfigure server. dynamic_reconfigure::Server<Config> reconfigureServer; dynamic_reconfigure::Server<Config>::CallbackType reconfigureCallback; reconfigureCallback = boost::bind(&RosReconfigure_callback, _1, _2); reconfigureServer.setCallback(reconfigureCallback); ros::Duration(2.0).sleep(); // Get parameter current values. global.xRoi=0; global.yRoi=0; global.widthRoi=0; global.heightRoi=0; arv_camera_get_region (global.pCamera, &global.xRoi, &global.yRoi, &global.widthRoi, &global.heightRoi); global.config.ExposureTimeAbs = global.isImplementedExposureTimeAbs ? arv_device_get_float_feature_value (global.pDevice, "ExposureTimeAbs") : 0; global.config.Gain = global.isImplementedGain ? arv_camera_get_gain (global.pCamera) : 0.0; global.pszPixelformat = g_string_ascii_down(g_string_new(arv_device_get_string_feature_value(global.pDevice, "PixelFormat")))->str; global.nBytesPixel = ARV_PIXEL_FORMAT_BYTE_PER_PIXEL(arv_device_get_integer_feature_value(global.pDevice, "PixelFormat")); global.config.FocusPos = global.isImplementedFocusPos ? arv_device_get_integer_feature_value (global.pDevice, "FocusPos") : 0; // Print information. ROS_INFO (" Using Camera Configuration:"); ROS_INFO (" ---------------------------"); ROS_INFO (" Vendor name = %s", arv_device_get_string_feature_value (global.pDevice, "DeviceVendorName")); ROS_INFO (" Model name = %s", arv_device_get_string_feature_value (global.pDevice, "DeviceModelName")); ROS_INFO (" Device id = %s", arv_device_get_string_feature_value (global.pDevice, "DeviceID")); ROS_INFO (" Sensor width = %d", global.widthSensor); ROS_INFO (" Sensor height = %d", global.heightSensor); ROS_INFO (" ROI x,y,w,h = %d, %d, %d, %d", global.xRoi, global.yRoi, global.widthRoi, global.heightRoi); ROS_INFO (" Pixel format = %s", global.pszPixelformat); ROS_INFO (" BytesPerPixel = %d", global.nBytesPixel); ROS_INFO (" Acquisition Mode = %s", global.isImplementedAcquisitionMode ? arv_device_get_string_feature_value (global.pDevice, "AcquisitionMode") : "(not implemented in camera)"); ROS_INFO (" Trigger Mode = %s", global.isImplementedTriggerMode ? arv_device_get_string_feature_value (global.pDevice, "TriggerMode") : "(not implemented in camera)"); ROS_INFO (" Trigger Source = %s", global.isImplementedTriggerSource ? arv_device_get_string_feature_value(global.pDevice, "TriggerSource") : "(not implemented in camera)"); ROS_INFO (" Can set FrameRate: %s", global.isImplementedAcquisitionFrameRate ? "True" : "False"); if (global.isImplementedAcquisitionFrameRate) { global.config.AcquisitionFrameRate = arv_device_get_float_feature_value (global.pDevice, global.keyAcquisitionFrameRate); ROS_INFO (" AcquisitionFrameRate = %g hz", global.config.AcquisitionFrameRate); } ROS_INFO (" Can set Exposure: %s", global.isImplementedExposureTimeAbs ? "True" : "False"); if (global.isImplementedExposureTimeAbs) { ROS_INFO (" Can set ExposureAuto: %s", global.isImplementedExposureAuto ? "True" : "False"); ROS_INFO (" Exposure = %g us in range [%g,%g]", global.config.ExposureTimeAbs, global.configMin.ExposureTimeAbs, global.configMax.ExposureTimeAbs); } ROS_INFO (" Can set Gain: %s", global.isImplementedGain ? "True" : "False"); if (global.isImplementedGain) { ROS_INFO (" Can set GainAuto: %s", global.isImplementedGainAuto ? "True" : "False"); ROS_INFO (" Gain = %f %% in range [%f,%f]", global.config.Gain, global.configMin.Gain, global.configMax.Gain); } ROS_INFO (" Can set FocusPos: %s", global.isImplementedFocusPos ? "True" : "False"); if (global.isImplementedMtu) ROS_INFO (" Network mtu = %lu", arv_device_get_integer_feature_value(global.pDevice, "GevSCPSPacketSize")); ROS_INFO (" ---------------------------"); // // Print the tree of camera features, with their values. // ROS_INFO (" ----------------------------------------------------------------------------------"); // NODEEX nodeex; // ArvGc *pGenicam=0; // pGenicam = arv_device_get_genicam(global.pDevice); // // nodeex.szName = "Root"; // nodeex.pNode = (ArvDomNode *)arv_gc_get_node(pGenicam, nodeex.szName); // nodeex.pNodeSibling = NULL; // PrintDOMTree(pGenicam, nodeex, 0); // ROS_INFO (" ----------------------------------------------------------------------------------"); ArvGvStream *pStream = NULL; while (TRUE) { pStream = CreateStream(); if (pStream) break; else { ROS_WARN("Could not create image stream for %s. Retrying...", pszGuid); ros::Duration(1.0).sleep(); ros::spinOnce(); } } ApplicationData applicationdata; applicationdata.nBuffers=0; applicationdata.main_loop = 0; // Set up image_raw. image_transport::ImageTransport *pTransport = new image_transport::ImageTransport(*global.phNode); global.publisher = pTransport->advertiseCamera(ros::this_node::getName()+"/image_raw", 1); // Connect signals with callbacks. g_signal_connect (pStream, "new-buffer", G_CALLBACK (NewBuffer_callback), &applicationdata); g_signal_connect (global.pDevice, "control-lost", G_CALLBACK (ControlLost_callback), NULL); g_timeout_add_seconds (1, PeriodicTask_callback, &applicationdata); arv_stream_set_emit_signals ((ArvStream *)pStream, TRUE); void (*pSigintHandlerOld)(int); pSigintHandlerOld = signal (SIGINT, set_cancel); arv_device_execute_command (global.pDevice, "AcquisitionStart"); applicationdata.main_loop = g_main_loop_new (NULL, FALSE); g_main_loop_run (applicationdata.main_loop); if (global.idSoftwareTriggerTimer) { g_source_remove(global.idSoftwareTriggerTimer); global.idSoftwareTriggerTimer = 0; } signal (SIGINT, pSigintHandlerOld); g_main_loop_unref (applicationdata.main_loop); guint64 n_completed_buffers; guint64 n_failures; guint64 n_underruns; guint64 n_resent; guint64 n_missing; arv_stream_get_statistics ((ArvStream *)pStream, &n_completed_buffers, &n_failures, &n_underruns); ROS_INFO ("Completed buffers = %Lu", (unsigned long long) n_completed_buffers); ROS_INFO ("Failures = %Lu", (unsigned long long) n_failures); ROS_INFO ("Underruns = %Lu", (unsigned long long) n_underruns); arv_gv_stream_get_statistics (pStream, &n_resent, &n_missing); ROS_INFO ("Resent buffers = %Lu", (unsigned long long) n_resent); ROS_INFO ("Missing = %Lu", (unsigned long long) n_missing); arv_device_execute_command (global.pDevice, "AcquisitionStop"); g_object_unref (pStream); } else ROS_ERROR ("No cameras detected."); delete global.phNode; return 0; } // main()