static void caerInputEDVSExit(caerModuleData moduleData) { // Remove listener, which can reference invalid memory in userData. sshsNodeRemoveAttributeListener(moduleData->moduleNode, moduleData, &logLevelListener); sshsNode biasNode = sshsGetRelativeNode(moduleData->moduleNode, "bias/"); sshsNodeRemoveAttributeListener(biasNode, moduleData, &biasConfigListener); sshsNode dvsNode = sshsGetRelativeNode(moduleData->moduleNode, "dvs/"); sshsNodeRemoveAttributeListener(dvsNode, moduleData, &dvsConfigListener); sshsNode serialNode = sshsGetRelativeNode(moduleData->moduleNode, "serial/"); sshsNodeRemoveAttributeListener(serialNode, moduleData, &serialConfigListener); sshsNode sysNode = sshsGetRelativeNode(moduleData->moduleNode, "system/"); sshsNodeRemoveAttributeListener(sysNode, moduleData, &systemConfigListener); caerDeviceDataStop(moduleData->moduleState); caerDeviceClose((caerDeviceHandle *) &moduleData->moduleState); // Clear sourceInfo node. sshsNode sourceInfoNode = sshsGetRelativeNode(moduleData->moduleNode, "sourceInfo/"); sshsNodeRemoveAllAttributes(sourceInfoNode); if (sshsNodeGetBool(moduleData->moduleNode, "autoRestart")) { // Prime input module again so that it will try to restart if new devices detected. sshsNodePutBool(moduleData->moduleNode, "running", true); } }
static void caerInputDVS128Exit(caerModuleData moduleData) { caerDeviceDataStop(moduleData->moduleState); caerDeviceClose((caerDeviceHandle *) &moduleData->moduleState); if (sshsNodeGetBool(moduleData->moduleNode, "Auto-Restart")) { // Prime input module again so that it will try to restart if new devices detected. sshsNodePutBool(moduleData->moduleNode, "shutdown", false); } }
int main(void) { // Install signal handler for global shutdown. #if defined(_WIN32) if (signal(SIGTERM, &globalShutdownSignalHandler) == SIG_ERR) { caerLog(CAER_LOG_CRITICAL, "ShutdownAction", "Failed to set signal handler for SIGTERM. Error: %d.", errno); return (EXIT_FAILURE); } if (signal(SIGINT, &globalShutdownSignalHandler) == SIG_ERR) { caerLog(CAER_LOG_CRITICAL, "ShutdownAction", "Failed to set signal handler for SIGINT. Error: %d.", errno); return (EXIT_FAILURE); } #else struct sigaction shutdownAction; shutdownAction.sa_handler = &globalShutdownSignalHandler; shutdownAction.sa_flags = 0; sigemptyset(&shutdownAction.sa_mask); sigaddset(&shutdownAction.sa_mask, SIGTERM); sigaddset(&shutdownAction.sa_mask, SIGINT); if (sigaction(SIGTERM, &shutdownAction, NULL) == -1) { caerLog(CAER_LOG_CRITICAL, "ShutdownAction", "Failed to set signal handler for SIGTERM. Error: %d.", errno); return (EXIT_FAILURE); } if (sigaction(SIGINT, &shutdownAction, NULL) == -1) { caerLog(CAER_LOG_CRITICAL, "ShutdownAction", "Failed to set signal handler for SIGINT. Error: %d.", errno); return (EXIT_FAILURE); } #endif // Open a DVS128, give it a device ID of 1, and don't care about USB bus or SN restrictions. caerDeviceHandle dvs128_handle = caerDeviceOpen(1, CAER_DEVICE_DVS128, 0, 0, NULL); if (dvs128_handle == NULL) { return (EXIT_FAILURE); } // Let's take a look at the information we have on the device. struct caer_dvs128_info dvs128_info = caerDVS128InfoGet(dvs128_handle); printf("%s --- ID: %d, Master: %d, DVS X: %d, DVS Y: %d, Logic: %d.\n", dvs128_info.deviceString, dvs128_info.deviceID, dvs128_info.deviceIsMaster, dvs128_info.dvsSizeX, dvs128_info.dvsSizeY, dvs128_info.logicVersion); // Send the default configuration before using the device. // No configuration is sent automatically! caerDeviceSendDefaultConfig(dvs128_handle); // Tweak some biases, to increase bandwidth in this case. caerDeviceConfigSet(dvs128_handle, DVS128_CONFIG_BIAS, DVS128_CONFIG_BIAS_PR, 695); caerDeviceConfigSet(dvs128_handle, DVS128_CONFIG_BIAS, DVS128_CONFIG_BIAS_FOLL, 867); // Let's verify they really changed! uint32_t prBias, follBias; caerDeviceConfigGet(dvs128_handle, DVS128_CONFIG_BIAS, DVS128_CONFIG_BIAS_PR, &prBias); caerDeviceConfigGet(dvs128_handle, DVS128_CONFIG_BIAS, DVS128_CONFIG_BIAS_FOLL, &follBias); printf("New bias values --- PR: %d, FOLL: %d.\n", prBias, follBias); // Now let's get start getting some data from the device. We just loop in blocking mode, // no notification needed regarding new events. The shutdown notification, for example if // the device is disconnected, should be listened to. caerDeviceDataStart(dvs128_handle, NULL, NULL, NULL, &usbShutdownHandler, NULL); // Let's turn on blocking data-get mode to avoid wasting resources. caerDeviceConfigSet(dvs128_handle, CAER_HOST_CONFIG_DATAEXCHANGE, CAER_HOST_CONFIG_DATAEXCHANGE_BLOCKING, true); while (!atomic_load_explicit(&globalShutdown, memory_order_relaxed)) { caerEventPacketContainer packetContainer = caerDeviceDataGet(dvs128_handle); if (packetContainer == NULL) { continue; // Skip if nothing there. } int32_t packetNum = caerEventPacketContainerGetEventPacketsNumber(packetContainer); printf("\nGot event container with %d packets (allocated).\n", packetNum); for (int32_t i = 0; i < packetNum; i++) { caerEventPacketHeader packetHeader = caerEventPacketContainerGetEventPacket(packetContainer, i); if (packetHeader == NULL) { printf("Packet %d is empty (not present).\n", i); continue; // Skip if nothing there. } printf("Packet %d of type %d -> size is %d.\n", i, caerEventPacketHeaderGetEventType(packetHeader), caerEventPacketHeaderGetEventNumber(packetHeader)); // Packet 0 is always the special events packet for DVS128, while packet is the polarity events packet. if (i == POLARITY_EVENT) { caerPolarityEventPacket polarity = (caerPolarityEventPacket) packetHeader; // Get full timestamp and addresses of first event. caerPolarityEvent firstEvent = caerPolarityEventPacketGetEvent(polarity, 0); int32_t ts = caerPolarityEventGetTimestamp(firstEvent); uint16_t x = caerPolarityEventGetX(firstEvent); uint16_t y = caerPolarityEventGetY(firstEvent); bool pol = caerPolarityEventGetPolarity(firstEvent); printf("First polarity event - ts: %d, x: %d, y: %d, pol: %d.\n", ts, x, y, pol); } } caerEventPacketContainerFree(packetContainer); } caerDeviceDataStop(dvs128_handle); caerDeviceClose(&dvs128_handle); printf("Shutdown successful.\n"); return (EXIT_SUCCESS); }
int main(void) { // Install signal handler for global shutdown. #if defined(_WIN32) if (signal(SIGTERM, &globalShutdownSignalHandler) == SIG_ERR) { caerLog(CAER_LOG_CRITICAL, "ShutdownAction", "Failed to set signal handler for SIGTERM. Error: %d.", errno); return (EXIT_FAILURE); } if (signal(SIGINT, &globalShutdownSignalHandler) == SIG_ERR) { caerLog(CAER_LOG_CRITICAL, "ShutdownAction", "Failed to set signal handler for SIGINT. Error: %d.", errno); return (EXIT_FAILURE); } #else struct sigaction shutdownAction; shutdownAction.sa_handler = &globalShutdownSignalHandler; shutdownAction.sa_flags = 0; sigemptyset(&shutdownAction.sa_mask); sigaddset(&shutdownAction.sa_mask, SIGTERM); sigaddset(&shutdownAction.sa_mask, SIGINT); if (sigaction(SIGTERM, &shutdownAction, NULL) == -1) { caerLog(CAER_LOG_CRITICAL, "ShutdownAction", "Failed to set signal handler for SIGTERM. Error: %d.", errno); return (EXIT_FAILURE); } if (sigaction(SIGINT, &shutdownAction, NULL) == -1) { caerLog(CAER_LOG_CRITICAL, "ShutdownAction", "Failed to set signal handler for SIGINT. Error: %d.", errno); return (EXIT_FAILURE); } #endif // Open a DYNAPSE, give it a device ID of 1, and don't care about USB bus or SN restrictions. caerDeviceHandle dynapse_handle = caerDeviceOpen(1, CAER_DEVICE_DYNAPSE, 0, 0, NULL); if (dynapse_handle == NULL) { return (EXIT_FAILURE); } // Let's take a look at the information we have on the device. struct caer_dynapse_info dynapse_info = caerDynapseInfoGet(dynapse_handle); printf("%s --- ID: %d, Master: %d, Logic: %d.\n", dynapse_info.deviceString, dynapse_info.deviceID, dynapse_info.deviceIsMaster, dynapse_info.logicVersion); // Send the default configuration before using the device. // No configuration is sent automatically! caerDeviceSendDefaultConfig(dynapse_handle); // Now let's get start getting some data from the device. We just loop in blocking mode, // no notification needed regarding new events. The shutdown notification, for example if // the device is disconnected, should be listened to. // This automatically turns on the AER and CHIP state machines. caerDeviceDataStart(dynapse_handle, NULL, NULL, NULL, &usbShutdownHandler, NULL); // Let's turn on blocking data-get mode to avoid wasting resources. caerDeviceConfigSet(dynapse_handle, CAER_HOST_CONFIG_DATAEXCHANGE, CAER_HOST_CONFIG_DATAEXCHANGE_BLOCKING, true); while (!atomic_load_explicit(&globalShutdown, memory_order_relaxed)) { caerEventPacketContainer packetContainer = caerDeviceDataGet(dynapse_handle); if (packetContainer == NULL) { continue; // Skip if nothing there. } int32_t packetNum = caerEventPacketContainerGetEventPacketsNumber(packetContainer); printf("\nGot event container with %d packets (allocated).\n", packetNum); for (int32_t i = 0; i < packetNum; i++) { caerEventPacketHeader packetHeader = caerEventPacketContainerGetEventPacket(packetContainer, i); if (packetHeader == NULL) { printf("Packet %d is empty (not present).\n", i); continue; // Skip if nothing there. } printf("Packet %d of type %d -> size is %d.\n", i, caerEventPacketHeaderGetEventType(packetHeader), caerEventPacketHeaderGetEventNumber(packetHeader)); // Spike Events if (i == SPIKE_EVENT) { caerSpikeEventPacket spike = (caerSpikeEventPacket) packetHeader; // Get full timestamp and addresses of first event. caerSpikeEventConst firstEvent = caerSpikeEventPacketGetEventConst(spike, 0); int32_t ts = caerSpikeEventGetTimestamp(firstEvent); uint16_t neuid = caerSpikeEventGetNeuronID(firstEvent); uint16_t coreid = caerSpikeEventGetSourceCoreID(firstEvent); printf("First spike event - ts: %d, neu: %d, core: %d\n", ts, neuid, coreid); } } caerEventPacketContainerFree(packetContainer); } caerDeviceDataStop(dynapse_handle); caerDeviceClose(&dynapse_handle); printf("Shutdown successful.\n"); return (EXIT_SUCCESS); }
static void caerInputDAVISExit(caerModuleData moduleData) { // Device related configuration has its own sub-node. struct caer_davis_info devInfo = caerDavisInfoGet(moduleData->moduleState); sshsNode deviceConfigNode = sshsGetRelativeNode(moduleData->moduleNode, chipIDToName(devInfo.chipID, true)); // Remove listener, which can reference invalid memory in userData. sshsNodeRemoveAttributeListener(moduleData->moduleNode, moduleData, &logLevelListener); sshsNode chipNode = sshsGetRelativeNode(deviceConfigNode, "chip/"); sshsNodeRemoveAttributeListener(chipNode, moduleData, &chipConfigListener); sshsNode muxNode = sshsGetRelativeNode(deviceConfigNode, "multiplexer/"); sshsNodeRemoveAttributeListener(muxNode, moduleData, &muxConfigListener); sshsNode dvsNode = sshsGetRelativeNode(deviceConfigNode, "dvs/"); sshsNodeRemoveAttributeListener(dvsNode, moduleData, &dvsConfigListener); sshsNode apsNode = sshsGetRelativeNode(deviceConfigNode, "aps/"); sshsNodeRemoveAttributeListener(apsNode, moduleData, &apsConfigListener); sshsNode imuNode = sshsGetRelativeNode(deviceConfigNode, "imu/"); sshsNodeRemoveAttributeListener(imuNode, moduleData, &imuConfigListener); sshsNode extNode = sshsGetRelativeNode(deviceConfigNode, "externalInput/"); sshsNodeRemoveAttributeListener(extNode, moduleData, &extInputConfigListener); sshsNode usbNode = sshsGetRelativeNode(deviceConfigNode, "usb/"); sshsNodeRemoveAttributeListener(usbNode, moduleData, &usbConfigListener); sshsNode sysNode = sshsGetRelativeNode(moduleData->moduleNode, "system/"); sshsNodeRemoveAttributeListener(sysNode, moduleData, &systemConfigListener); sshsNode biasNode = sshsGetRelativeNode(deviceConfigNode, "bias/"); size_t biasNodesLength = 0; sshsNode *biasNodes = sshsNodeGetChildren(biasNode, &biasNodesLength); if (biasNodes != NULL) { for (size_t i = 0; i < biasNodesLength; i++) { // Remove listener for this particular bias. sshsNodeRemoveAttributeListener(biasNodes[i], moduleData, &biasConfigListener); } free(biasNodes); } // Ensure Exposure value is coherent with libcaer. sshsAttributeUpdaterRemoveAllForNode(apsNode); sshsNodePutAttribute( apsNode, "Exposure", SSHS_INT, apsExposureUpdater(moduleData->moduleState, "Exposure", SSHS_INT)); // Remove statistics updaters. sshsNode statNode = sshsGetRelativeNode(deviceConfigNode, "statistics/"); sshsAttributeUpdaterRemoveAllForNode(statNode); caerDeviceDataStop(moduleData->moduleState); caerDeviceClose((caerDeviceHandle *) &moduleData->moduleState); // Clear sourceInfo node. sshsNode sourceInfoNode = sshsGetRelativeNode(moduleData->moduleNode, "sourceInfo/"); sshsNodeRemoveAllAttributes(sourceInfoNode); if (sshsNodeGetBool(moduleData->moduleNode, "autoRestart")) { // Prime input module again so that it will try to restart if new devices detected. sshsNodePutBool(moduleData->moduleNode, "running", true); } }
void DvsRosDriver::readout() { caerDeviceDataStart(dvs128_handle, NULL, NULL, NULL, NULL, NULL); caerDeviceConfigSet(dvs128_handle, CAER_HOST_CONFIG_DATAEXCHANGE, CAER_HOST_CONFIG_DATAEXCHANGE_BLOCKING, true); boost::posix_time::ptime next_send_time = boost::posix_time::microsec_clock::local_time(); dvs_msgs::EventArrayPtr event_array_msg(new dvs_msgs::EventArray()); event_array_msg->height = dvs128_info_.dvsSizeY; event_array_msg->width = dvs128_info_.dvsSizeX; while (running_) { try { caerEventPacketContainer packetContainer = caerDeviceDataGet(dvs128_handle); if (packetContainer == NULL) { continue; // Skip if nothing there. } int32_t packetNum = caerEventPacketContainerGetEventPacketsNumber(packetContainer); for (int32_t i = 0; i < packetNum; i++) { caerEventPacketHeader packetHeader = caerEventPacketContainerGetEventPacket(packetContainer, i); if (packetHeader == NULL) { continue; // Skip if nothing there. } // Packet 0 is always the special events packet for DVS128, while packet is the polarity events packet. if (i == POLARITY_EVENT) { caerPolarityEventPacket polarity = (caerPolarityEventPacket) packetHeader; const int numEvents = caerEventPacketHeaderGetEventNumber(packetHeader); for (int j = 0; j < numEvents; j++) { // Get full timestamp and addresses of first event. caerPolarityEvent event = caerPolarityEventPacketGetEvent(polarity, j); dvs_msgs::Event e; e.x = caerPolarityEventGetX(event); e.y = caerPolarityEventGetY(event); e.ts = reset_time_ + ros::Duration().fromNSec(caerPolarityEventGetTimestamp64(event, polarity) * 1000); e.polarity = caerPolarityEventGetPolarity(event); event_array_msg->events.push_back(e); } // throttle event messages if (boost::posix_time::microsec_clock::local_time() > next_send_time || current_config_.streaming_rate == 0) { event_array_pub_.publish(event_array_msg); event_array_msg->events.clear(); if (current_config_.streaming_rate > 0) { next_send_time += delta_; } } if (camera_info_manager_->isCalibrated()) { sensor_msgs::CameraInfoPtr camera_info_msg(new sensor_msgs::CameraInfo(camera_info_manager_->getCameraInfo())); camera_info_pub_.publish(camera_info_msg); } } } caerEventPacketContainerFree(packetContainer); ros::spinOnce(); } catch (boost::thread_interrupted&) { return; } } caerDeviceDataStop(dvs128_handle); }